Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update process.c #21

Open
wants to merge 7 commits into
base: humble
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
36 changes: 36 additions & 0 deletions .github/workflows/fork_checker.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
name: micro-ROS fork Update Checker
on:
workflow_dispatch:
inputs:
name:
description: "Manual trigger"
schedule:
- cron: '0 4 * * *'

jobs:
micro_ros_fork_update_check:
runs-on: ubuntu-latest
container: ubuntu:20.04
strategy:
fail-fast: false
matrix:
branches: [foxy, galactic, humble, master]
steps:
- name: Check
id: check
shell: bash
run: |
apt update; apt install -y git
REPO=$(echo ${{ github.repository }} | awk '{split($0,a,"/"); print a[2]}')
git clone -b ${{ matrix.branches }} https://github.com/micro-ros/$REPO
cd $REPO
git remote add ros2 https://github.com/ros2/$REPO
git fetch ros2
git fetch origin
echo "::set-output name=merge_required::true"
CMP=$(git rev-list --left-right --count ros2/${{ matrix.branches }}...origin/${{ matrix.branches }} | awk '{print $1}')
if [ $CMP = "0" ]; then echo "::set-output name=merge_required::false"; fi

- name: Alert
if: ${{ steps.check.outputs.merge_required == 'true' }}
run: exit 1
13 changes: 12 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@ cmake_minimum_required(VERSION 3.12)

project(rcutils)

option(RCUTILS_NO_THREAD_SUPPORT "Disable thread support." OFF)
option(RCUTILS_NO_FILESYSTEM "Disable filesystem usage." OFF)
option(RCUTILS_AVOID_DYNAMIC_ALLOCATION "Disable dynamic allocations." OFF)
option(RCUTILS_NO_64_ATOMIC "Enable alternative support for 64 bits atomic operations in platforms with no native support." OFF)
option(RCUTILS_MICROROS "Flag for building micro-ROS." ON)

# Default to C11
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 11)
Expand Down Expand Up @@ -30,7 +36,7 @@ if(UNIX AND NOT APPLE)
endif()
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
if(NOT RCUTILS_MICROROS AND (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang"))
# enables building a static library but later link it into a dynamic library
add_compile_options(-fPIC)
endif()
Expand Down Expand Up @@ -75,6 +81,7 @@ set(rcutils_sources
src/time.c
${time_impl_c}
src/uint8_array.c
$<$<BOOL:${RCUTILS_NO_64_ATOMIC}>:src/atomic_64bits.c>
)
set_source_files_properties(
${rcutils_sources}
Expand Down Expand Up @@ -129,6 +136,10 @@ target_compile_definitions(${PROJECT_NAME} PRIVATE "RCUTILS_BUILDING_DLL")
if(BUILD_TESTING AND NOT RCUTILS_DISABLE_FAULT_INJECTION)
target_compile_definitions(${PROJECT_NAME} PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
endif()
configure_file(
"${PROJECT_SOURCE_DIR}/include/rcutils/configuration_flags.h.in"
"${PROJECT_BINARY_DIR}/include/rcutils/configuration_flags.h"
)

target_link_libraries(${PROJECT_NAME} ${CMAKE_DL_LIBS})

Expand Down
15 changes: 15 additions & 0 deletions include/rcutils/allocator.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,21 @@ RCUTILS_WARN_UNUSED
rcutils_allocator_t
rcutils_get_zero_initialized_allocator(void);

/// Set rcutils default allocators.
/**
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | Yes
* Uses Atomics | No
* Lock-Free | Yes
*/
RCUTILS_PUBLIC
RCUTILS_WARN_UNUSED
bool
rcutils_set_default_allocator(rcutils_allocator_t * allocator);

/// Return a properly initialized rcutils_allocator_t with default values.
/**
* This defaults to:
Expand Down
18 changes: 18 additions & 0 deletions include/rcutils/configuration_flags.h.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@

#ifndef RCUTILS__CONFIGURATION_FLAGS_H_
#define RCUTILS__CONFIGURATION_FLAGS_H_

#ifdef __cplusplus
extern "C"
{
#endif

#cmakedefine RCUTILS_NO_FILESYSTEM
#cmakedefine RCUTILS_AVOID_DYNAMIC_ALLOCATION
#cmakedefine RCUTILS_NO_THREAD_SUPPORT

#ifdef __cplusplus
}
#endif

#endif // RCUTILS__CONFIGURATION_FLAGS_H_
32 changes: 28 additions & 4 deletions include/rcutils/error_handling.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,19 +39,21 @@ extern "C"
#include "rcutils/testing/fault_injection.h"
#include "rcutils/types/rcutils_ret.h"
#include "rcutils/visibility_control.h"
#include "rcutils/configuration_flags.h"

#ifdef __STDC_LIB_EXT1__
#if defined(__STDC_LIB_EXT1__) && !defined(RCUTILS_NO_FILESYSTEM)
/// Write the given msg out to stderr, limiting the buffer size in the `fwrite`.
/**
* This ensures that there is an upper bound to a buffer overrun if `msg` is
* non-null terminated.
*/
#define RCUTILS_SAFE_FWRITE_TO_STDERR(msg) \
do {fwrite(msg, sizeof(char), strnlen_s(msg, 4096), stderr);} while (0)
#else
/// Write the given msg out to stderr.
#elif !defined(RCUTILS_NO_FILESYSTEM)
#define RCUTILS_SAFE_FWRITE_TO_STDERR(msg) \
do {fwrite(msg, sizeof(char), strlen(msg), stderr);} while (0)
#else
#define RCUTILS_SAFE_FWRITE_TO_STDERR(msg)
#endif

/// Set the error message to stderr using a format string and format arguments.
Expand All @@ -63,6 +65,8 @@ extern "C"
* \param[in] format_string The string to be used as the format of the error message.
* \param[in] ... Arguments for the format string.
*/

#if !defined(RCUTILS_AVOID_DYNAMIC_ALLOCATION)
#define RCUTILS_SAFE_FWRITE_TO_STDERR_WITH_FORMAT_STRING(format_string, ...) \
do { \
char output_msg[RCUTILS_ERROR_MESSAGE_MAX_LENGTH]; \
Expand All @@ -73,7 +77,11 @@ extern "C"
RCUTILS_SAFE_FWRITE_TO_STDERR(output_msg); \
} \
} while (0)
#else
#define RCUTILS_SAFE_FWRITE_TO_STDERR_WITH_FORMAT_STRING(format_string, ...)
#endif

#if !defined(RCUTILS_AVOID_DYNAMIC_ALLOCATION)
/// The maximum length a formatted number is allowed to have.
#define RCUTILS_ERROR_STATE_LINE_NUMBER_STR_MAX_LENGTH 20 // "18446744073709551615"

Expand All @@ -100,6 +108,13 @@ extern "C"
RCUTILS_ERROR_STATE_LINE_NUMBER_STR_MAX_LENGTH - \
RCUTILS_ERROR_FORMATTING_CHARACTERS - \
1)
#else
#define RCUTILS_ERROR_STATE_LINE_NUMBER_STR_MAX_LENGTH 1
#define RCUTILS_ERROR_FORMATTING_CHARACTERS 1
#define RCUTILS_ERROR_MESSAGE_MAX_LENGTH 1
#define RCUTILS_ERROR_STATE_MESSAGE_MAX_LENGTH 1
#define RCUTILS_ERROR_STATE_FILE_MAX_LENGTH 1
#endif // RCUTILS_AVOID_DYNAMIC_ALLOCATION

/// Struct wrapping a fixed-size c string used for returning the formatted error string.
typedef struct rcutils_error_string_s
Expand All @@ -121,7 +136,7 @@ typedef struct rcutils_error_state_s
} rcutils_error_state_t;

// make sure our math is right...
#if __STDC_VERSION__ >= 201112L
#if __STDC_VERSION__ >= 201112L && !defined(RCUTILS_AVOID_DYNAMIC_ALLOCATION)
static_assert(
sizeof(rcutils_error_string_t) == (
RCUTILS_ERROR_STATE_MESSAGE_MAX_LENGTH +
Expand Down Expand Up @@ -233,8 +248,12 @@ rcutils_set_error_state(const char * error_string, const char * file, size_t lin
*
* \param[in] msg The error message to be set.
*/
#ifdef RCUTILS_AVOID_DYNAMIC_ALLOCATION
#define RCUTILS_SET_ERROR_MSG(msg)
#else
#define RCUTILS_SET_ERROR_MSG(msg) \
do {rcutils_set_error_state(msg, __FILE__, __LINE__);} while (0)
#endif // RCUTILS_AVOID_DYNAMIC_ALLOCATION

/// Set the error message using a format string and format arguments.
/**
Expand All @@ -245,6 +264,9 @@ rcutils_set_error_state(const char * error_string, const char * file, size_t lin
* \param[in] format_string The string to be used as the format of the error message.
* \param[in] ... Arguments for the format string.
*/
#ifdef RCUTILS_AVOID_DYNAMIC_ALLOCATION
#define RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(format_string, ...)
#else
#define RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(format_string, ...) \
do { \
char output_msg[RCUTILS_ERROR_MESSAGE_MAX_LENGTH]; \
Expand All @@ -255,6 +277,8 @@ rcutils_set_error_state(const char * error_string, const char * file, size_t lin
RCUTILS_SET_ERROR_MSG(output_msg); \
} \
} while (0)
#endif // RCUTILS_AVOID_DYNAMIC_ALLOCATION


/// Indicate that the function intends to set an error message and return an error value.
/**
Expand Down
2 changes: 1 addition & 1 deletion include/rcutils/logging.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ extern "C"
* \def RCUTILS_DEFAULT_LOGGER_DEFAULT_LEVEL
* \brief The default severity level of the default logger.
*/
#define RCUTILS_DEFAULT_LOGGER_DEFAULT_LEVEL RCUTILS_LOG_SEVERITY_INFO
#define RCUTILS_DEFAULT_LOGGER_DEFAULT_LEVEL RCUTILS_LOG_SEVERITY_UNSET

/// The flag if the logging system has been initialized.
RCUTILS_PUBLIC
Expand Down
6 changes: 5 additions & 1 deletion include/rcutils/macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,8 @@ extern "C"
{
#endif

#include "rcutils/configuration_flags.h"

#ifndef _WIN32
/// A macro to make the compiler warn when the return value of a function is not used.
#define RCUTILS_WARN_UNUSED __attribute__((warn_unused_result))
Expand All @@ -32,7 +34,9 @@ extern "C"

/// @cond Doxygen_Suppress
// This block either sets RCUTILS_THREAD_LOCAL or RCUTILS_THREAD_LOCAL_PTHREAD.
#if defined _WIN32 || defined __CYGWIN__
#if defined(RCUTILS_NO_THREAD_SUPPORT)
#define RCUTILS_THREAD_LOCAL
#elif defined _WIN32 || defined __CYGWIN__
// Windows or Cygwin
#define RCUTILS_THREAD_LOCAL __declspec(thread)
#elif defined __APPLE__
Expand Down
67 changes: 67 additions & 0 deletions include/rcutils/security_directory.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
// Copyright 2018 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCUTILS__SECURITY_DIRECTORY_H_
#define RCUTILS__SECURITY_DIRECTORY_H_

#ifdef __cplusplus
extern "C"
{
#endif

#include "rcutils/allocator.h"
#include "rcutils/visibility_control.h"

#ifndef ROS_SECURITY_NODE_DIRECTORY_VAR_NAME
#define ROS_SECURITY_NODE_DIRECTORY_VAR_NAME "ROS_SECURITY_NODE_DIRECTORY"
#endif

#ifndef ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME
#define ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "ROS_SECURITY_ROOT_DIRECTORY"
#endif

#ifndef ROS_SECURITY_LOOKUP_TYPE_VAR_NAME
#define ROS_SECURITY_LOOKUP_TYPE_VAR_NAME "ROS_SECURITY_LOOKUP_TYPE"
#endif

/// Return the secure root directory associated with a node given its validated name and namespace.
/**
* E.g. for a node named "c" in namespace "/a/b", the secure root path will be
* "a/b/c", where the delimiter "/" is native for target file system (e.g. "\\" for _WIN32).
* If no exact match is found for the node name, a best match would be used instead
* (by performing longest-prefix matching).
*
* However, this expansion can be overridden by setting the secure node directory environment
* variable, allowing users to explicitly specify the exact secure root directory to be utilized.
* Such an override is useful for where the FQN of a node is non-deterministic before runtime,
* or when testing and using additional tools that may not otherwise be easily provisioned.
*
* \param[in] node_name validated node name (a single token)
* \param[in] node_namespace validated, absolute namespace (starting with "/")
* \param[in] allocator the allocator to use for allocation
* \returns machine specific (absolute) node secure root path or NULL on failure
* returned pointer must be deallocated by the caller of this function
*/
RCUTILS_PUBLIC
char * rcutils_get_secure_root(
const char * node_name,
const char * node_namespace,
const rcutils_allocator_t * allocator
);

#ifdef __cplusplus
}
#endif

#endif // RCUTILS__SECURITY_DIRECTORY_H_
13 changes: 13 additions & 0 deletions include/rcutils/testing/fault_injection.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,8 @@ RCUTILS_WARN_UNUSED
int_least64_t
_rcutils_fault_injection_maybe_fail(void);

#ifdef RCUTILS_ENABLE_FAULT_INJECTION

/**
* \def RCUTILS_FAULT_INJECTION_MAYBE_RETURN_ERROR
* \brief This macro checks and decrements a static global variable atomic counter and returns
Expand Down Expand Up @@ -199,6 +201,17 @@ _rcutils_fault_injection_maybe_fail(void);
rcutils_fault_injection_set_count(no_fault_injection_count); \
} while (0)

#else

// Mocks for micro-ROS when fault injection not enabled

#define RCUTILS_FAULT_INJECTION_MAYBE_RETURN_ERROR(return_value_on_error)
#define RCUTILS_FAULT_INJECTION_MAYBE_FAIL(failure_code)
#define RCUTILS_FAULT_INJECTION_TEST(code)
#define RCUTILS_NO_FAULT_INJECTION(code)

#endif

#ifdef __cplusplus
}
#endif
Expand Down
2 changes: 1 addition & 1 deletion resource/logging_macros.h.em
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ extern "C"
* Use RCUTILS_LOG_MIN_SEVERITY_NONE to compile out all macros.
*/
#ifndef RCUTILS_LOG_MIN_SEVERITY
#define RCUTILS_LOG_MIN_SEVERITY RCUTILS_LOG_MIN_SEVERITY_DEBUG
#define RCUTILS_LOG_MIN_SEVERITY RCUTILS_LOG_MIN_SEVERITY_NONE
#endif

// TODO(dhood): optimise severity check via notifyLoggerLevelsChanged concept or similar.
Expand Down
23 changes: 19 additions & 4 deletions src/allocator.c
Original file line number Diff line number Diff line change
Expand Up @@ -75,16 +75,31 @@ rcutils_get_zero_initialized_allocator(void)
return zero_allocator;
}

rcutils_allocator_t
rcutils_get_default_allocator()
{
static rcutils_allocator_t default_allocator = {
static rcutils_allocator_t default_allocator = {
.allocate = __default_allocate,
.deallocate = __default_deallocate,
.reallocate = __default_reallocate,
.zero_allocate = __default_zero_allocate,
.state = NULL,
};

bool
rcutils_set_default_allocator(rcutils_allocator_t * allocator){
if (rcutils_allocator_is_valid(allocator))
{
default_allocator.allocate = allocator->allocate;
default_allocator.deallocate = allocator->deallocate;
default_allocator.reallocate = allocator->reallocate;
default_allocator.zero_allocate = allocator->zero_allocate;
default_allocator.state = NULL;
return true;
}
return false;
}

rcutils_allocator_t
rcutils_get_default_allocator()
{
return default_allocator;
}

Expand Down
Loading