diff --git a/rcl/CMakeLists.txt b/rcl/CMakeLists.txt index 830e84ef2..4f0f5f138 100644 --- a/rcl/CMakeLists.txt +++ b/rcl/CMakeLists.txt @@ -30,14 +30,16 @@ set(${PROJECT_NAME}_sources src/rcl/arguments.c src/rcl/client.c src/rcl/common.c + src/rcl/context.c src/rcl/expand_topic_name.c src/rcl/graph.c src/rcl/guard_condition.c + src/rcl/init.c + src/rcl/init_options.c src/rcl/lexer.c src/rcl/lexer_lookahead.c src/rcl/node.c src/rcl/publisher.c - src/rcl/rcl.c src/rcl/remap.c src/rcl/rmw_implementation_identifier_check.c src/rcl/service.c diff --git a/rcl/include/rcl/arguments.h b/rcl/include/rcl/arguments.h index f6f41f433..5d790bcd2 100644 --- a/rcl/include/rcl/arguments.h +++ b/rcl/include/rcl/arguments.h @@ -278,30 +278,6 @@ rcl_ret_t rcl_arguments_fini( rcl_arguments_t * args); -/// Get a global instance of command line arguments. -/** - * \sa rcl_init(int, char **, rcl_allocator_t) - * \sa rcl_shutdown() - * This returns parsed command line arguments that were passed to `rcl_init()`. - * The value returned by this function is undefined before `rcl_init()` is called and after - * `rcl_shutdown()` is called. - * The return value must not be finalized. - * - *
- * Attribute | Adherence - * ------------------ | ------------- - * Allocates Memory | No - * Thread-Safe | Yes - * Uses Atomics | No - * Lock-Free | Yes - * - * \return a global instance of parsed command line arguments. - */ -RCL_PUBLIC -RCL_WARN_UNUSED -rcl_arguments_t * -rcl_get_global_arguments(); - #ifdef __cplusplus } #endif diff --git a/rcl/include/rcl/context.h b/rcl/include/rcl/context.h new file mode 100644 index 000000000..71bae0733 --- /dev/null +++ b/rcl/include/rcl/context.h @@ -0,0 +1,261 @@ +// 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 RCL__CONTEXT_H_ +#define RCL__CONTEXT_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rmw/init.h" + +#include "rcl/allocator.h" +#include "rcl/arguments.h" +#include "rcl/init_options.h" +#include "rcl/macros.h" +#include "rcl/types.h" +#include "rcl/visibility_control.h" + +typedef uint64_t rcl_context_instance_id_t; + +struct rcl_context_impl_t; + +/// Encapsulates the non-global state of an init/shutdown cycle. +/** + * The context is used in the creation of top level entities like nodes and + * guard conditions, as well as to shutdown a specific instance of init. + * + * Here is a diagram of a typical context's lifecycle: + * + * ``` + * +---------------+ + * | | + * +--> uninitialized +---> rcl_get_zero_initialized_context() + + * | | | | + * | +---------------+ | + * | | + * | +-----------------------------------------------+ + * | | + * | +--------v---------+ +-----------------------+ + * | | | | | + * | | zero-initialized +-> rcl_init() +-> initialized and valid +-> rcl_shutdown() + + * | | | | | | + * | +------------------+ +-----------------------+ | + * | | + * | +-----------------------------------------------------------------+ + * | | + * | +------------v------------+ + * | | | + * | | initialized but invalid +---> finalize all entities, then rcl_context_fini() + + * | | | | + * | +-------------------------+ | + * | | + * +---------------------------------------------------------------------------------+ + * ``` + * + * A declared but not defined `rcl_context_t` instance is considered to be + * "uninitialized", and passing an uninitialized context to any functions will + * result in undefined behavior. + * Some functions, like `rcl_init()` require the context instance to be + * zero initialized (all members set to "zero" state) before use. + * + * Zero initialization of an `rcl_context_t` should be done with + * `rcl_get_zero_initialized_context()`, which ensures the context is in a safe + * state for initialization with `rcl_init()`. + * + * Initialization of an `rcl_context_t` should be done with `rcl_init()`, after + * which the context is considered both initialized and valid. + * After initialization it can be used in the creation of other entities like + * nodes and guard conditions. + * + * At any time the context can be invalidated by calling `rcl_shutdown()` on + * the `rcl_context_t`, after which the context is still initialized but now + * invalid. + * + * Invalidation indicates to other entities that the context was shutdown, but + * is still accessible for use during cleanup of themselves. + * + * After being invalidated, and after all of the entities which used it have + * been finalized, the context should be finalized with `rcl_context_fini()`. + * + * Finalizing the context while entities which have copies of it have not yet + * been finalized is undefined behavior. + * Therefore, the context's lifetime (between calls to `rcl_init()` and + * `rcl_context_fini()`) should exceed the lifetime of all entities which use + * it directly (e.g. nodes and guard conditions) or indirectly (e.g. + * subscriptions and topics). + */ +typedef struct rcl_context_t +{ + /// Global arguments for all nodes which share this context. + /** Typically generated by the parsing of argc/argv in `rcl_init()`. */ + rcl_arguments_t global_arguments; + + /// Implementation specific pointer. + struct rcl_context_impl_t * impl; + + // The assumption that this is big enough for an atomic_uint_least64_t is + // ensured with a static_assert in the context.c file. + // In most cases it should just be a plain uint64_t. +#if !defined(RCL_CONTEXT_ATOMIC_INSTANCE_ID_STORAGE_SIZE) +#define RCL_CONTEXT_ATOMIC_INSTANCE_ID_STORAGE_SIZE sizeof(uint_least64_t) +#endif + /// Private storage for instance ID atomic. + /** + * Accessing the instance id should be done using the function + * `rcl_context_get_instance_id()` because the instance id's type is an + * atomic and needs to be accessed properly to ensure safety. + * + * The instance id should not be changed manually - doing so is undefined + * behavior. + * + * The instance id cannot be protected within the `impl` pointer's type + * because it needs to be accessible even when the context is zero + * initialized and therefore `impl` is `NULL`. + * Specifically, storing the instance id in the `impl` would introduce a + * race condition between accessing it and finalizing the context. + * Additionally, C11 atomics (i.e. "stdatomic.h") cannot be used directly + * here in the case that this header is included into a C++ program. + * See this paper for an effort to make this possible in the future: + * http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2018/p0943r1.html + */ + uint8_t instance_id_storage[RCL_CONTEXT_ATOMIC_INSTANCE_ID_STORAGE_SIZE]; +} rcl_context_t; + +/// Return a zero initialization context object. +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_context_t +rcl_get_zero_initialized_context(void); + +// See `rcl_init()` for initialization of the context. + +/// Finalize a context. +/** + * The context to be finalized must have been previously initialized with + * `rcl_init()`, and then later invalidated with `rcl_shutdown()`. + * If context is `NULL`, then `RCL_RET_INVALID_ARGUMENT` is returned. + * If context is zero-initialized, then `RCL_RET_INVALID_ARGUMENT` is returned. + * If context is initialized and valid (`rcl_shutdown()` was not called on it), + * then `RCL_RET_INVALID_ARGUMENT` is returned. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | No + * Uses Atomics | Yes + * Lock-Free | Yes [1] + * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` + * + * \return `RCL_RET_OK` if the shutdown was completed successfully, or + * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or + * \return `RCL_RET_ERROR` if an unspecified error occur. + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_context_fini(rcl_context_t * context); + +// See `rcl_shutdown()` for invalidation of the context. + +/// Return the init options used during initialization for this context. +/** + * This function can fail and return `NULL` if: + * - context is NULL + * - context is zero-initialized, e.g. context->impl is `NULL` + * + * If context is uninitialized then that is undefined behavior. + * + * If `NULL` is returned an error message will have been set. + * + * The options are for reference only, and therefore the returned pointer is + * const. + * Changing the values in the options is undefined behavior but will likely + * have no effect. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | No + * Thread-Safe | Yes + * Uses Atomics | Yes + * Lock-Free | Yes + * + * \param[in] context object from which the init options should be retrieved + * \return pointer to the the init options, or + * \return `NULL` if there was an error + */ +RCL_PUBLIC +RCL_WARN_UNUSED +const rcl_init_options_t * +rcl_context_get_init_options(rcl_context_t * context); + +/// Returns an unsigned integer that is unique to the given context, or `0` if invalid. +/** + * The given context must be non-`NULL`, but does not need to be initialized or valid. + * If context is `NULL`, then `0` will be returned. + * If context is uninitialized, then it is undefined behavior. + * + * The instance ID may be `0` if the context is zero-initialized or if the + * context has been invalidated by `rcl_shutdown()`. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | No + * Thread-Safe | Yes + * Uses Atomics | Yes + * Lock-Free | Yes [1] + * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` + * + * \param[in] context object from which the instance id should be retrieved + * \return a unique id specific to this context instance, or + * \return `0` if invalid, or + * \return `0` if context is `NULL` + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_context_instance_id_t +rcl_context_get_instance_id(rcl_context_t * context); + +/// Return `true` if the given context is currently valid, otherwise `false`. +/** + * If context is `NULL`, then `false` is returned. + * If context is zero-initialized, then `false` is returned. + * If context is uninitialized, then it is undefined behavior. + * + * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | No + * Thread-Safe | Yes + * Uses Atomics | Yes + * Lock-Free | Yes [1] + * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` + * + * \param[in] context object which should be checked for validity + * \return `true` if valid, otherwise `false` + */ +RCL_PUBLIC +RCL_WARN_UNUSED +bool +rcl_context_is_valid(rcl_context_t * context); + +#ifdef __cplusplus +} +#endif + +#endif // RCL__CONTEXT_H_ diff --git a/rcl/include/rcl/guard_condition.h b/rcl/include/rcl/guard_condition.h index 8c4781ce4..2ecf98006 100644 --- a/rcl/include/rcl/guard_condition.h +++ b/rcl/include/rcl/guard_condition.h @@ -21,6 +21,7 @@ extern "C" #endif #include "rcl/allocator.h" +#include "rcl/context.h" #include "rcl/macros.h" #include "rcl/types.h" #include "rcl/visibility_control.h" @@ -31,6 +32,9 @@ struct rcl_guard_condition_impl_t; /// Handle for a rcl guard condition. typedef struct rcl_guard_condition_t { + /// Context associated with this guard condition. + rcl_context_t * context; + struct rcl_guard_condition_impl_t * impl; } rcl_guard_condition_t; @@ -61,7 +65,7 @@ rcl_get_zero_initialized_guard_condition(void); * rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); * // ... customize guard condition options * rcl_ret_t ret = rcl_guard_condition_init( - * &guard_condition, rcl_guard_condition_get_default_options()); + * &guard_condition, context, rcl_guard_condition_get_default_options()); * // ... error handling, and on shutdown do deinitialization: * ret = rcl_guard_condition_fini(&guard_condition); * // ... error handling for rcl_guard_condition_fini() @@ -76,9 +80,12 @@ rcl_get_zero_initialized_guard_condition(void); * Lock-Free | Yes * * \param[inout] guard_condition preallocated guard_condition structure + * \param[in] context the context instance with which the guard condition + * should be associated * \param[in] options the guard_condition's options * \return `RCL_RET_OK` if guard_condition was initialized successfully, or * \return `RCL_RET_ALREADY_INIT` if the guard condition is already initialized, or + * \return `RCL_RET_NOT_INIT` if the given context is invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or * \return `RCL_RET_ERROR` if an unspecified error occurs. @@ -88,6 +95,7 @@ RCL_WARN_UNUSED rcl_ret_t rcl_guard_condition_init( rcl_guard_condition_t * guard_condition, + rcl_context_t * context, const rcl_guard_condition_options_t options); /// Same as rcl_guard_condition_init(), but reusing an existing rmw handle. @@ -114,6 +122,9 @@ rcl_guard_condition_init( * * \param[inout] guard_condition preallocated guard_condition structure * \param[in] rmw_guard_condition existing rmw guard condition to reuse + * \param[in] context the context instance with which the rmw guard condition + * was initialized with, i.e. the rmw context inside rcl context needs to + * match rmw context in rmw guard condition * \param[in] options the guard_condition's options * \return `RCL_RET_OK` if guard_condition was initialized successfully, or * \return `RCL_RET_ALREADY_INIT` if the guard condition is already initialized, or @@ -125,6 +136,7 @@ rcl_ret_t rcl_guard_condition_init_from_rmw( rcl_guard_condition_t * guard_condition, const rmw_guard_condition_t * rmw_guard_condition, + rcl_context_t * context, const rcl_guard_condition_options_t options); /// Finalize a rcl_guard_condition_t. @@ -142,6 +154,7 @@ rcl_guard_condition_init_from_rmw( * [1] specifically not thread-safe with rcl_trigger_guard_condition() * * \param[inout] guard_condition handle to the guard_condition to be finalized + * \param[in] context the context originally used to init the guard condition * \return `RCL_RET_OK` if guard_condition was finalized successfully, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or * \return `RCL_RET_ERROR` if an unspecified error occurs. diff --git a/rcl/include/rcl/init.h b/rcl/include/rcl/init.h new file mode 100644 index 000000000..6ff623272 --- /dev/null +++ b/rcl/include/rcl/init.h @@ -0,0 +1,117 @@ +// Copyright 2014 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 RCL__INIT_H_ +#define RCL__INIT_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rcl/allocator.h" +#include "rcl/context.h" +#include "rcl/init_options.h" +#include "rcl/macros.h" +#include "rcl/types.h" +#include "rcl/visibility_control.h" + +/// Initialization of rcl. +/** + * This function can be run any number of times, so long as the given context + * has been properly prepared. + * + * The given `rcl_context_t` must be zero initialized with the function + * `rcl_get_zero_initialized_context()` and must not be already initialized + * by this function. + * If the context is already initialized this function will fail and return the + * `RCL_RET_ALREADY_INIT` error code. + * A context may be initialized again after it has been finalized with the + * `rcl_shutdown()` function and zero initialized again with + * `rcl_get_zero_initialized_context()`. + * + * The `argc` and `argv` parameters may contain command line arguments for the + * program. + * rcl specific arguments will be parsed, but not removed. + * If `argc` is `0` and `argv` is `NULL` no parameters will be parsed. + * + * The `options` argument must be non-`NULL` and must have been initialized + * with `rcl_init_options_init()`. + * It is unmodified by this function, and the ownership is not transfered to + * the context, but instead a copy is made into the context for later reference. + * Therefore, the given options need to be cleaned up with + * `rcl_init_options_fini()` after this function returns. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | No + * Uses Atomics | Yes + * Lock-Free | Yes [1] + * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` + * + * \param[in] argc number of strings in argv + * \param[in] argv command line arguments; rcl specific arguments are removed + * \param[in] options options used during initialization + * \param[out] context resulting context object that represents this init + * \return `RCL_RET_OK` if initialization is successful, or + * \return `RCL_RET_ALREADY_INIT` if rcl_init has already been called, or + * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or + * \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or + * \return `RCL_RET_ERROR` if an unspecified error occurs. + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_init( + int argc, + char const * const * argv, + const rcl_init_options_t * options, + rcl_context_t * context); + +/// Shutdown a given rcl context. +/** + * The given context must have been initialized with `rcl_init()`. + * If not, this function will fail with `RCL_RET_ALREADY_SHUTDOWN`. + * + * When this function is called: + * - Any rcl objects created using this context are invalidated. + * - Functions called on invalid objects may or may not fail. + * - Calls to `rcl_context_is_initialized()` will return `false`. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | Yes + * Uses Atomics | Yes + * Lock-Free | Yes [1] + * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` + * + * \return `RCL_RET_OK` if the shutdown was completed successfully, or + * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or + * \return `RCL_RET_ALREADY_SHUTDOWN` if the context is not currently valid, or + * \return `RCL_RET_ERROR` if an unspecified error occur. + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_shutdown(rcl_context_t * context); + +#ifdef __cplusplus +} +#endif + +#endif // RCL__INIT_H_ diff --git a/rcl/include/rcl/init_options.h b/rcl/include/rcl/init_options.h new file mode 100644 index 000000000..7b1533cba --- /dev/null +++ b/rcl/include/rcl/init_options.h @@ -0,0 +1,159 @@ +// 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 RCL__INIT_OPTIONS_H_ +#define RCL__INIT_OPTIONS_H_ + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rmw/init.h" + +#include "rcl/allocator.h" +#include "rcl/macros.h" +#include "rcl/types.h" +#include "rcl/visibility_control.h" + +struct rcl_init_options_impl_t; + +/// Encapsulation of init options and implementation defined init options. +typedef struct rcl_init_options_t +{ + /// Implementation specific pointer. + struct rcl_init_options_impl_t * impl; +} rcl_init_options_t; + +/// Return a zero initialized rcl_init_options_t struct. +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_init_options_t +rcl_get_zero_initialized_init_options(void); + +/// Initialize given init_options with the default values and implementation specific values. +/** + * The given allocator is used, if required, during setup of the init options, + * but is also used during initialization. + * + * In either case the given allocator is stored in the returned init options. + * + * The `impl` pointer should not be changed manually. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | No + * Uses Atomics | Yes + * Lock-Free | Yes + * + * \param[inout] init_options object to be setup + * \param[in] allocator to be used during setup and during initialization + * \return `RCL_RET_OK` if setup is successful, or + * \return `RCL_RET_ALREADY_INIT` if init_options has already be initialized, or + * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or + * \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or + * \return `RCL_RET_ERROR` if an unspecified error occurs. + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_init_options_init(rcl_init_options_t * init_options, rcl_allocator_t allocator); + +/// Copy the given source init_options to the destination init_options. +/** + * The allocator from the source is used for any allocations and stored in the + * destination. + * + * The destination should either be zero initialized with + * `rcl_get_zero_initialized_init_options()` or should have had + * `rcl_init_options_fini()` called on it. + * Giving an already initialized init options for the destination will result + * in a failure with return code `RCL_RET_ALREADY_INIT`. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | No + * Uses Atomics | Yes + * Lock-Free | Yes + * + * \param[in] src rcl_init_options_t object to be copied from + * \param[out] dst rcl_init_options_t object to be copied into + * \return `RCL_RET_OK` if the copy is successful, or + * \return `RCL_RET_ALREADY_INIT` if the dst has already be initialized, or + * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or + * \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or + * \return `RCL_RET_ERROR` if an unspecified error occurs. + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_init_options_copy(const rcl_init_options_t * src, rcl_init_options_t * dst); + +/// Finalize the given init_options. +/** + * The given init_options must be non-`NULL` and valid, i.e. had + * `rcl_init_options_init()` called on it but not this function yet. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | No + * Uses Atomics | Yes + * Lock-Free | Yes + * + * \param[inout] init_options object to be setup + * \return `RCL_RET_OK` if setup is successful, or + * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or + * \return `RCL_RET_ERROR` if an unspecified error occurs. + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_init_options_fini(rcl_init_options_t * init_options); + +/// Return the rmw init options which are stored internally. +/** + * This function can fail and return `NULL` if: + * - init_options is NULL + * - init_options is invalid, e.g. init_options->impl is NULL + * + * If NULL is returned an error message will have been set. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | No + * Thread-Safe | No + * Uses Atomics | Yes + * Lock-Free | Yes + * + * \param[in] init_options object from which the rmw init options should be retrieved + * \return pointer to the the rmw init options, or + * \return `NULL` if there was an error + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rmw_init_options_t * +rcl_init_options_get_rmw_init_options(rcl_init_options_t * init_options); + +#ifdef __cplusplus +} +#endif + +#endif // RCL__INIT_OPTIONS_H_ diff --git a/rcl/include/rcl/node.h b/rcl/include/rcl/node.h index 734e64423..2f1999c03 100644 --- a/rcl/include/rcl/node.h +++ b/rcl/include/rcl/node.h @@ -24,6 +24,7 @@ extern "C" #include "rcl/allocator.h" #include "rcl/arguments.h" +#include "rcl/context.h" #include "rcl/macros.h" #include "rcl/types.h" #include "rcl/visibility_control.h" @@ -37,6 +38,9 @@ struct rcl_node_impl_t; /// Structure which encapsulates a ROS Node. typedef struct rcl_node_t { + /// Context associated with this node. + rcl_context_t * context; + /// Private implementation pointer. struct rcl_node_impl_t * impl; } rcl_node_t; @@ -74,6 +78,19 @@ typedef struct rcl_node_options_t rcl_arguments_t arguments; } rcl_node_options_t; +/// Return the default node options in a rcl_node_options_t. +/** + * The default values are: + * + * - domain_id = RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID + * - allocator = rcl_get_default_allocator() + * - use_global_arguments = true + * - arguments = rcl_get_zero_initialized_arguments() + */ +RCL_PUBLIC +rcl_node_options_t +rcl_node_get_default_options(void); + /// Return a rcl_node_t struct with members initialized to `NULL`. RCL_PUBLIC RCL_WARN_UNUSED @@ -152,9 +169,12 @@ rcl_get_zero_initialized_node(void); * \param[inout] node a preallocated rcl_node_t * \param[in] name the name of the node, must be a valid c-string * \param[in] namespace_ the namespace of the node, must be a valid c-string + * \param[in] context the context instance with which the node should be + * associated * \param[in] options the node options. - * The options are deep copied into the node. - * The caller is always responsible for freeing memory used options they pass in. + * The options are deep copied into the node. + * The caller is always responsible for freeing memory used options they + * pass in. * \return `RCL_RET_OK` if the node was initialized successfully, or * \return `RCL_RET_ALREADY_INIT` if the node has already be initialized, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or @@ -170,6 +190,7 @@ rcl_node_init( rcl_node_t * node, const char * name, const char * namespace_, + rcl_context_t * context, const rcl_node_options_t * options); /// Finalize a rcl_node_t. @@ -190,6 +211,7 @@ rcl_node_init( * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` * * \param[in] node rcl_node_t to be finalized + * \param[in] context the context originally used to init the node * \return `RCL_RET_OK` if node was finalized successfully, or * \return `RCL_RET_NODE_INVALID` if the node pointer is null, or * \return `RCL_RET_ERROR` if an unspecified error occurs. @@ -199,17 +221,6 @@ RCL_WARN_UNUSED rcl_ret_t rcl_node_fini(rcl_node_t * node); -/// Return the default node options in a rcl_node_options_t. -/** - * The default values are: - * - * - domain_id = RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID - * - allocator = rcl_get_default_allocator() - */ -RCL_PUBLIC -rcl_node_options_t -rcl_node_get_default_options(void); - /// Copy one options structure into another. /** *
@@ -221,7 +232,7 @@ rcl_node_get_default_options(void); * Lock-Free | Yes * * \param[in] options The structure to be copied. - * Its allocator is used to copy memory into the new structure. + * Its allocator is used to copy memory into the new structure. * \param[out] options_out An options structure containing default values. * \return `RCL_RET_OK` if the structure was copied successfully, or * \return `RCL_RET_INVALID_ARGUMENT` if any function arguments are invalid, or @@ -274,6 +285,19 @@ RCL_PUBLIC bool rcl_node_is_valid(const rcl_node_t * node); +/// Return true if node is valid, except for the context being valid. +/** + * This is used in clean up functions that need to access the node, but do not + * need use any functions with the context. + * + * It is identical to rcl_node_is_valid except it ignores the state of the + * context associated with the node. + * \sa rcl_node_is_valid() + */ +RCL_PUBLIC +bool +rcl_node_is_valid_except_context(const rcl_node_t * node); + /// Return the name of the node. /** * This function returns the node's internal name string. diff --git a/rcl/include/rcl/publisher.h b/rcl/include/rcl/publisher.h index d6a829af5..beb130118 100644 --- a/rcl/include/rcl/publisher.h +++ b/rcl/include/rcl/publisher.h @@ -375,7 +375,35 @@ RCL_WARN_UNUSED rmw_publisher_t * rcl_publisher_get_rmw_handle(const rcl_publisher_t * publisher); -/// Check that the publisher is valid +/// Return the context associated with this publisher. +/** + * This function can fail, and therefore return `NULL`, if the: + * - publisher is `NULL` + * - publisher is invalid (never called init, called fini, etc.) + * + * The returned context is made invalid if the publisher is finalized or if + * rcl_shutdown() is called. + * Therefore it is recommended to get the handle from the publisher using + * this function each time it is needed and avoid use of the handle + * concurrently with functions that might change it. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | No + * Thread-Safe | No + * Uses Atomics | No + * Lock-Free | Yes + * + * \param[in] publisher pointer to the rcl publisher + * \return context if successful, otherwise `NULL` + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_context_t * +rcl_publisher_get_context(const rcl_publisher_t * publisher); + +/// Return true if the publisher is valid, otherwise false. /** * The bool returned is `false` if `publisher` is invalid. * The bool returned is `true` otherwise. @@ -397,6 +425,19 @@ RCL_PUBLIC bool rcl_publisher_is_valid(const rcl_publisher_t * publisher); +/// Return true if the publisher is valid except the context, otherwise false. +/** + * This is used in clean up functions that need to access the publisher, but do + * not need use any functions with the context. + * + * It is identical to rcl_publisher_is_valid except it ignores the state of the + * context associated with the publisher. + * \sa rcl_publisher_is_valid() + */ +RCL_PUBLIC +bool +rcl_publisher_is_valid_except_context(const rcl_publisher_t * publisher); + /// Get the number of subscriptions matched to a publisher. /** * Used to get the internal count of subscriptions matched to a publisher. diff --git a/rcl/include/rcl/rcl.h b/rcl/include/rcl/rcl.h index 0405b9ba6..b63e6a97c 100644 --- a/rcl/include/rcl/rcl.h +++ b/rcl/include/rcl/rcl.h @@ -40,8 +40,8 @@ * * It also has some machinery that is necessary to wait on and act on these concepts: * - * - Initialization and shutdown management (global for now) - * - rcl/rcl.h + * - Initialization and shutdown management + * - rcl/init.h * - Wait sets for waiting on messages/service requests and responses/timers to be ready * - rcl/wait.h * - Guard conditions for waking up wait sets asynchronously @@ -73,125 +73,11 @@ extern "C" { #endif -#include "rcl/macros.h" +#include "rcl/init.h" #include "rcl/node.h" #include "rcl/publisher.h" #include "rcl/subscription.h" -#include "rcl/types.h" #include "rcl/wait.h" -#include "rcl/visibility_control.h" - -/// Global initialization of rcl. -/** - * Unless otherwise noted, this must be called before using any rcl functions. - * - * This function can only be run once after starting the program, and once - * after each call to rcl_shutdown(). - * Repeated calls will fail with `RCL_RET_ALREADY_INIT`. - * - * This function can be called any time after rcl_shutdown() is called, but it - * cannot be called from within a callback being executed by an rcl executor. - * For example, you can call rcl_shutdown() from within a timer callback, but - * you have to return from the callback, and therefore exit any in-progress - * call to a spin function, before calling rcl_init() again. - * - * The `argc` and `argv` parameters can contain command line arguments for the - * program. - * rcl specific arguments will be parsed and removed, but other arguments will - * be ignored. - * If `argc` is `0` and `argv` is `NULL` no parameters will be parsed. - * - *
- * Attribute | Adherence - * ------------------ | ------------- - * Allocates Memory | Yes - * Thread-Safe | No - * Uses Atomics | Yes - * Lock-Free | Yes [1] - * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` - * - * \param[in] argc number of strings in argv - * \param[in] argv command line arguments; rcl specific arguments are removed - * \param[in] allocator rcl_allocator_t used in rcl_init() and rcl_shutdown() - * \return `RCL_RET_OK` if initialization is successful, or - * \return `RCL_RET_ALREADY_INIT` if rcl_init has already been called, or - * \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or - * \return `RCL_RET_ERROR` if an unspecified error occurs. - */ -RCL_PUBLIC -RCL_WARN_UNUSED -rcl_ret_t -rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator); - -/// Signal global shutdown of rcl. -/** - * This function does not have to be called on exit, but does have to be called - * making a repeat call to rcl_init(). - * - * This function can only be called once after each call to rcl_init(). - * Repeated calls will fail with RCL_RET_NOT_INIT. - * This function is not thread safe. - * - * When this function is called: - * - Any rcl objects created since the last call to rcl_init() are invalidated. - * - Calls to rcl_ok() will return `false`. - * - Any executors waiting for work (within a call to spin) are interrupted. - * - No new work (executing callbacks) will be done in executors. - * - Currently running work in executors will be finished. - * - *
- * Attribute | Adherence - * ------------------ | ------------- - * Allocates Memory | Yes - * Thread-Safe | Yes [1] - * Uses Atomics | Yes - * Lock-Free | Yes [2] - * [1] not thread-safe with rcl_init() - * [2] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` - * - * \return `RCL_RET_OK` if the shutdown was completed successfully, or - * \return `RCL_RET_NOT_INIT` if rcl is not currently initialized, or - * \return `RCL_RET_ERROR` if an unspecified error occur. - */ -RCL_PUBLIC -RCL_WARN_UNUSED -rcl_ret_t -rcl_shutdown(void); - -/// Returns an uint64_t number that is unique for the latest rcl_init call. -/** - * If called before rcl_init or after rcl_shutdown then 0 will be returned. - * - *
- * Attribute | Adherence - * ------------------ | ------------- - * Allocates Memory | No - * Thread-Safe | Yes - * Uses Atomics | Yes - * Lock-Free | Yes [1] - * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` - * - * \return a unique id specific to this rcl instance, or `0` if not initialized. - */ -RCL_PUBLIC -RCL_WARN_UNUSED -uint64_t -rcl_get_instance_id(void); - -/// Return `true` if rcl is currently initialized, otherwise `false`. -/** - * Attribute | Adherence - * ------------------ | ------------- - * Allocates Memory | No - * Thread-Safe | Yes - * Uses Atomics | Yes - * Lock-Free | Yes [1] - * [1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t` - */ -RCL_PUBLIC -RCL_WARN_UNUSED -bool -rcl_ok(void); #ifdef __cplusplus } diff --git a/rcl/include/rcl/timer.h b/rcl/include/rcl/timer.h index 35238e64f..36a1bfbaa 100644 --- a/rcl/include/rcl/timer.h +++ b/rcl/include/rcl/timer.h @@ -23,6 +23,7 @@ extern "C" #include #include "rcl/allocator.h" +#include "rcl/context.h" #include "rcl/guard_condition.h" #include "rcl/macros.h" #include "rcl/time.h" @@ -107,6 +108,7 @@ rcl_get_zero_initialized_timer(void); * // Optionally reconfigure, cancel, or reset the timer... * } * + * rcl_context_t * context; // initialized previously by rcl_init()... * rcl_clock_t clock; * rcl_allocator_t allocator = rcl_get_default_allocator(); * rcl_ret_t ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); @@ -114,7 +116,7 @@ rcl_get_zero_initialized_timer(void); * * rcl_timer_t timer = rcl_get_zero_initialized_timer(); * ret = rcl_timer_init( - * &timer, &clock, RCL_MS_TO_NS(100), my_timer_callback, allocator); + * &timer, &clock, context, RCL_MS_TO_NS(100), my_timer_callback, allocator); * // ... error handling, use the timer with a wait set, or poll it manually, then cleanup * ret = rcl_timer_fini(&timer); * // ... error handling @@ -135,6 +137,7 @@ rcl_get_zero_initialized_timer(void); * * \param[inout] timer the timer handle to be initialized * \param[in] clock the clock providing the current time + * \param[in] context the context that this timer is to be associated with * \param[in] period the duration between calls to the callback in nanoseconds * \param[in] callback the user defined function to be called every period * \param[in] allocator the allocator to use for allocations @@ -150,6 +153,7 @@ rcl_ret_t rcl_timer_init( rcl_timer_t * timer, rcl_clock_t * clock, + rcl_context_t * context, int64_t period, const rcl_timer_callback_t callback, rcl_allocator_t allocator); diff --git a/rcl/include/rcl/types.h b/rcl/include/rcl/types.h index 4825bf2f3..cba805452 100644 --- a/rcl/include/rcl/types.h +++ b/rcl/include/rcl/types.h @@ -42,6 +42,8 @@ typedef rmw_ret_t rcl_ret_t; #define RCL_RET_SERVICE_NAME_INVALID 104 /// Topic name substitution is unknown. #define RCL_RET_UNKNOWN_SUBSTITUTION 105 +/// rcl_shutdown() already called return code. +#define RCL_RET_ALREADY_SHUTDOWN 106 // rcl node specific ret codes in 2XX /// Invalid rcl_node_t given return code. diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 8c4205fa6..030d1dc62 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -36,9 +36,6 @@ extern "C" { #endif -// Instance of global arguments. -static rcl_arguments_t __rcl_global_arguments; - /// Parse an argument that may or may not be a remap rule. /** * \param[in] arg the argument to parse @@ -510,14 +507,6 @@ rcl_arguments_fini( return RCL_RET_ERROR; } -RCL_PUBLIC -RCL_WARN_UNUSED -rcl_arguments_t * -rcl_get_global_arguments() -{ - return &__rcl_global_arguments; -} - /// Parses a fully qualified namespace for a namespace replacement rule (ex: `/foo/bar`) /** * \sa _rcl_parse_remap_begin_remap_rule() diff --git a/rcl/src/rcl/client.c b/rcl/src/rcl/client.c index 7972179bc..2acef58c6 100644 --- a/rcl/src/rcl/client.c +++ b/rcl/src/rcl/client.c @@ -131,7 +131,7 @@ rcl_client_init( } rcl_arguments_t * global_args = NULL; if (node_options->use_global_arguments) { - global_args = rcl_get_global_arguments(); + global_args = &(node->context->global_arguments); } ret = rcl_remap_service_name( &(node_options->arguments), global_args, expanded_service_name, @@ -200,7 +200,7 @@ rcl_client_fini(rcl_client_t * client, rcl_node_t * node) RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing client"); rcl_ret_t result = RCL_RET_OK; RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT); - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return RCL_RET_NODE_INVALID; // error already set } if (client->impl) { diff --git a/rcl/src/rcl/context.c b/rcl/src/rcl/context.c new file mode 100644 index 000000000..989286657 --- /dev/null +++ b/rcl/src/rcl/context.c @@ -0,0 +1,147 @@ +// 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. + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rcl/context.h" + +#include + +#include "./context_impl.h" +#include "rcutils/stdatomic_helper.h" + +rcl_context_t +rcl_get_zero_initialized_context(void) +{ + static rcl_context_t context = { + .impl = NULL, + .instance_id_storage = {0}, + }; + // this is not constexpr so it cannot be in the struct initialization + context.global_arguments = rcl_get_zero_initialized_arguments(); + // ensure assumption about static storage + static_assert( + sizeof(context.instance_id_storage) >= sizeof(atomic_uint_least64_t), + "expected rcl_context_t's instance id storage to be >= size of atomic_uint_least64_t"); + // initialize atomic + atomic_init((atomic_uint_least64_t *)(&context.instance_id_storage), 0); + return context; +} + +// See `rcl_init()` for initialization of the context. + +rcl_ret_t +rcl_context_fini(rcl_context_t * context) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(context, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_FOR_NULL_WITH_MSG( + context->impl, "context is zero-initialized", return RCL_RET_INVALID_ARGUMENT); + if (rcl_context_is_valid(context)) { + RCL_SET_ERROR_MSG("rcl_shutdown() not called on the given context"); + return RCL_RET_INVALID_ARGUMENT; + } + RCL_CHECK_ALLOCATOR_WITH_MSG( + &(context->impl->allocator), "invalid allocator", return RCL_RET_INVALID_ARGUMENT); + __cleanup_context(context); + return RCL_RET_OK; +} + +// See `rcl_shutdown()` for invalidation of the context. + +const rcl_init_options_t * +rcl_context_get_init_options(rcl_context_t * context) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(context, NULL); + RCL_CHECK_FOR_NULL_WITH_MSG(context->impl, "context is zero-initialized", return NULL); + return &(context->impl->init_options); +} + +rcl_context_instance_id_t +rcl_context_get_instance_id(rcl_context_t * context) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(context, 0); + return rcutils_atomic_load_uint64_t((atomic_uint_least64_t *)(&context->instance_id_storage)); +} + +bool +rcl_context_is_valid(rcl_context_t * context) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(context, false); + return 0 != rcl_context_get_instance_id(context); +} + +void +__cleanup_context(rcl_context_t * context) +{ + // if null, nothing can be done + if (NULL == context) { + return; + } + + // reset the instance id to 0 to indicate "invalid" (should already be 0, but this is defensive) + rcutils_atomic_store((atomic_uint_least64_t *)(&context->instance_id_storage), 0); + + // clean up global_arguments if initialized + if (NULL != context->global_arguments.impl) { + rcl_ret_t ret = rcl_arguments_fini(&(context->global_arguments)); + if (RCL_RET_OK != ret) { + RCUTILS_SAFE_FWRITE_TO_STDERR( + "[rcl|init.c:" RCUTILS_STRINGIFY(__LINE__) + "] failed to finalize global arguments while cleaning up context, memory may be leaked: "); + RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str); + RCUTILS_SAFE_FWRITE_TO_STDERR("\n"); + rcl_reset_error(); + } + } + + // if impl is null, nothing else can be cleaned up + if (NULL != context->impl) { + // pull allocator out for use during deallocation + rcl_allocator_t allocator = context->impl->allocator; + + // finalize init options if valid + if (NULL != context->impl->init_options.impl) { + rcl_ret_t ret = rcl_init_options_fini(&(context->impl->init_options)); + if (RCL_RET_OK != ret) { + RCUTILS_SAFE_FWRITE_TO_STDERR( + "[rcl|init.c:" RCUTILS_STRINGIFY(__LINE__) + "] failed to finalize init options while cleaning up context, memory may be leaked: "); + RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str); + RCUTILS_SAFE_FWRITE_TO_STDERR("\n"); + rcl_reset_error(); + } + } + + // clean up copy of argv if valid + if (NULL != context->impl->argv) { + int64_t i; + for (i = 0; i < context->impl->argc; ++i) { + if (NULL != context->impl->argv[i]) { + allocator.deallocate(context->impl->argv[i], allocator.state); + } + } + allocator.deallocate(context->impl->argv, allocator.state); + } + } // if (NULL != context->impl) + + // zero-initialize the context + *context = rcl_get_zero_initialized_context(); +} + +#ifdef __cplusplus +} +#endif diff --git a/rcl/src/rcl/context_impl.h b/rcl/src/rcl/context_impl.h new file mode 100644 index 000000000..79741e31d --- /dev/null +++ b/rcl/src/rcl/context_impl.h @@ -0,0 +1,51 @@ +// 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 RCL__CONTEXT_IMPL_H_ +#define RCL__CONTEXT_IMPL_H_ + +#include "rcl/context.h" +#include "rcl/error_handling.h" + +#include "./init_options_impl.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +/// \internal +typedef struct rcl_context_impl_t +{ + /// Allocator used during init and shutdown. + rcl_allocator_t allocator; + /// Copy of init options given during init. + rcl_init_options_t init_options; + /// Length of argv (may be `0`). + int64_t argc; + /// Copy of argv used during init (may be `NULL`). + char ** argv; + /// rmw context. + rmw_context_t rmw_context; +} rcl_context_impl_t; + +RCL_LOCAL +void +__cleanup_context(rcl_context_t * context); + +#ifdef __cplusplus +} +#endif + +#endif // RCL__CONTEXT_IMPL_H_ diff --git a/rcl/src/rcl/graph.c b/rcl/src/rcl/graph.c index fcc0b9c98..cc89fca86 100644 --- a/rcl/src/rcl/graph.c +++ b/rcl/src/rcl/graph.c @@ -130,6 +130,9 @@ rcl_count_publishers( const char * topic_name, size_t * count) { + if (!rcl_node_is_valid(node)) { + return RCL_RET_NODE_INVALID; // error already set + } const rcl_node_options_t * node_options = rcl_node_get_options(node); if (!node_options) { return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so @@ -146,6 +149,9 @@ rcl_count_subscribers( const char * topic_name, size_t * count) { + if (!rcl_node_is_valid(node)) { + return RCL_RET_NODE_INVALID; // error already set + } const rcl_node_options_t * node_options = rcl_node_get_options(node); if (!node_options) { return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so @@ -162,6 +168,9 @@ rcl_service_server_is_available( const rcl_client_t * client, bool * is_available) { + if (!rcl_node_is_valid(node)) { + return RCL_RET_NODE_INVALID; // error already set + } const rcl_node_options_t * node_options = rcl_node_get_options(node); if (!node_options) { return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so diff --git a/rcl/src/rcl/guard_condition.c b/rcl/src/rcl/guard_condition.c index e55d19ade..05aa63693 100644 --- a/rcl/src/rcl/guard_condition.c +++ b/rcl/src/rcl/guard_condition.c @@ -24,6 +24,8 @@ extern "C" #include "rmw/error_handling.h" #include "rmw/rmw.h" +#include "./context_impl.h" + typedef struct rcl_guard_condition_impl_t { rmw_guard_condition_t * rmw_handle; @@ -42,6 +44,7 @@ rcl_ret_t __rcl_guard_condition_init_from_rmw_impl( rcl_guard_condition_t * guard_condition, const rmw_guard_condition_t * rmw_guard_condition, + rcl_context_t * context, const rcl_guard_condition_options_t options) { // This function will create an rmw_guard_condition if the parameter is null. @@ -56,8 +59,11 @@ __rcl_guard_condition_init_from_rmw_impl( return RCL_RET_ALREADY_INIT; } // Make sure rcl has been initialized. - if (!rcl_ok()) { - RCL_SET_ERROR_MSG("rcl_init() has not been called"); + RCL_CHECK_ARGUMENT_FOR_NULL(context, RCL_RET_INVALID_ARGUMENT); + if (!rcl_context_is_valid(context)) { + RCL_SET_ERROR_MSG( + "the given context is not valid, " + "either rcl_init() was not called or rcl_shutdown() was called."); return RCL_RET_NOT_INIT; } // Allocate space for the guard condition impl. @@ -74,7 +80,7 @@ __rcl_guard_condition_init_from_rmw_impl( guard_condition->impl->allocated_rmw_guard_condition = false; } else { // Otherwise create one. - guard_condition->impl->rmw_handle = rmw_create_guard_condition(); + guard_condition->impl->rmw_handle = rmw_create_guard_condition(&(context->impl->rmw_context)); if (!guard_condition->impl->rmw_handle) { // Deallocate impl and exit. allocator->deallocate(guard_condition->impl, allocator->state); @@ -91,19 +97,22 @@ __rcl_guard_condition_init_from_rmw_impl( rcl_ret_t rcl_guard_condition_init( rcl_guard_condition_t * guard_condition, + rcl_context_t * context, const rcl_guard_condition_options_t options) { // NULL indicates "create a new rmw guard condition". - return __rcl_guard_condition_init_from_rmw_impl(guard_condition, NULL, options); + return __rcl_guard_condition_init_from_rmw_impl(guard_condition, NULL, context, options); } rcl_ret_t rcl_guard_condition_init_from_rmw( rcl_guard_condition_t * guard_condition, const rmw_guard_condition_t * rmw_guard_condition, + rcl_context_t * context, const rcl_guard_condition_options_t options) { - return __rcl_guard_condition_init_from_rmw_impl(guard_condition, rmw_guard_condition, options); + return __rcl_guard_condition_init_from_rmw_impl( + guard_condition, rmw_guard_condition, context, options); } rcl_ret_t diff --git a/rcl/src/rcl/init.c b/rcl/src/rcl/init.c new file mode 100644 index 000000000..1902f10a0 --- /dev/null +++ b/rcl/src/rcl/init.c @@ -0,0 +1,178 @@ +// Copyright 2015 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. + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rcl/init.h" + +#include "./arguments_impl.h" +#include "./common.h" +#include "./context_impl.h" +#include "./init_options_impl.h" +#include "rcl/arguments.h" +#include "rcl/error_handling.h" +#include "rcutils/logging_macros.h" +#include "rcutils/stdatomic_helper.h" +#include "rmw/error_handling.h" + +static atomic_uint_least64_t __rcl_next_unique_id = ATOMIC_VAR_INIT(1); + +rcl_ret_t +rcl_init( + int argc, + char const * const * argv, + const rcl_init_options_t * options, + rcl_context_t * context) +{ + rcl_ret_t fail_ret = RCL_RET_ERROR; + + if (argc > 0) { + RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT); + } else { + if (NULL != argv) { + RCL_SET_ERROR_MSG("argc is <= 0, but argv is not NULL"); + return RCL_RET_INVALID_ARGUMENT; + } + } + RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(options->impl, RCL_RET_INVALID_ARGUMENT); + rcl_allocator_t allocator = options->impl->allocator; + RCL_CHECK_ALLOCATOR(&allocator, return RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(context, RCL_RET_INVALID_ARGUMENT); + + RCUTILS_LOG_DEBUG_NAMED( + ROS_PACKAGE_NAME, + "Initializing ROS client library, for context at address: %p", context); + + // test expectation that given context is zero initialized + if (NULL != context->impl) { + // note that this can also occur when the given context is used before initialization + // i.e. it is declared on the stack but never defined or zero initialized + RCL_SET_ERROR_MSG("rcl_init called on an already initialized context"); + return RCL_RET_ALREADY_INIT; + } + + // Zero initialize global arguments. + context->global_arguments = rcl_get_zero_initialized_arguments(); + + // Setup impl for context. + // use zero_allocate so the cleanup function will not try to clean up uninitialized parts later + context->impl = allocator.zero_allocate(1, sizeof(rcl_context_impl_t), allocator.state); + RCL_CHECK_FOR_NULL_WITH_MSG( + context->impl, "failed to allocate memory for context impl", return RCL_RET_BAD_ALLOC); + + // Copy the options into the context for future reference. + rcl_ret_t ret = rcl_init_options_copy(options, &(context->impl->init_options)); + if (RCL_RET_OK != ret) { + fail_ret = ret; // error message already set + goto fail; + } + + // Copy the argc and argv into the context, if argc >= 0. + context->impl->argc = argc; + context->impl->argv = NULL; + if (0 != argc && argv != NULL) { + context->impl->argv = (char **)allocator.zero_allocate(argc, sizeof(char *), allocator.state); + RCL_CHECK_FOR_NULL_WITH_MSG( + context->impl->argv, + "failed to allocate memory for argv", + fail_ret = RCL_RET_BAD_ALLOC; goto fail); + int64_t i; + for (i = 0; i < argc; ++i) { + size_t argv_i_length = strlen(argv[i]); + context->impl->argv[i] = (char *)allocator.allocate(argv_i_length, allocator.state); + RCL_CHECK_FOR_NULL_WITH_MSG( + context->impl->argv[i], + "failed to allocate memory for string entry in argv", + fail_ret = RCL_RET_BAD_ALLOC; goto fail); + memcpy(context->impl->argv[i], argv[i], argv_i_length); + } + } + + // Parse the ROS specific arguments. + ret = rcl_parse_arguments(argc, argv, allocator, &context->global_arguments); + if (RCL_RET_OK != ret) { + fail_ret = ret; + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to parse global arguments"); + goto fail; + } + // Update the default log level if specified in arguments. + if (context->global_arguments.impl->log_level >= 0) { + rcutils_logging_set_default_logger_level(context->global_arguments.impl->log_level); + } + + // Set the instance id. + uint64_t next_instance_id = rcutils_atomic_fetch_add_uint64_t(&__rcl_next_unique_id, 1); + if (0 == next_instance_id) { + // Roll over occurred, this is an extremely unlikely occurrence. + RCL_SET_ERROR_MSG("unique rcl instance ids exhausted"); + // Roll back to try to avoid the next call succeeding, but there's a data race here. + rcutils_atomic_store(&__rcl_next_unique_id, -1); + goto fail; + } + rcutils_atomic_store((atomic_uint_least64_t *)(&context->instance_id_storage), next_instance_id); + context->impl->init_options.impl->rmw_init_options.instance_id = next_instance_id; + + // Initialize rmw_init. + context->impl->rmw_context = rmw_get_zero_initialized_context(); + rmw_ret_t rmw_ret = rmw_init( + &(context->impl->init_options.impl->rmw_init_options), + &(context->impl->rmw_context)); + if (RMW_RET_OK != rmw_ret) { + RCL_SET_ERROR_MSG(rmw_get_error_string().str); + fail_ret = rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); + goto fail; + } + + // Store the allocator. + context->impl->allocator = allocator; + + return RCL_RET_OK; +fail: + __cleanup_context(context); + return fail_ret; +} + +rcl_ret_t +rcl_shutdown(rcl_context_t * context) +{ + RCUTILS_LOG_DEBUG_NAMED( + ROS_PACKAGE_NAME, + "Shutting down ROS client library, for context at address: %p", context); + RCL_CHECK_ARGUMENT_FOR_NULL(context, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_FOR_NULL_WITH_MSG( + context->impl, "context is zero-initialized", return RCL_RET_INVALID_ARGUMENT); + if (!rcl_context_is_valid(context)) { + RCL_SET_ERROR_MSG("rcl_shutdown already called on the given context"); + return RCL_RET_ALREADY_SHUTDOWN; + } + + // reset the instance id to 0 to indicate "invalid" + rcutils_atomic_store((atomic_uint_least64_t *)(&context->instance_id_storage), 0); + + rmw_ret_t rmw_ret = rmw_shutdown(&(context->impl->rmw_context)); + if (RMW_RET_OK != rmw_ret) { + RCL_SET_ERROR_MSG(rmw_get_error_string().str); + return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); + } + + return RCL_RET_OK; +} + +#ifdef __cplusplus +} +#endif diff --git a/rcl/src/rcl/init_options.c b/rcl/src/rcl/init_options.c new file mode 100644 index 000000000..12b17fd68 --- /dev/null +++ b/rcl/src/rcl/init_options.c @@ -0,0 +1,144 @@ +// Copyright 2015 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. + +#ifdef __cplusplus +extern "C" +{ +#endif + +#include "rcl/init_options.h" + +#include "./common.h" +#include "./init_options_impl.h" +#include "rcl/error_handling.h" +#include "rmw/error_handling.h" +#include "rcutils/logging_macros.h" + +rcl_init_options_t +rcl_get_zero_initialized_init_options(void) +{ + return (const rcl_init_options_t) { + .impl = 0, + }; // NOLINT(readability/braces): false positive +} + +rcl_ret_t +rcl_init_options_init(rcl_init_options_t * init_options, rcl_allocator_t allocator) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(init_options, RCL_RET_INVALID_ARGUMENT); + if (NULL != init_options->impl) { + RCL_SET_ERROR_MSG("given init_options (rcl_init_options_t) is already initialized"); + return RCL_RET_ALREADY_INIT; + } + RCL_CHECK_ALLOCATOR(&allocator, return RCL_RET_INVALID_ARGUMENT); + init_options->impl = allocator.allocate(sizeof(rcl_init_options_impl_t), allocator.state); + RCL_CHECK_FOR_NULL_WITH_MSG( + init_options->impl, + "failed to allocate memory for init options impl", + return RCL_RET_BAD_ALLOC); + init_options->impl->allocator = allocator; + init_options->impl->rmw_init_options = rmw_get_zero_initialized_init_options(); + rmw_ret_t rmw_ret = rmw_init_options_init(&(init_options->impl->rmw_init_options), allocator); + if (RMW_RET_OK != rmw_ret) { + allocator.deallocate(init_options->impl, allocator.state); + RCL_SET_ERROR_MSG(rmw_get_error_string().str); + return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); + } + return RCL_RET_OK; +} + +rcl_ret_t +rcl_init_options_copy(const rcl_init_options_t * src, rcl_init_options_t * dst) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(src, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(src->impl, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(dst, RCL_RET_INVALID_ARGUMENT); + if (NULL != dst->impl) { + RCL_SET_ERROR_MSG("given dst (rcl_init_options_t) is already initialized"); + return RCL_RET_ALREADY_INIT; + } + + // initialize dst (since we know it's in a zero initialized state) + rcl_ret_t ret = rcl_init_options_init(dst, src->impl->allocator); + if (RCL_RET_OK != ret) { + return ret; // error already set + } + + // copy src information into dst + dst->impl->allocator = src->impl->allocator; + // first zero-initialize rmw init options + rmw_ret_t rmw_ret = rmw_init_options_fini(&(dst->impl->rmw_init_options)); + if (RMW_RET_OK != rmw_ret) { + rmw_error_string_t error_string = rmw_get_error_string(); + rmw_reset_error(); + ret = rcl_init_options_fini(dst); + if (RCL_RET_OK != ret) { + RCUTILS_LOG_ERROR_NAMED( + "rcl", + "failed to finalize dst rcl_init_options while handling failure to " + "finalize rmw_init_options, original ret '%d' and error: %s", rmw_ret, error_string.str); + return ret; // error already set + } + RCL_SET_ERROR_MSG(error_string.str); + return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); + } + // then copy + dst->impl->rmw_init_options = rmw_get_zero_initialized_init_options(); + rmw_ret = + rmw_init_options_copy(&(src->impl->rmw_init_options), &(dst->impl->rmw_init_options)); + if (RMW_RET_OK != rmw_ret) { + rmw_error_string_t error_string = rmw_get_error_string(); + rmw_reset_error(); + ret = rcl_init_options_fini(dst); + if (RCL_RET_OK != ret) { + RCUTILS_LOG_ERROR_NAMED( + "rcl", + "failed to finalize dst rcl_init_options while handling failure to " + "copy rmw_init_options, original ret '%d' and error: %s", rmw_ret, error_string.str); + return ret; // error already set + } + RCL_SET_ERROR_MSG(error_string.str); + return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); + } + + return RCL_RET_OK; +} + +rcl_ret_t +rcl_init_options_fini(rcl_init_options_t * init_options) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(init_options, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(init_options->impl, RCL_RET_INVALID_ARGUMENT); + rcl_allocator_t allocator = init_options->impl->allocator; + RCL_CHECK_ALLOCATOR(&allocator, return RCL_RET_INVALID_ARGUMENT); + rmw_ret_t rmw_ret = rmw_init_options_fini(&(init_options->impl->rmw_init_options)); + if (RMW_RET_OK != rmw_ret) { + RCL_SET_ERROR_MSG(rmw_get_error_string().str); + return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); + } + allocator.deallocate(init_options->impl, allocator.state); + return RCL_RET_OK; +} + +rmw_init_options_t * +rcl_init_options_get_rmw_init_options(rcl_init_options_t * init_options) +{ + RCL_CHECK_ARGUMENT_FOR_NULL(init_options, NULL); + RCL_CHECK_ARGUMENT_FOR_NULL(init_options->impl, NULL); + return &(init_options->impl->rmw_init_options); +} + +#ifdef __cplusplus +} +#endif diff --git a/rcl/src/rcl/init_options_impl.h b/rcl/src/rcl/init_options_impl.h new file mode 100644 index 000000000..e03a8e88a --- /dev/null +++ b/rcl/src/rcl/init_options_impl.h @@ -0,0 +1,38 @@ +// 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 RCL__INIT_OPTIONS_IMPL_H_ +#define RCL__INIT_OPTIONS_IMPL_H_ + +#include "rcl/init_options.h" + +#include "rmw/init.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +/// \internal +typedef struct rcl_init_options_impl_t +{ + rcl_allocator_t allocator; + rmw_init_options_t rmw_init_options; +} rcl_init_options_impl_t; + +#ifdef __cplusplus +} +#endif + +#endif // RCL__INIT_OPTIONS_IMPL_H_ diff --git a/rcl/src/rcl/node.c b/rcl/src/rcl/node.c index 2e3e2ee0e..5d7fdf0e2 100644 --- a/rcl/src/rcl/node.c +++ b/rcl/src/rcl/node.c @@ -44,7 +44,7 @@ extern "C" #include "rmw/validate_node_name.h" #include "./common.h" - +#include "./context_impl.h" #define ROS_SECURITY_NODE_DIRECTORY_VAR_NAME "ROS_SECURITY_NODE_DIRECTORY" #define ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "ROS_SECURITY_ROOT_DIRECTORY" @@ -56,7 +56,6 @@ typedef struct rcl_node_impl_t rcl_node_options_t options; size_t actual_domain_id; rmw_node_t * rmw_node_handle; - uint64_t rcl_instance_id; rcl_guard_condition_t * graph_guard_condition; const char * logger_name; } rcl_node_impl_t; @@ -192,6 +191,7 @@ rcl_node_init( rcl_node_t * node, const char * name, const char * namespace_, + rcl_context_t * context, const rcl_node_options_t * options) { size_t domain_id = 0; @@ -218,8 +218,12 @@ rcl_node_init( return RCL_RET_ALREADY_INIT; } // Make sure rcl has been initialized. - if (!rcl_ok()) { - RCL_SET_ERROR_MSG("rcl_init() has not been called"); + RCL_CHECK_FOR_NULL_WITH_MSG( + context, "given context in options is NULL", return RCL_RET_INVALID_ARGUMENT); + if (!rcl_context_is_valid(context)) { + RCL_SET_ERROR_MSG( + "the given context is not valid, " + "either rcl_init() was not called or rcl_shutdown() was called."); return RCL_RET_NOT_INIT; } // Make sure the node name is valid before allocating memory. @@ -277,6 +281,7 @@ rcl_node_init( node->impl->graph_guard_condition = NULL; node->impl->logger_name = NULL; node->impl->options = rcl_node_get_default_options(); + node->context = context; // Initialize node impl. ret = rcl_node_options_copy(options, &(node->impl->options)); if (RCL_RET_OK != ret) { @@ -286,7 +291,7 @@ rcl_node_init( // Remap the node name and namespace if remap rules are given rcl_arguments_t * global_args = NULL; if (node->impl->options.use_global_arguments) { - global_args = rcl_get_global_arguments(); + global_args = &(node->context->global_arguments); } ret = rcl_remap_node_name( &(node->impl->options.arguments), global_args, name, *allocator, @@ -386,12 +391,11 @@ rcl_node_init( } } node->impl->rmw_node_handle = rmw_create_node( + &(node->context->impl->rmw_context), name, local_namespace_, domain_id, &node_security_options); RCL_CHECK_FOR_NULL_WITH_MSG( node->impl->rmw_node_handle, rmw_get_error_string().str, goto fail); - // instance id - node->impl->rcl_instance_id = rcl_get_instance_id(); // graph guard condition rmw_graph_guard_condition = rmw_node_get_graph_guard_condition(node->impl->rmw_node_handle); RCL_CHECK_FOR_NULL_WITH_MSG( @@ -408,6 +412,7 @@ rcl_node_init( ret = rcl_guard_condition_init_from_rmw( node->impl->graph_guard_condition, rmw_graph_guard_condition, + context, graph_guard_condition_options); if (ret != RCL_RET_OK) { // error message already set @@ -503,19 +508,29 @@ rcl_node_fini(rcl_node_t * node) } bool -rcl_node_is_valid(const rcl_node_t * node) +rcl_node_is_valid_except_context(const rcl_node_t * node) { RCL_CHECK_FOR_NULL_WITH_MSG(node, "rcl node pointer is invalid", return false); RCL_CHECK_FOR_NULL_WITH_MSG(node->impl, "rcl node implementation is invalid", return false); - if (node->impl->rcl_instance_id != rcl_get_instance_id()) { - RCL_SET_ERROR_MSG("rcl node is invalid, rcl instance id does not match"); - return false; - } RCL_CHECK_FOR_NULL_WITH_MSG( node->impl->rmw_node_handle, "rcl node's rmw handle is invalid", return false); return true; } +bool +rcl_node_is_valid(const rcl_node_t * node) +{ + bool result = rcl_node_is_valid_except_context(node); + if (!result) { + return result; + } + if (!rcl_context_is_valid(node->context)) { + RCL_SET_ERROR_MSG("rcl node's context is invalid"); + return false; + } + return true; +} + rcl_node_options_t rcl_node_get_default_options() { @@ -554,7 +569,7 @@ rcl_node_options_copy( const char * rcl_node_get_name(const rcl_node_t * node) { - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return NULL; // error already set } return node->impl->rmw_node_handle->name; @@ -563,7 +578,7 @@ rcl_node_get_name(const rcl_node_t * node) const char * rcl_node_get_namespace(const rcl_node_t * node) { - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return NULL; // error already set } return node->impl->rmw_node_handle->namespace_; @@ -572,7 +587,7 @@ rcl_node_get_namespace(const rcl_node_t * node) const rcl_node_options_t * rcl_node_get_options(const rcl_node_t * node) { - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return NULL; // error already set } return &node->impl->options; @@ -593,7 +608,7 @@ rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id) rmw_node_t * rcl_node_get_rmw_handle(const rcl_node_t * node) { - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return NULL; // error already set } return node->impl->rmw_node_handle; @@ -602,17 +617,16 @@ rcl_node_get_rmw_handle(const rcl_node_t * node) uint64_t rcl_node_get_rcl_instance_id(const rcl_node_t * node) { - // Not using rcl_node_is_valid() since we can still get the - // instance ID from an initialized node, even if it is invalid - RCL_CHECK_ARGUMENT_FOR_NULL(node, 0); - RCL_CHECK_FOR_NULL_WITH_MSG(node->impl, "node implementation is invalid", return 0); - return node->impl->rcl_instance_id; + if (!rcl_node_is_valid_except_context(node)) { + return 0; // error already set + } + return rcl_context_get_instance_id(node->context); } const struct rcl_guard_condition_t * rcl_node_get_graph_guard_condition(const rcl_node_t * node) { - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return NULL; // error already set } return node->impl->graph_guard_condition; @@ -621,7 +635,7 @@ rcl_node_get_graph_guard_condition(const rcl_node_t * node) const char * rcl_node_get_logger_name(const rcl_node_t * node) { - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return NULL; // error already set } return node->impl->logger_name; diff --git a/rcl/src/rcl/publisher.c b/rcl/src/rcl/publisher.c index c3d695251..8709a9905 100644 --- a/rcl/src/rcl/publisher.c +++ b/rcl/src/rcl/publisher.c @@ -35,6 +35,7 @@ extern "C" typedef struct rcl_publisher_impl_t { rcl_publisher_options_t options; + rcl_context_t * context; rmw_publisher_t * rmw_handle; } rcl_publisher_impl_t; @@ -130,7 +131,7 @@ rcl_publisher_init( } rcl_arguments_t * global_args = NULL; if (node_options->use_global_arguments) { - global_args = rcl_get_global_arguments(); + global_args = &(node->context->global_arguments); } ret = rcl_remap_topic_name( &(node_options->arguments), global_args, expanded_topic_name, @@ -173,6 +174,8 @@ rcl_publisher_init( // options publisher->impl->options = *options; RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Publisher initialized"); + // context + publisher->impl->context = node->context; goto cleanup; fail: if (publisher->impl) { @@ -195,7 +198,7 @@ rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node) { rcl_ret_t result = RCL_RET_OK; RCL_CHECK_ARGUMENT_FOR_NULL(publisher, RCL_RET_PUBLISHER_INVALID); - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return RCL_RET_NODE_INVALID; // error already set } @@ -232,7 +235,6 @@ rcl_publisher_get_default_options() rcl_ret_t rcl_publish(const rcl_publisher_t * publisher, const void * ros_message) { - RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Publisher publishing message"); if (!rcl_publisher_is_valid(publisher)) { return RCL_RET_PUBLISHER_INVALID; // error already set } @@ -266,7 +268,7 @@ rcl_publish_serialized_message( const char * rcl_publisher_get_topic_name(const rcl_publisher_t * publisher) { - if (!rcl_publisher_is_valid(publisher)) { + if (!rcl_publisher_is_valid_except_context(publisher)) { return NULL; // error already set } return publisher->impl->rmw_handle->topic_name; @@ -277,7 +279,7 @@ rcl_publisher_get_topic_name(const rcl_publisher_t * publisher) const rcl_publisher_options_t * rcl_publisher_get_options(const rcl_publisher_t * publisher) { - if (!rcl_publisher_is_valid(publisher)) { + if (!rcl_publisher_is_valid_except_context(publisher)) { return NULL; // error already set } return _publisher_get_options(publisher); @@ -286,14 +288,38 @@ rcl_publisher_get_options(const rcl_publisher_t * publisher) rmw_publisher_t * rcl_publisher_get_rmw_handle(const rcl_publisher_t * publisher) { - if (!rcl_publisher_is_valid(publisher)) { + if (!rcl_publisher_is_valid_except_context(publisher)) { return NULL; // error already set } return publisher->impl->rmw_handle; } +rcl_context_t * +rcl_publisher_get_context(const rcl_publisher_t * publisher) +{ + if (!rcl_publisher_is_valid_except_context(publisher)) { + return NULL; // error already set + } + return publisher->impl->context; +} + bool rcl_publisher_is_valid(const rcl_publisher_t * publisher) +{ + if (!rcl_publisher_is_valid_except_context(publisher)) { + return false; // error already set + } + if (!rcl_context_is_valid(publisher->impl->context)) { + RCL_SET_ERROR_MSG("publisher's context is invalid"); + return false; + } + RCL_CHECK_FOR_NULL_WITH_MSG( + publisher->impl->rmw_handle, "publisher's rmw handle is invalid", return false); + return true; +} + +bool +rcl_publisher_is_valid_except_context(const rcl_publisher_t * publisher) { RCL_CHECK_FOR_NULL_WITH_MSG(publisher, "publisher pointer is invalid", return false); RCL_CHECK_FOR_NULL_WITH_MSG( diff --git a/rcl/src/rcl/rcl.c b/rcl/src/rcl/rcl.c deleted file mode 100644 index 7aa692565..000000000 --- a/rcl/src/rcl/rcl.c +++ /dev/null @@ -1,166 +0,0 @@ -// Copyright 2015 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. - -#ifdef __cplusplus -extern "C" -{ -#endif - -#include "rcl/rcl.h" - -#include - -#include "./arguments_impl.h" -#include "rcl/arguments.h" -#include "rcl/error_handling.h" -#include "rcutils/logging_macros.h" -#include "rcutils/stdatomic_helper.h" -#include "rmw/error_handling.h" - -static atomic_bool __rcl_is_initialized = ATOMIC_VAR_INIT(false); -static rcl_allocator_t __rcl_allocator; -static int __rcl_argc = 0; -static char ** __rcl_argv = NULL; -static atomic_uint_least64_t __rcl_instance_id = ATOMIC_VAR_INIT(0); -static uint64_t __rcl_next_unique_id = 0; - -static void -__clean_up_init() -{ - if (__rcl_argv) { - int i; - for (i = 0; i < __rcl_argc; ++i) { - if (__rcl_argv[i]) { - // Use the old allocator. - __rcl_allocator.deallocate(__rcl_argv[i], __rcl_allocator.state); - } - } - // Use the old allocator. - __rcl_allocator.deallocate(__rcl_argv, __rcl_allocator.state); - } - __rcl_argc = 0; - __rcl_argv = NULL; - // This is the only place where it is OK to finalize the global arguments. - rcl_arguments_t * global_args = rcl_get_global_arguments(); - if (NULL != global_args->impl && RCL_RET_OK != rcl_arguments_fini(global_args)) { - rcl_reset_error(); - } - rcutils_atomic_store(&__rcl_instance_id, 0); - rcutils_atomic_store(&__rcl_is_initialized, false); -} - -rcl_ret_t -rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator) -{ - rcl_ret_t fail_ret = RCL_RET_ERROR; - - // Check allocator first, so it can be used in other errors. - RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); - - if (argc > 0) { - RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT); - } - if (rcutils_atomic_exchange_bool(&__rcl_is_initialized, true)) { - RCL_SET_ERROR_MSG("rcl_init called while already initialized"); - return RCL_RET_ALREADY_INIT; - } - - // Zero initialize global arguments before any chance of calling __clean_up_init() - rcl_arguments_t * global_args = rcl_get_global_arguments(); - *global_args = rcl_get_zero_initialized_arguments(); - - // There is a race condition between the time __rcl_is_initialized is set true, - // and when the allocator is set, in which rcl_shutdown() could get rcl_ok() as - // true and try to use the allocator, but it isn't set yet... - // A very unlikely race condition, but it is possile I think. - // I've documented that rcl_init() and rcl_shutdown() are not thread-safe with each other. - __rcl_allocator = allocator; // Set the new allocator. - // Initialize rmw_init. - rmw_ret_t rmw_ret = rmw_init(); - if (rmw_ret != RMW_RET_OK) { - RCL_SET_ERROR_MSG(rmw_get_error_string().str); - fail_ret = RCL_RET_ERROR; - goto fail; - } - // TODO(wjwwood): Remove rcl specific command line arguments. - // For now just copy the argc and argv. - __rcl_argc = argc; - __rcl_argv = (char **)__rcl_allocator.allocate(sizeof(char *) * argc, __rcl_allocator.state); - if (!__rcl_argv) { - RCL_SET_ERROR_MSG("allocation failed"); - fail_ret = RCL_RET_BAD_ALLOC; - goto fail; - } - memset(__rcl_argv, 0, sizeof(char **) * argc); - int i; - for (i = 0; i < argc; ++i) { - __rcl_argv[i] = (char *)__rcl_allocator.allocate(strlen(argv[i]), __rcl_allocator.state); - if (!__rcl_argv[i]) { - RCL_SET_ERROR_MSG("allocation failed"); - fail_ret = RCL_RET_BAD_ALLOC; - goto fail; - } - memcpy(__rcl_argv[i], argv[i], strlen(argv[i])); - } - if (RCL_RET_OK != rcl_parse_arguments(argc, (const char **)argv, allocator, global_args)) { - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to parse global arguments"); - goto fail; - } - - // Update the default log level if specified in arguments. - if (global_args->impl->log_level >= 0) { - rcutils_logging_set_default_logger_level(global_args->impl->log_level); - } - - rcutils_atomic_store(&__rcl_instance_id, ++__rcl_next_unique_id); - if (rcutils_atomic_load_uint64_t(&__rcl_instance_id) == 0) { - // Roll over occurred. - __rcl_next_unique_id--; // roll back to avoid the next call succeeding. - RCL_SET_ERROR_MSG("unique rcl instance ids exhausted"); - goto fail; - } - return RCL_RET_OK; -fail: - __clean_up_init(); - return fail_ret; -} - -rcl_ret_t -rcl_shutdown() -{ - RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Shutting down"); - if (!rcl_ok()) { - // must use default allocator here because __rcl_allocator may not be set yet - RCL_SET_ERROR_MSG("rcl_shutdown called before rcl_init"); - return RCL_RET_NOT_INIT; - } - __clean_up_init(); - return RCL_RET_OK; -} - -uint64_t -rcl_get_instance_id() -{ - return rcutils_atomic_load_uint64_t(&__rcl_instance_id); -} - -bool -rcl_ok() -{ - return rcutils_atomic_load_bool(&__rcl_is_initialized); -} - -#ifdef __cplusplus -} -#endif diff --git a/rcl/src/rcl/rmw_implementation_identifier_check.c b/rcl/src/rcl/rmw_implementation_identifier_check.c index c561ef8eb..0b250bf16 100644 --- a/rcl/src/rcl/rmw_implementation_identifier_check.c +++ b/rcl/src/rcl/rmw_implementation_identifier_check.c @@ -129,10 +129,12 @@ INITIALIZER(initialize) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error getting RMW implementation identifier / RMW implementation not installed " - "(expected identifier of '%s'), exiting with %d.", + "(expected identifier of '%s'), with error message '%s', exiting with %d.", expected_rmw_impl, + rcl_get_error_string().str, RCL_RET_ERROR ); + rcl_reset_error(); exit(RCL_RET_ERROR); } if (strcmp(actual_rmw_impl_id, expected_rmw_impl) != 0) { diff --git a/rcl/src/rcl/service.c b/rcl/src/rcl/service.c index 963286248..70ddd7690 100644 --- a/rcl/src/rcl/service.c +++ b/rcl/src/rcl/service.c @@ -129,7 +129,7 @@ rcl_service_init( } rcl_arguments_t * global_args = NULL; if (node_options->use_global_arguments) { - global_args = rcl_get_global_arguments(); + global_args = &(node->context->global_arguments); } ret = rcl_remap_service_name( &(node_options->arguments), global_args, expanded_service_name, @@ -204,7 +204,7 @@ rcl_service_fini(rcl_service_t * service, rcl_node_t * node) { RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing service"); RCL_CHECK_ARGUMENT_FOR_NULL(service, RCL_RET_SERVICE_INVALID); - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return RCL_RET_NODE_INVALID; // error already set } diff --git a/rcl/src/rcl/subscription.c b/rcl/src/rcl/subscription.c index a78bd6812..1d8762d55 100644 --- a/rcl/src/rcl/subscription.c +++ b/rcl/src/rcl/subscription.c @@ -127,7 +127,7 @@ rcl_subscription_init( } rcl_arguments_t * global_args = NULL; if (node_options->use_global_arguments) { - global_args = rcl_get_global_arguments(); + global_args = &(node->context->global_arguments); } ret = rcl_remap_topic_name( &(node_options->arguments), global_args, expanded_topic_name, @@ -197,7 +197,7 @@ rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node) RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing subscription"); rcl_ret_t result = RCL_RET_OK; RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_SUBSCRIPTION_INVALID); - if (!rcl_node_is_valid(node)) { + if (!rcl_node_is_valid_except_context(node)) { return RCL_RET_NODE_INVALID; // error already set } if (subscription->impl) { diff --git a/rcl/src/rcl/timer.c b/rcl/src/rcl/timer.c index 9fecdf160..16e4243b6 100644 --- a/rcl/src/rcl/timer.c +++ b/rcl/src/rcl/timer.c @@ -30,6 +30,8 @@ typedef struct rcl_timer_impl_t { // The clock providing time. rcl_clock_t * clock; + // The associated context. + rcl_context_t * context; // A guard condition used to wake a wait set if using ROSTime, else zero initialized. rcl_guard_condition_t guard_condition; // The user supplied callback. @@ -123,6 +125,7 @@ rcl_ret_t rcl_timer_init( rcl_timer_t * timer, rcl_clock_t * clock, + rcl_context_t * context, int64_t period, const rcl_timer_callback_t callback, rcl_allocator_t allocator) @@ -147,10 +150,11 @@ rcl_timer_init( } rcl_timer_impl_t impl; impl.clock = clock; + impl.context = context; impl.guard_condition = rcl_get_zero_initialized_guard_condition(); if (RCL_ROS_TIME == impl.clock->type) { rcl_guard_condition_options_t options = rcl_guard_condition_get_default_options(); - rcl_ret_t ret = rcl_guard_condition_init(&(impl.guard_condition), options); + rcl_ret_t ret = rcl_guard_condition_init(&(impl.guard_condition), context, options); if (RCL_RET_OK != ret) { return ret; } diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 50ce76904..0ac72b187 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -61,6 +61,7 @@ function(test_target_function) rcl_add_custom_gtest(test_get_node_names${target_suffix} SRCS rcl/test_get_node_names.cpp + INCLUDE_DIRS ${osrf_testing_tools_cpp_INCLUDE_DIRS} ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} @@ -111,8 +112,8 @@ function(test_target_function) AMENT_DEPENDENCIES ${rmw_implementation} "test_msgs" ) - rcl_add_custom_gtest(test_rcl${target_suffix} - SRCS rcl/test_rcl.cpp + rcl_add_custom_gtest(test_init${target_suffix} + SRCS rcl/test_init.cpp ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools diff --git a/rcl/test/rcl/arg_macros.hpp b/rcl/test/rcl/arg_macros.hpp index 8dfc48588..f29621bdb 100644 --- a/rcl/test/rcl/arg_macros.hpp +++ b/rcl/test/rcl/arg_macros.hpp @@ -15,12 +15,12 @@ #ifndef RCL__ARG_MACROS_HPP_ #define RCL__ARG_MACROS_HPP_ +#include "osrf_testing_tools_cpp/scope_exit.hpp" + #include "rcl/error_handling.h" #include "rcl/rcl.h" #include "rcutils/strdup.h" -#include "osrf_testing_tools_cpp/scope_exit.hpp" - /// Helper to get around non-const args passed to rcl_init(). char ** copy_args(int argc, const char ** args) @@ -45,17 +45,22 @@ destroy_args(int argc, char ** args) } #define SCOPE_GLOBAL_ARGS(argc, argv, ...) \ + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); \ + ASSERT_EQ(RCL_RET_OK, rcl_init_options_init(&init_options, rcl_get_default_allocator())) \ + << rcl_get_error_string().str; \ + rcl_context_t context = rcl_get_zero_initialized_context(); \ { \ const char * const_argv[] = {__VA_ARGS__}; \ argc = (sizeof(const_argv) / sizeof(const char *)); \ argv = copy_args(argc, const_argv); \ - rcl_ret_t ret = rcl_init(argc, argv, rcl_get_default_allocator()); \ + rcl_ret_t ret = rcl_init(argc, argv, &init_options, &context); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \ } \ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ \ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; \ destroy_args(argc, argv); \ - rcl_ret_t ret = rcl_shutdown(); \ - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \ + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)) << rcl_get_error_string().str; \ + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)) << rcl_get_error_string().str; \ }) #define SCOPE_ARGS(local_arguments, ...) \ diff --git a/rcl/test/rcl/client_fixture.cpp b/rcl/test/rcl/client_fixture.cpp index f0a56dab7..7e2a081f5 100644 --- a/rcl/test/rcl/client_fixture.cpp +++ b/rcl/test/rcl/client_fixture.cpp @@ -108,15 +108,36 @@ int main(int argc, char ** argv) { int main_ret = 0; { - if (rcl_init(argc, argv, rcl_get_default_allocator()) != RCL_RET_OK) { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + if (RCL_RET_OK != ret) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in rcl init options init: %s", rcl_get_error_string().str); + return -1; + } + rcl_context_t context = rcl_get_zero_initialized_context(); + if (rcl_init(argc, argv, &init_options, &context) != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in rcl init: %s", rcl_get_error_string().str); return -1; } + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_shutdown(&context) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error shutting down rcl: %s", rcl_get_error_string().str); + main_ret = -1; + } + if (rcl_context_fini(&context) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error finalizing rcl context: %s", rcl_get_error_string().str); + main_ret = -1; + } + }); + ret = rcl_init_options_fini(&init_options); rcl_node_t node = rcl_get_zero_initialized_node(); const char * name = "client_fixture_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - if (rcl_node_init(&node, name, "", &node_options) != RCL_RET_OK) { + if (rcl_node_init(&node, name, "", &context, &node_options) != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string().str); return -1; @@ -135,7 +156,7 @@ int main(int argc, char ** argv) rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_options_t client_options = rcl_client_get_default_options(); - rcl_ret_t ret = rcl_client_init(&client, &node, ts, service_name, &client_options); + ret = rcl_client_init(&client, &node, ts, service_name, &client_options); if (ret != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in client init: %s", rcl_get_error_string().str); diff --git a/rcl/test/rcl/service_fixture.cpp b/rcl/test/rcl/service_fixture.cpp index 58d128064..87eb4f17d 100644 --- a/rcl/test/rcl/service_fixture.cpp +++ b/rcl/test/rcl/service_fixture.cpp @@ -81,15 +81,36 @@ int main(int argc, char ** argv) { int main_ret = 0; { - if (rcl_init(argc, argv, rcl_get_default_allocator()) != RCL_RET_OK) { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + if (RCL_RET_OK != ret) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error in rcl init options init: %s", rcl_get_error_string().str); + return -1; + } + rcl_context_t context = rcl_get_zero_initialized_context(); + if (rcl_init(argc, argv, &init_options, &context) != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in rcl init: %s", rcl_get_error_string().str); return -1; } + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + if (rcl_shutdown(&context) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error shutting down rcl: %s", rcl_get_error_string().str); + main_ret = -1; + } + if (rcl_context_fini(&context) != RCL_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + ROS_PACKAGE_NAME, "Error finalizing rcl context: %s", rcl_get_error_string().str); + main_ret = -1; + } + }); + ret = rcl_init_options_fini(&init_options); rcl_node_t node = rcl_get_zero_initialized_node(); const char * name = "service_fixture_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - if (rcl_node_init(&node, name, "", &node_options) != RCL_RET_OK) { + if (rcl_node_init(&node, name, "", &context, &node_options) != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string().str); return -1; @@ -108,7 +129,7 @@ int main(int argc, char ** argv) rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_options_t service_options = rcl_service_get_default_options(); - rcl_ret_t ret = rcl_service_init(&service, &node, ts, service_name, &service_options); + ret = rcl_service_init(&service, &node, ts, service_name, &service_options); if (ret != RCL_RET_OK) { RCUTILS_LOG_ERROR_NAMED( ROS_PACKAGE_NAME, "Error in service init: %s", rcl_get_error_string().str); diff --git a/rcl/test/rcl/test_client.cpp b/rcl/test/rcl/test_client.cpp index 907d0f9b0..3fb49a7d5 100644 --- a/rcl/test/rcl/test_client.cpp +++ b/rcl/test/rcl/test_client.cpp @@ -28,17 +28,28 @@ class TestClientFixture : public ::testing::Test { public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); const char * name = "test_client_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -47,7 +58,8 @@ class TestClientFixture : public ::testing::Test rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; diff --git a/rcl/test/rcl/test_count_matched.cpp b/rcl/test/rcl/test_count_matched.cpp index dbfdfb67f..63eb15fca 100644 --- a/rcl/test/rcl/test_count_matched.cpp +++ b/rcl/test/rcl/test_count_matched.cpp @@ -99,18 +99,24 @@ class CLASSNAME (TestCountFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: rcl_node_t * node_ptr; + rcl_context_t * context_ptr; rcl_wait_set_t * wait_set_ptr; void SetUp() { rcl_ret_t ret; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); const char * name = "test_count_node"; - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->wait_set_ptr = new rcl_wait_set_t; @@ -130,7 +136,11 @@ class CLASSNAME (TestCountFixture, RMW_IMPLEMENTATION) : public ::testing::Test delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; diff --git a/rcl/test/rcl/test_get_node_names.cpp b/rcl/test/rcl/test_get_node_names.cpp index d29035cd5..d17d74832 100644 --- a/rcl/test/rcl/test_get_node_names.cpp +++ b/rcl/test/rcl/test_get_node_names.cpp @@ -21,6 +21,7 @@ #include "rcutils/types.h" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/graph.h" #include "rcl/rcl.h" #include "rmw/rmw.h" @@ -47,14 +48,26 @@ class CLASSNAME (TestGetNodeNames, RMW_IMPLEMENTATION) : public ::testing::Test }; TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) { - auto ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_ret_t ret; + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_shutdown(&context)) << rcl_get_error_string().str; + EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&context)) << rcl_get_error_string().str; + }); auto node1_ptr = new rcl_node_t; *node1_ptr = rcl_get_zero_initialized_node(); const char * node1_name = "node1"; const char * node1_namespace = "/"; rcl_node_options_t node1_options = rcl_node_get_default_options(); - ret = rcl_node_init(node1_ptr, node1_name, node1_namespace, &node1_options); + ret = rcl_node_init(node1_ptr, node1_name, node1_namespace, &context, &node1_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; auto node2_ptr = new rcl_node_t; @@ -62,7 +75,7 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) const char * node2_name = "node2"; const char * node2_namespace = "/"; rcl_node_options_t node2_options = rcl_node_get_default_options(); - ret = rcl_node_init(node2_ptr, node2_name, node2_namespace, &node2_options); + ret = rcl_node_init(node2_ptr, node2_name, node2_namespace, &context, &node2_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; auto node3_ptr = new rcl_node_t; @@ -70,7 +83,7 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) const char * node3_name = "node3"; const char * node3_namespace = "/ns"; rcl_node_options_t node3_options = rcl_node_get_default_options(); - ret = rcl_node_init(node3_ptr, node3_name, node3_namespace, &node3_options); + ret = rcl_node_init(node3_ptr, node3_name, node3_namespace, &context, &node3_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; auto node4_ptr = new rcl_node_t; @@ -78,7 +91,7 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) const char * node4_name = "node2"; const char * node4_namespace = "/ns/ns"; rcl_node_options_t node4_options = rcl_node_get_default_options(); - ret = rcl_node_init(node4_ptr, node4_name, node4_namespace, &node4_options); + ret = rcl_node_init(node4_ptr, node4_name, node4_namespace, &context, &node4_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; std::this_thread::sleep_for(1s); @@ -126,7 +139,4 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) ret = rcl_node_fini(node4_ptr); delete node4_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - - ret = rcl_shutdown(); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index fcddf7768..c7e2610da 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -51,29 +51,42 @@ bool is_connext = class CLASSNAME (TestGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: + rcl_context_t * old_context_ptr; + rcl_context_t * context_ptr; rcl_node_t * old_node_ptr; rcl_node_t * node_ptr; rcl_wait_set_t * wait_set_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->old_context_ptr = new rcl_context_t; + *this->old_context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->old_context_ptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->old_node_ptr = new rcl_node_t; *this->old_node_ptr = rcl_get_zero_initialized_node(); const char * old_name = "old_node_name"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->old_node_ptr, old_name, "", &node_options); + ret = rcl_node_init(this->old_node_ptr, old_name, "", this->old_context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); // after this, the old_node_ptr should be invalid + ret = rcl_shutdown(this->old_context_ptr); // after this, the old_node_ptr should be invalid EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); const char * name = "test_graph_node"; - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->wait_set_ptr = new rcl_wait_set_t; @@ -96,8 +109,14 @@ class CLASSNAME (TestGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + delete this->context_ptr; + ret = rcl_context_fini(this->old_context_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + delete this->old_context_ptr; } }; diff --git a/rcl/test/rcl/test_guard_condition.cpp b/rcl/test/rcl/test_guard_condition.cpp index 3abe6efbb..312ffb770 100644 --- a/rcl/test/rcl/test_guard_condition.cpp +++ b/rcl/test/rcl/test_guard_condition.cpp @@ -63,13 +63,21 @@ TEST_F( rcl_ret_t ret; // Initialize rcl with rcl_init(). - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); + ASSERT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)); + }); + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; // Setup automatic rcl_shutdown() OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); }); // Create a zero initialized guard_condition (but not initialized). @@ -78,7 +86,7 @@ TEST_F( // Create a normal guard_condition. rcl_guard_condition_options_t default_options = rcl_guard_condition_get_default_options(); rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); - ret = rcl_guard_condition_init(&guard_condition, default_options); + ret = rcl_guard_condition_init(&guard_condition, &context, default_options); ASSERT_EQ(RCL_RET_OK, ret); // Setup automatic finalization of guard condition. OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ @@ -121,22 +129,34 @@ TEST_F( TEST_F( CLASSNAME(TestGuardConditionFixture, RMW_IMPLEMENTATION), test_rcl_guard_condition_life_cycle) { rcl_ret_t ret; + rcl_context_t context = rcl_get_zero_initialized_context(); rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition(); rcl_guard_condition_options_t default_options = rcl_guard_condition_get_default_options(); // Trying to init before rcl_init() should fail. - ret = rcl_guard_condition_init(&guard_condition, default_options); + ret = rcl_guard_condition_init(&guard_condition, &context, default_options); ASSERT_EQ(RCL_RET_NOT_INIT, ret) << "Expected RCL_RET_NOT_INIT"; ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); // Initialize rcl with rcl_init(). - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); + osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); + ASSERT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)); + }); + ret = rcl_init(0, nullptr, &init_options, &context); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); }); // Try invalid arguments. - ret = rcl_guard_condition_init(nullptr, default_options); + ret = rcl_guard_condition_init(nullptr, &context, default_options); + ASSERT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT"; + ASSERT_TRUE(rcl_error_is_set()); + rcl_reset_error(); + // Now with nullptr for context. + ret = rcl_guard_condition_init(&guard_condition, nullptr, default_options); ASSERT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT"; ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -146,7 +166,7 @@ TEST_F( options_with_invalid_allocator.allocator.allocate = nullptr; options_with_invalid_allocator.allocator.deallocate = nullptr; options_with_invalid_allocator.allocator.reallocate = nullptr; - ret = rcl_guard_condition_init(&guard_condition, options_with_invalid_allocator); + ret = rcl_guard_condition_init(&guard_condition, &context, options_with_invalid_allocator); ASSERT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT"; ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -156,12 +176,10 @@ TEST_F( options_with_failing_allocator.allocator.allocate = failing_malloc; options_with_failing_allocator.allocator.reallocate = failing_realloc; options_with_failing_allocator.allocator.zero_allocate = failing_calloc; - ret = rcl_guard_condition_init(&guard_condition, options_with_failing_allocator); + ret = rcl_guard_condition_init(&guard_condition, &context, options_with_failing_allocator); ASSERT_EQ(RCL_RET_BAD_ALLOC, ret) << "Expected RCL_RET_BAD_ALLOC"; - // The error will not be set because the allocator will not work. - // It should, however, print a message to the screen and get the bad alloc ret code. - // ASSERT_TRUE(rcl_error_is_set()); - // rcl_reset_error(); + ASSERT_TRUE(rcl_error_is_set()); + rcl_reset_error(); // Try fini with invalid arguments. ret = rcl_guard_condition_fini(nullptr); @@ -172,14 +190,14 @@ TEST_F( ret = rcl_guard_condition_fini(&guard_condition); EXPECT_EQ(RCL_RET_OK, ret); // Try a normal init and fini. - ret = rcl_guard_condition_init(&guard_condition, default_options); + ret = rcl_guard_condition_init(&guard_condition, &context, default_options); EXPECT_EQ(RCL_RET_OK, ret); ret = rcl_guard_condition_fini(&guard_condition); EXPECT_EQ(RCL_RET_OK, ret); // Try repeated init and fini calls. - ret = rcl_guard_condition_init(&guard_condition, default_options); + ret = rcl_guard_condition_init(&guard_condition, &context, default_options); EXPECT_EQ(RCL_RET_OK, ret); - ret = rcl_guard_condition_init(&guard_condition, default_options); + ret = rcl_guard_condition_init(&guard_condition, &context, default_options); EXPECT_EQ(RCL_RET_ALREADY_INIT, ret) << "Expected RCL_RET_ALREADY_INIT"; ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); diff --git a/rcl/test/rcl/test_rcl.cpp b/rcl/test/rcl/test_init.cpp similarity index 55% rename from rcl/test/rcl/test_rcl.cpp rename to rcl/test/rcl/test_init.cpp index bb82a2bd7..904350107 100644 --- a/rcl/test/rcl/test_rcl.cpp +++ b/rcl/test/rcl/test_init.cpp @@ -18,10 +18,13 @@ #include "./failing_allocator_functions.hpp" #include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "rcl/error_handling.h" #include "rcutils/format_string.h" #include "rcutils/snprintf.h" +#include "../src/rcl/init_options_impl.h" + #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX # define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) @@ -99,29 +102,32 @@ struct FakeTestArgv */ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_and_ok_and_shutdown) { rcl_ret_t ret; + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_context_t context = rcl_get_zero_initialized_context(); // A shutdown before any init has been called should fail. - ret = rcl_shutdown(); - EXPECT_EQ(RCL_RET_NOT_INIT, ret); + ret = rcl_shutdown(&context); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); - ASSERT_FALSE(rcl_ok()); + ASSERT_FALSE(rcl_context_is_valid(&context)); // If argc is not 0, but argv is, it should be an invalid argument. - ret = rcl_init(42, nullptr, rcl_get_default_allocator()); + ret = rcl_init(42, nullptr, &init_options, &context); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); - ASSERT_FALSE(rcl_ok()); + ASSERT_FALSE(rcl_context_is_valid(&context)); // If either the allocate or deallocate function pointers are not set, it should be invalid arg. - rcl_allocator_t invalid_allocator = rcl_get_default_allocator(); - invalid_allocator.allocate = nullptr; - ret = rcl_init(0, nullptr, invalid_allocator); + init_options.impl->allocator.allocate = nullptr; + ret = rcl_init(0, nullptr, &init_options, &context); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); - ASSERT_FALSE(rcl_ok()); - invalid_allocator.allocate = rcl_get_default_allocator().allocate; - invalid_allocator.deallocate = nullptr; - ret = rcl_init(0, nullptr, invalid_allocator); + ASSERT_FALSE(rcl_context_is_valid(&context)); + init_options.impl->allocator.allocate = rcl_get_default_allocator().allocate; + init_options.impl->allocator.deallocate = nullptr; + ret = rcl_init(0, nullptr, &init_options, &context); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); - ASSERT_FALSE(rcl_ok()); + ASSERT_FALSE(rcl_context_is_valid(&context)); // If the malloc call fails (with some valid arguments to copy), it should be a bad alloc. { FakeTestArgv test_args; @@ -129,97 +135,127 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_and_ok_and_s failing_allocator.allocate = failing_malloc; failing_allocator.reallocate = failing_realloc; failing_allocator.zero_allocate = failing_calloc; - ret = rcl_init(test_args.argc, test_args.argv, failing_allocator); + init_options.impl->allocator = failing_allocator; + ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret); rcl_reset_error(); - ASSERT_FALSE(rcl_ok()); + ASSERT_FALSE(rcl_context_is_valid(&context)); } + init_options.impl->allocator = rcl_get_default_allocator(); // If argc is 0 and argv is nullptr and the allocator is valid, it should succeed. - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + ret = rcl_init(0, nullptr, &init_options, &context); EXPECT_EQ(RCL_RET_OK, ret); - ASSERT_TRUE(rcl_ok()); + ASSERT_TRUE(rcl_context_is_valid(&context)); // Then shutdown should work. - ret = rcl_shutdown(); + ret = rcl_shutdown(&context); EXPECT_EQ(ret, RCL_RET_OK); - ASSERT_FALSE(rcl_ok()); + ASSERT_FALSE(rcl_context_is_valid(&context)); + ret = rcl_context_fini(&context); + EXPECT_EQ(ret, RCL_RET_OK); + context = rcl_get_zero_initialized_context(); // Valid argc/argv values and a valid allocator should succeed. { FakeTestArgv test_args; - ret = rcl_init(test_args.argc, test_args.argv, rcl_get_default_allocator()); + ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context); EXPECT_EQ(RCL_RET_OK, ret); - ASSERT_TRUE(rcl_ok()); + ASSERT_TRUE(rcl_context_is_valid(&context)); } // Then shutdown should work. - ret = rcl_shutdown(); - EXPECT_EQ(RCL_RET_OK, ret); - ASSERT_FALSE(rcl_ok()); + ret = rcl_shutdown(&context); + EXPECT_EQ(ret, RCL_RET_OK); + ASSERT_FALSE(rcl_context_is_valid(&context)); + // Then a repeated shutdown should fail. + ret = rcl_shutdown(&context); + EXPECT_EQ(ret, RCL_RET_ALREADY_SHUTDOWN); + ASSERT_FALSE(rcl_context_is_valid(&context)); + rcl_reset_error(); + ret = rcl_context_fini(&context); + EXPECT_EQ(ret, RCL_RET_OK); + context = rcl_get_zero_initialized_context(); // A repeat call to shutdown should not work. - ret = rcl_shutdown(); - EXPECT_EQ(RCL_RET_NOT_INIT, ret); + ret = rcl_shutdown(&context); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); - ASSERT_FALSE(rcl_ok()); + ASSERT_FALSE(rcl_context_is_valid(&context)); // Repeat, but valid, calls to rcl_init() should fail. { FakeTestArgv test_args; - ret = rcl_init(test_args.argc, test_args.argv, rcl_get_default_allocator()); + ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context); EXPECT_EQ(RCL_RET_OK, ret); - ASSERT_TRUE(rcl_ok()); - ret = rcl_init(test_args.argc, test_args.argv, rcl_get_default_allocator()); + ASSERT_TRUE(rcl_context_is_valid(&context)); + ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context); EXPECT_EQ(RCL_RET_ALREADY_INIT, ret); rcl_reset_error(); - ASSERT_TRUE(rcl_ok()); + ASSERT_TRUE(rcl_context_is_valid(&context)); } // But shutdown should still work. - ret = rcl_shutdown(); + ret = rcl_shutdown(&context); + EXPECT_EQ(ret, RCL_RET_OK); + ASSERT_FALSE(rcl_context_is_valid(&context)); + ret = rcl_context_fini(&context); EXPECT_EQ(ret, RCL_RET_OK); - ASSERT_FALSE(rcl_ok()); + context = rcl_get_zero_initialized_context(); } /* Tests the rcl_get_instance_id() and rcl_ok() functions. */ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_get_instance_id_and_ok) { rcl_ret_t ret; + rcl_context_t context = rcl_get_zero_initialized_context(); // Instance id should be 0 before rcl_init(). - EXPECT_EQ(0u, rcl_get_instance_id()); - ASSERT_FALSE(rcl_ok()); + EXPECT_EQ(0u, rcl_context_get_instance_id(&context)); + ASSERT_FALSE(rcl_context_is_valid(&context)); // It should still return 0 after an invalid init. - ret = rcl_init(1, nullptr, rcl_get_default_allocator()); + ret = rcl_init(1, nullptr, nullptr, &context); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); - EXPECT_EQ(0u, rcl_get_instance_id()); - ASSERT_FALSE(rcl_ok()); + EXPECT_EQ(0u, rcl_context_get_instance_id(&context)); + ASSERT_FALSE(rcl_context_is_valid(&context)); + rcl_reset_error(); // A non-zero instance id should be returned after a valid init. + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); { FakeTestArgv test_args; - ret = rcl_init(test_args.argc, test_args.argv, rcl_get_default_allocator()); + ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context); EXPECT_EQ(RCL_RET_OK, ret); - ASSERT_TRUE(rcl_ok()); + ASSERT_TRUE(rcl_context_is_valid(&context)); } // And it should be allocation free. uint64_t first_instance_id; EXPECT_NO_MEMORY_OPERATIONS({ - first_instance_id = rcl_get_instance_id(); + first_instance_id = rcl_context_get_instance_id(&context); }); EXPECT_NE(0u, first_instance_id); - EXPECT_EQ(first_instance_id, rcl_get_instance_id()); // Repeat calls should return the same. - EXPECT_EQ(true, rcl_ok()); + // Repeat calls should return the same. + EXPECT_EQ(first_instance_id, rcl_context_get_instance_id(&context)); + EXPECT_EQ(true, rcl_context_is_valid(&context)); // Calling after a shutdown should return 0. - ret = rcl_shutdown(); + ret = rcl_shutdown(&context); + EXPECT_EQ(ret, RCL_RET_OK); + EXPECT_EQ(0u, rcl_context_get_instance_id(&context)); + ASSERT_FALSE(rcl_context_is_valid(&context)); + ret = rcl_context_fini(&context); EXPECT_EQ(ret, RCL_RET_OK); - EXPECT_EQ(0u, rcl_get_instance_id()); - ASSERT_FALSE(rcl_ok()); + context = rcl_get_zero_initialized_context(); // It should return a different value after another valid init. { FakeTestArgv test_args; - ret = rcl_init(test_args.argc, test_args.argv, rcl_get_default_allocator()); + ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context); EXPECT_EQ(RCL_RET_OK, ret); - ASSERT_TRUE(rcl_ok()); + ASSERT_TRUE(rcl_context_is_valid(&context)); } - EXPECT_NE(0u, rcl_get_instance_id()); - EXPECT_NE(first_instance_id, rcl_get_instance_id()); - ASSERT_TRUE(rcl_ok()); + EXPECT_NE(0u, rcl_context_get_instance_id(&context)); + EXPECT_NE(first_instance_id, rcl_context_get_instance_id(&context)); + ASSERT_TRUE(rcl_context_is_valid(&context)); // Shutting down a second time should result in 0 again. - ret = rcl_shutdown(); + ret = rcl_shutdown(&context); + EXPECT_EQ(ret, RCL_RET_OK); + EXPECT_EQ(0u, rcl_context_get_instance_id(&context)); + ASSERT_FALSE(rcl_context_is_valid(&context)); + ret = rcl_context_fini(&context); EXPECT_EQ(ret, RCL_RET_OK); - EXPECT_EQ(0u, rcl_get_instance_id()); - ASSERT_FALSE(rcl_ok()); } diff --git a/rcl/test/rcl/test_node.cpp b/rcl/test/rcl/test_node.cpp index 6236cad98..0a5d2f95a 100644 --- a/rcl/test/rcl/test_node.cpp +++ b/rcl/test/rcl/test_node.cpp @@ -86,7 +86,14 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) osrf_testing_tools_cpp::memory_tools::enable_monitoring_in_all_threads(); rcl_ret_t ret; // Initialize rcl with rcl_init(). - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + rcl_context_t invalid_context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &invalid_context); ASSERT_EQ(RCL_RET_OK, ret); // Shutdown later after invalid node. // Create an invalid node (rcl_shutdown). rcl_node_t invalid_node = rcl_get_zero_initialized_node(); @@ -94,13 +101,13 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) const char * namespace_ = "/ns"; rcl_node_options_t default_options = rcl_node_get_default_options(); default_options.domain_id = 42; // Set the domain id to something explicit. - ret = rcl_node_init(&invalid_node, name, namespace_, &default_options); + ret = rcl_node_init(&invalid_node, name, namespace_, &invalid_context, &default_options); if (is_windows && is_opensplice) { // On Windows with OpenSplice, setting the domain id is not expected to work. ASSERT_NE(RCL_RET_OK, ret); // So retry with the default domain id setting (uses the environment as is). default_options.domain_id = rcl_node_get_default_options().domain_id; - ret = rcl_node_init(&invalid_node, name, namespace_, &default_options); + ret = rcl_node_init(&invalid_node, name, namespace_, &invalid_context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); } else { // This is the normal check (not windows and windows if not opensplice) @@ -111,20 +118,24 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) rcl_ret_t ret = rcl_node_fini(&invalid_node); EXPECT_EQ(RCL_RET_OK, ret); }); - ret = rcl_shutdown(); // Shutdown to invalidate the node. + ret = rcl_shutdown(&invalid_context); // Shutdown to invalidate the node. ASSERT_EQ(RCL_RET_OK, ret); - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&invalid_context)) << rcl_get_error_string().str; + }); + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); }); // Create a zero init node. rcl_node_t zero_node = rcl_get_zero_initialized_node(); // Create a normal node. rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, namespace_, &default_options); + ret = rcl_node_init(&node, name, namespace_, &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ osrf_testing_tools_cpp::memory_tools::disable_monitoring_in_all_threads(); @@ -139,9 +150,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) is_valid = rcl_node_is_valid(&zero_node); EXPECT_FALSE(is_valid); rcl_reset_error(); + + // invalid node will be true for rcl_node_is_valid_except_context, but false for valid only + is_valid = rcl_node_is_valid_except_context(&invalid_node); + EXPECT_TRUE(is_valid); + rcl_reset_error(); is_valid = rcl_node_is_valid(&invalid_node); EXPECT_FALSE(is_valid); rcl_reset_error(); + is_valid = rcl_node_is_valid(&node); EXPECT_TRUE(is_valid); rcl_reset_error(); @@ -154,14 +171,17 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(nullptr, actual_node_name); rcl_reset_error(); actual_node_name = rcl_node_get_name(&invalid_node); - EXPECT_EQ(nullptr, actual_node_name); + EXPECT_TRUE(actual_node_name ? true : false); + if (actual_node_name) { + EXPECT_STREQ(name, actual_node_name); + } rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ actual_node_name = rcl_node_get_name(&node); }); EXPECT_TRUE(actual_node_name ? true : false); if (actual_node_name) { - EXPECT_EQ(std::string(name), std::string(actual_node_name)); + EXPECT_STREQ(name, actual_node_name); } // Test rcl_node_get_namespace(). const char * actual_node_namespace; @@ -172,7 +192,10 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(nullptr, actual_node_namespace); rcl_reset_error(); actual_node_namespace = rcl_node_get_namespace(&invalid_node); - EXPECT_EQ(nullptr, actual_node_namespace); + EXPECT_TRUE(actual_node_namespace ? true : false); + if (actual_node_namespace) { + EXPECT_STREQ(namespace_, actual_node_namespace); + } rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ actual_node_namespace = rcl_node_get_namespace(&node); @@ -190,7 +213,10 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(nullptr, actual_node_logger_name); rcl_reset_error(); actual_node_logger_name = rcl_node_get_logger_name(&invalid_node); - EXPECT_EQ(nullptr, actual_node_logger_name); + EXPECT_TRUE(actual_node_logger_name ? true : false); + if (actual_node_logger_name) { + EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name)); + } rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ actual_node_logger_name = rcl_node_get_logger_name(&node); @@ -208,7 +234,11 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(nullptr, actual_options); rcl_reset_error(); actual_options = rcl_node_get_options(&invalid_node); - EXPECT_EQ(nullptr, actual_options); + EXPECT_NE(nullptr, actual_options); + if (actual_options) { + EXPECT_EQ(default_options.allocator.allocate, actual_options->allocator.allocate); + EXPECT_EQ(default_options.domain_id, actual_options->domain_id); + } rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ actual_options = rcl_node_get_options(&node); @@ -229,8 +259,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); ret = rcl_node_get_domain_id(&invalid_node, &actual_domain_id); - EXPECT_EQ(RCL_RET_NODE_INVALID, ret); - ASSERT_TRUE(rcl_error_is_set()); + EXPECT_EQ(RCL_RET_OK, ret); rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ ret = rcl_node_get_domain_id(&node, &actual_domain_id); @@ -249,7 +278,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(nullptr, node_handle); rcl_reset_error(); node_handle = rcl_node_get_rmw_handle(&invalid_node); - EXPECT_EQ(nullptr, node_handle); + EXPECT_NE(nullptr, node_handle); rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ node_handle = rcl_node_get_rmw_handle(&node); @@ -264,15 +293,14 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(0u, instance_id); rcl_reset_error(); instance_id = rcl_node_get_rcl_instance_id(&invalid_node); - EXPECT_NE(0u, instance_id); - EXPECT_NE(42u, instance_id); + EXPECT_EQ(0u, instance_id); rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ instance_id = rcl_node_get_rcl_instance_id(&node); }); EXPECT_NE(0u, instance_id); // Test rcl_node_get_graph_guard_condition - const rcl_guard_condition_t * graph_guard_condition = nullptr; + const rcl_guard_condition_t * graph_guard_condition; graph_guard_condition = rcl_node_get_graph_guard_condition(nullptr); EXPECT_EQ(nullptr, graph_guard_condition); rcl_reset_error(); @@ -280,7 +308,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) EXPECT_EQ(nullptr, graph_guard_condition); rcl_reset_error(); graph_guard_condition = rcl_node_get_graph_guard_condition(&invalid_node); - EXPECT_EQ(nullptr, graph_guard_condition); + EXPECT_NE(nullptr, graph_guard_condition); rcl_reset_error(); EXPECT_NO_MEMORY_OPERATIONS({ graph_guard_condition = rcl_node_get_graph_guard_condition(&node); @@ -292,36 +320,47 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors) */ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) { rcl_ret_t ret; + rcl_context_t context = rcl_get_zero_initialized_context(); rcl_node_t node = rcl_get_zero_initialized_node(); const char * name = "test_rcl_node_life_cycle_node"; const char * namespace_ = "/ns"; rcl_node_options_t default_options = rcl_node_get_default_options(); // Trying to init before rcl_init() should fail. - ret = rcl_node_init(&node, name, "", &default_options); + ret = rcl_node_init(&node, name, "", &context, &default_options); ASSERT_EQ(RCL_RET_NOT_INIT, ret) << "Expected RCL_RET_NOT_INIT"; ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); // Initialize rcl with rcl_init(). - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); }); // Try invalid arguments. - ret = rcl_node_init(nullptr, name, namespace_, &default_options); + ret = rcl_node_init(nullptr, name, namespace_, &context, &default_options); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); - ret = rcl_node_init(&node, nullptr, namespace_, &default_options); + ret = rcl_node_init(&node, nullptr, namespace_, &context, &default_options); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); - ret = rcl_node_init(&node, name, nullptr, &default_options); + ret = rcl_node_init(&node, name, nullptr, &context, &default_options); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); - ret = rcl_node_init(&node, name, namespace_, nullptr); + ret = rcl_node_init(&node, name, namespace_, nullptr, &default_options); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + ASSERT_TRUE(rcl_error_is_set()); + rcl_reset_error(); + ret = rcl_node_init(&node, name, namespace_, &context, nullptr); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -330,7 +369,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) options_with_invalid_allocator.allocator.allocate = nullptr; options_with_invalid_allocator.allocator.deallocate = nullptr; options_with_invalid_allocator.allocator.reallocate = nullptr; - ret = rcl_node_init(&node, name, namespace_, &options_with_invalid_allocator); + ret = rcl_node_init(&node, name, namespace_, &context, &options_with_invalid_allocator); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT"; ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -338,12 +377,10 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) rcl_node_options_t options_with_failing_allocator = rcl_node_get_default_options(); options_with_failing_allocator.allocator.allocate = failing_malloc; options_with_failing_allocator.allocator.reallocate = failing_realloc; - ret = rcl_node_init(&node, name, namespace_, &options_with_failing_allocator); + ret = rcl_node_init(&node, name, namespace_, &context, &options_with_failing_allocator); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << "Expected RCL_RET_BAD_ALLOC"; - // The error will not be set because the allocator will not work. - // It should, however, print a message to the screen and get the bad alloc ret code. - // ASSERT_TRUE(rcl_error_is_set()); - // rcl_reset_error(); + ASSERT_TRUE(rcl_error_is_set()); + rcl_reset_error(); // Try fini with invalid arguments. ret = rcl_node_fini(nullptr); @@ -354,14 +391,14 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) ret = rcl_node_fini(&node); EXPECT_EQ(RCL_RET_OK, ret); // Try a normal init and fini. - ret = rcl_node_init(&node, name, namespace_, &default_options); + ret = rcl_node_init(&node, name, namespace_, &context, &default_options); EXPECT_EQ(RCL_RET_OK, ret); ret = rcl_node_fini(&node); EXPECT_EQ(RCL_RET_OK, ret); // Try repeated init and fini calls. - ret = rcl_node_init(&node, name, namespace_, &default_options); + ret = rcl_node_init(&node, name, namespace_, &context, &default_options); EXPECT_EQ(RCL_RET_OK, ret); - ret = rcl_node_init(&node, name, namespace_, &default_options); + ret = rcl_node_init(&node, name, namespace_, &context, &default_options); EXPECT_EQ(RCL_RET_ALREADY_INIT, ret) << "Expected RCL_RET_ALREADY_INIT"; ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -372,7 +409,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle) // Try with a specific domain id. rcl_node_options_t options_with_custom_domain_id = rcl_node_get_default_options(); options_with_custom_domain_id.domain_id = 42; - ret = rcl_node_init(&node, name, namespace_, &options_with_custom_domain_id); + ret = rcl_node_init(&node, name, namespace_, &context, &options_with_custom_domain_id); if (is_windows && is_opensplice) { // A custom domain id is not expected to work on Windows with Opensplice. EXPECT_NE(RCL_RET_OK, ret); @@ -390,11 +427,18 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri rcl_ret_t ret; // Initialize rcl with rcl_init(). - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); }); const char * namespace_ = "/ns"; @@ -403,7 +447,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri // First do a normal node name. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, "my_node_42", namespace_, &default_options); + ret = rcl_node_init(&node, "my_node_42", namespace_, &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_node_fini(&node); EXPECT_EQ(RCL_RET_OK, ret); @@ -412,7 +456,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri // Node name with invalid characters. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, "my_node_42$", namespace_, &default_options); + ret = rcl_node_init(&node, "my_node_42$", namespace_, &context, &default_options); ASSERT_EQ(RCL_RET_NODE_INVALID_NAME, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -423,7 +467,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri // Node name with /, which is valid in a topic, but not a node name. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, "my/node_42", namespace_, &default_options); + ret = rcl_node_init(&node, "my/node_42", namespace_, &context, &default_options); ASSERT_EQ(RCL_RET_NODE_INVALID_NAME, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -434,7 +478,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restri // Node name with {}, which is valid in a topic, but not a node name. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, "my_{node}_42", namespace_, &default_options); + ret = rcl_node_init(&node, "my_{node}_42", namespace_, &context, &default_options); ASSERT_EQ(RCL_RET_NODE_INVALID_NAME, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -449,11 +493,18 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r rcl_ret_t ret; // Initialize rcl with rcl_init(). - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); }); const char * name = "node"; @@ -462,7 +513,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r // First do a normal node namespace. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/ns", &default_options); + ret = rcl_node_init(&node, name, "/ns", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_node_fini(&node); EXPECT_EQ(RCL_RET_OK, ret); @@ -471,7 +522,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r // Node namespace which is an empty string, which is also valid. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "", &default_options); + ret = rcl_node_init(&node, name, "", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); ASSERT_STREQ("/", rcl_node_get_namespace(&node)); rcl_ret_t ret = rcl_node_fini(&node); @@ -481,7 +532,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r // Node namespace which is just a forward slash, which is valid. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/", &default_options); + ret = rcl_node_init(&node, name, "/", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); rcl_ret_t ret = rcl_node_fini(&node); EXPECT_EQ(RCL_RET_OK, ret); @@ -490,7 +541,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r // Node namespaces with invalid characters. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/ns/{name}", &default_options); + ret = rcl_node_init(&node, name, "/ns/{name}", &context, &default_options); ASSERT_EQ(RCL_RET_NODE_INVALID_NAMESPACE, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -499,7 +550,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r } { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/~/", &default_options); + ret = rcl_node_init(&node, name, "/~/", &context, &default_options); ASSERT_EQ(RCL_RET_NODE_INVALID_NAMESPACE, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -510,7 +561,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r // Node namespace with a trailing / which is not allowed. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/ns/foo/", &default_options); + ret = rcl_node_init(&node, name, "/ns/foo/", &context, &default_options); ASSERT_EQ(RCL_RET_NODE_INVALID_NAMESPACE, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -521,7 +572,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r // Node namespace which is not absolute, it should get / added automatically. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "ns", &default_options); + ret = rcl_node_init(&node, name, "ns", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); ASSERT_STREQ("/ns", rcl_node_get_namespace(&node)); rcl_ret_t ret = rcl_node_fini(&node); @@ -531,7 +582,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r // Other reasons for being invalid, which are related to being part of a topic. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/starts/with/42number", &default_options); + ret = rcl_node_init(&node, name, "/starts/with/42number", &context, &default_options); ASSERT_EQ(RCL_RET_NODE_INVALID_NAMESPACE, ret); ASSERT_TRUE(rcl_error_is_set()); rcl_reset_error(); @@ -546,11 +597,18 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name rcl_ret_t ret; // Initialize rcl with rcl_init(). - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ - rcl_ret_t ret = rcl_shutdown(); - ASSERT_EQ(RCL_RET_OK, ret); + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); }); const char * name = "node"; @@ -560,7 +618,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name // First do a normal node namespace. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/ns", &default_options); + ret = rcl_node_init(&node, name, "/ns", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); actual_node_logger_name = rcl_node_get_logger_name(&node); EXPECT_TRUE(actual_node_logger_name ? true : false); @@ -574,7 +632,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name // Node namespace that is an empty string. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "", &default_options); + ret = rcl_node_init(&node, name, "", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); actual_node_logger_name = rcl_node_get_logger_name(&node); EXPECT_TRUE(actual_node_logger_name ? true : false); @@ -588,7 +646,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name // Node namespace that is just a forward slash. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/", &default_options); + ret = rcl_node_init(&node, name, "/", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); actual_node_logger_name = rcl_node_get_logger_name(&node); EXPECT_TRUE(actual_node_logger_name ? true : false); @@ -602,7 +660,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name // Node namespace that is not absolute. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "ns", &default_options); + ret = rcl_node_init(&node, name, "ns", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); actual_node_logger_name = rcl_node_get_logger_name(&node); EXPECT_TRUE(actual_node_logger_name ? true : false); @@ -616,7 +674,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name // Nested namespace. { rcl_node_t node = rcl_get_zero_initialized_node(); - ret = rcl_node_init(&node, name, "/ns/sub_1/sub_2", &default_options); + ret = rcl_node_init(&node, name, "/ns/sub_1/sub_2", &context, &default_options); ASSERT_EQ(RCL_RET_OK, ret); actual_node_logger_name = rcl_node_get_logger_name(&node); EXPECT_TRUE(actual_node_logger_name ? true : false); diff --git a/rcl/test/rcl/test_publisher.cpp b/rcl/test/rcl/test_publisher.cpp index cfce023df..94dd8fd6f 100644 --- a/rcl/test/rcl/test_publisher.cpp +++ b/rcl/test/rcl/test_publisher.cpp @@ -34,17 +34,28 @@ class CLASSNAME (TestPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); const char * name = "test_publisher_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -53,7 +64,10 @@ class CLASSNAME (TestPublisherFixture, RMW_IMPLEMENTATION) : public ::testing::T rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; diff --git a/rcl/test/rcl/test_remap_integration.cpp b/rcl/test/rcl/test_remap_integration.cpp index 155da3cad..4ea00fc18 100644 --- a/rcl/test/rcl/test_remap_integration.cpp +++ b/rcl/test/rcl/test_remap_integration.cpp @@ -50,7 +50,9 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_options_t default_options = rcl_node_get_default_options(); - ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/original_ns", &default_options)); + ASSERT_EQ( + RCL_RET_OK, + rcl_node_init(&node, "original_name", "/original_ns", &context, &default_options)); { // Node name gets remapped EXPECT_STREQ("new_name", rcl_node_get_name(&node)); @@ -118,7 +120,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global rcl_node_options_t options = rcl_node_get_default_options(); options.use_global_arguments = false; options.arguments = local_arguments; - ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/original_ns", &options)); + ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/original_ns", &context, &options)); { // Node name does not get remapped EXPECT_STREQ("original_name", rcl_node_get_name(&node)); @@ -187,7 +189,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_options_t options = rcl_node_get_default_options(); options.arguments = local_arguments; - ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/original_ns", &options)); + ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/original_ns", &context, &options)); { // Node name EXPECT_STREQ("local_name", rcl_node_get_name(&node)); @@ -250,7 +252,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_options_t default_options = rcl_node_get_default_options(); - ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/foo", &default_options)); + ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "/foo", &context, &default_options)); { // Publisher topic const rosidl_message_type_support_t * ts = @@ -305,7 +307,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_n rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_options_t default_options = rcl_node_get_default_options(); - ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "", &default_options)); + ASSERT_EQ(RCL_RET_OK, rcl_node_init(&node, "original_name", "", &context, &default_options)); { // Node namespace gets remapped EXPECT_STREQ("/new_ns", rcl_node_get_namespace(&node)); diff --git a/rcl/test/rcl/test_rmw_impl_id_check_exe.cpp b/rcl/test/rcl/test_rmw_impl_id_check_exe.cpp index 59141247b..03bb29230 100644 --- a/rcl/test/rcl/test_rmw_impl_id_check_exe.cpp +++ b/rcl/test/rcl/test_rmw_impl_id_check_exe.cpp @@ -16,7 +16,22 @@ int main(int, char **) { - rcl_ret_t ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + if (ret != RCL_RET_OK) { + return ret; + } + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); + if (ret != RCL_RET_OK) { + return ret; + } + ret = rcl_init_options_fini(&init_options); + ret = rcl_shutdown(&context); + if (ret != RCL_RET_OK) { + return ret; + } + ret = rcl_context_fini(&context); if (ret != RCL_RET_OK) { return ret; } diff --git a/rcl/test/rcl/test_service.cpp b/rcl/test/rcl/test_service.cpp index 9f4459846..8f2942c96 100644 --- a/rcl/test/rcl/test_service.cpp +++ b/rcl/test/rcl/test_service.cpp @@ -37,17 +37,28 @@ class CLASSNAME (TestServiceFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); const char * name = "test_service_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -56,7 +67,10 @@ class CLASSNAME (TestServiceFixture, RMW_IMPLEMENTATION) : public ::testing::Tes rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index d42faaaef..7c8c3f290 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -37,17 +37,28 @@ class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); const char * name = "test_subscription_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -56,7 +67,10 @@ class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; diff --git a/rcl/test/rcl/test_timer.cpp b/rcl/test/rcl/test_timer.cpp index 5248142f6..af5bc0171 100644 --- a/rcl/test/rcl/test_timer.cpp +++ b/rcl/test/rcl/test_timer.cpp @@ -26,17 +26,28 @@ class TestTimerFixture : public ::testing::Test { public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); - const char * name = "test_publisher_node"; + const char * name = "test_timer_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -45,7 +56,10 @@ class TestTimerFixture : public ::testing::Test rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; @@ -61,10 +75,12 @@ TEST_F(TestTimerFixture, test_two_timers) { rcl_timer_t timer = rcl_get_zero_initialized_timer(); rcl_timer_t timer2 = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_timer_init(&timer2, &clock, RCL_MS_TO_NS(20), nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer2, &clock, this->context_ptr, RCL_MS_TO_NS(20), nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); @@ -115,10 +131,12 @@ TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) { rcl_timer_t timer = rcl_get_zero_initialized_timer(); rcl_timer_t timer2 = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_timer_init(&timer2, &clock, RCL_MS_TO_NS(10), nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer2, &clock, this->context_ptr, RCL_MS_TO_NS(10), nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); @@ -168,7 +186,8 @@ TEST_F(TestTimerFixture, test_timer_not_ready) { rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); @@ -212,7 +231,8 @@ TEST_F(TestTimerFixture, test_canceled_timer) { rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, 500, nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, 500, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_timer_cancel(&timer); @@ -264,7 +284,8 @@ TEST_F(TestTimerFixture, test_rostime_time_until_next_call) { ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string().str; rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, sec_5, nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, sec_5, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str; @@ -300,7 +321,8 @@ TEST_F(TestTimerFixture, test_system_time_to_ros_time) { }); rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, sec_5, nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, sec_5, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str; @@ -340,7 +362,8 @@ TEST_F(TestTimerFixture, test_ros_time_to_system_time) { ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string().str; rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, sec_5, nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, sec_5, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str; @@ -383,7 +406,8 @@ TEST_F(TestTimerFixture, test_ros_time_backwards_jump) { ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string().str; rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, sec_5, nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, sec_5, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str; @@ -424,7 +448,8 @@ TEST_F(TestTimerFixture, test_ros_time_wakes_wait) { ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string().str; rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, sec_1, nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, sec_1, nullptr, rcl_get_default_allocator()); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str; diff --git a/rcl/test/rcl/test_wait.cpp b/rcl/test/rcl/test_wait.cpp index b252e1038..8f68935ec 100644 --- a/rcl/test/rcl/test_wait.cpp +++ b/rcl/test/rcl/test_wait.cpp @@ -41,18 +41,27 @@ class CLASSNAME (WaitSetTestFixture, RMW_IMPLEMENTATION) : public ::testing::Test { public: + rcl_context_t * context_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } void TearDown() { - rcl_ret_t ret; - ret = rcl_shutdown(); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + EXPECT_EQ(RCL_RET_OK, rcl_shutdown(this->context_ptr)) << rcl_get_error_string().str; + EXPECT_EQ(RCL_RET_OK, rcl_context_fini(this->context_ptr)) << rcl_get_error_string().str; + delete this->context_ptr; } }; @@ -102,7 +111,8 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) { // Add a dummy guard condition to avoid an error rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); - ret = rcl_guard_condition_init(&guard_cond, rcl_guard_condition_get_default_options()); + ret = rcl_guard_condition_init( + &guard_cond, this->context_ptr, rcl_guard_condition_get_default_options()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond, NULL); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -113,7 +123,8 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) { ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_timer_t timer = rcl_get_zero_initialized_timer(); - ret = rcl_timer_init(&timer, &clock, RCL_MS_TO_NS(10), nullptr, rcl_get_default_allocator()); + ret = rcl_timer_init( + &timer, &clock, this->context_ptr, RCL_MS_TO_NS(10), nullptr, rcl_get_default_allocator()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_add_timer(&wait_set, &timer, NULL); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -146,7 +157,8 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) { // Add a dummy guard condition to avoid an error rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); - ret = rcl_guard_condition_init(&guard_cond, rcl_guard_condition_get_default_options()); + ret = rcl_guard_condition_init( + &guard_cond, this->context_ptr, rcl_guard_condition_get_default_options()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond, NULL); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -176,7 +188,8 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); - ret = rcl_guard_condition_init(&guard_cond, rcl_guard_condition_get_default_options()); + ret = rcl_guard_condition_init( + &guard_cond, this->context_ptr, rcl_guard_condition_get_default_options()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond, NULL); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -209,7 +222,8 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) { // Add a dummy guard condition to avoid an error rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); - ret = rcl_guard_condition_init(&guard_cond, rcl_guard_condition_get_default_options()); + ret = rcl_guard_condition_init( + &guard_cond, this->context_ptr, rcl_guard_condition_get_default_options()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond, NULL); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -221,7 +235,8 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) { rcl_timer_t canceled_timer = rcl_get_zero_initialized_timer(); ret = rcl_timer_init( - &canceled_timer, &clock, RCL_MS_TO_NS(1), nullptr, rcl_get_default_allocator()); + &canceled_timer, &clock, this->context_ptr, + RCL_MS_TO_NS(1), nullptr, rcl_get_default_allocator()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_timer_cancel(&canceled_timer); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -334,7 +349,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade // setup the guard condition test_set.guard_condition = rcl_get_zero_initialized_guard_condition(); ret = rcl_guard_condition_init( - &test_set.guard_condition, rcl_guard_condition_get_default_options()); + &test_set.guard_condition, this->context_ptr, rcl_guard_condition_get_default_options()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; // setup the wait set test_set.wait_set = rcl_get_zero_initialized_wait_set(); @@ -398,7 +413,8 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) { rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 0, 0, 0, rcl_get_default_allocator()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); - ret = rcl_guard_condition_init(&guard_cond, rcl_guard_condition_get_default_options()); + ret = rcl_guard_condition_init( + &guard_cond, this->context_ptr, rcl_guard_condition_get_default_options()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond, NULL); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -452,7 +468,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), add_with_index) { for (size_t i = 0u; i < kNumEntities; ++i) { guard_conditions[i] = rcl_get_zero_initialized_guard_condition(); ret = rcl_guard_condition_init( - &guard_conditions[i], rcl_guard_condition_get_default_options()); + &guard_conditions[i], this->context_ptr, rcl_guard_condition_get_default_options()); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_add_guard_condition( &wait_set, &guard_conditions[i], &guard_condition_index); diff --git a/rcl/test/test_namespace.cpp b/rcl/test/test_namespace.cpp index f25a80df5..18df73e0b 100644 --- a/rcl/test/test_namespace.cpp +++ b/rcl/test/test_namespace.cpp @@ -33,17 +33,28 @@ using namespace std::chrono_literals; class TestNamespaceFixture : public ::testing::Test { public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); - const char * name = "rcl_test_namespace_node"; + const char * name = "test_namespace_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -52,7 +63,10 @@ class TestNamespaceFixture : public ::testing::Test rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; diff --git a/rcl_action/CMakeLists.txt b/rcl_action/CMakeLists.txt index def67842c..2fc49b942 100644 --- a/rcl_action/CMakeLists.txt +++ b/rcl_action/CMakeLists.txt @@ -77,6 +77,7 @@ install(TARGETS ${PROJECT_NAME} if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) find_package(ament_lint_auto REQUIRED) + find_package(osrf_testing_tools_cpp REQUIRED) find_package(test_msgs REQUIRED) ament_lint_auto_find_test_dependencies() ament_find_gtest() @@ -87,6 +88,7 @@ if(BUILD_TESTING) if(TARGET test_action_client) target_include_directories(test_action_client PUBLIC include + ${osrf_testing_tools_cpp_INCLUDE_DIRS} ) target_link_libraries(test_action_client ${PROJECT_NAME} diff --git a/rcl_action/package.xml b/rcl_action/package.xml index 63c3e2f79..1b45b5037 100644 --- a/rcl_action/package.xml +++ b/rcl_action/package.xml @@ -24,6 +24,7 @@ ament_cmake_gtest ament_lint_common ament_lint_auto + osrf_testing_tools_cpp test_msgs diff --git a/rcl_action/test/rcl_action/test_action_client.cpp b/rcl_action/test/rcl_action/test_action_client.cpp index eb2508d54..9686e253f 100644 --- a/rcl_action/test/rcl_action/test_action_client.cpp +++ b/rcl_action/test/rcl_action/test_action_client.cpp @@ -19,6 +19,7 @@ #include "rcl/error_handling.h" #include "rcl/rcl.h" +#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "test_msgs/action/fibonacci.h" class TestActionClientBaseFixture : public ::testing::Test @@ -26,12 +27,22 @@ class TestActionClientBaseFixture : public ::testing::Test protected: void SetUp() override { - rcl_ret_t ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_ret_t ret; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &this->context); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node = rcl_get_zero_initialized_node(); rcl_node_options_t node_options = rcl_node_get_default_options(); const char * node_name = "test_action_client_node"; - ret = rcl_node_init(&this->node, node_name, "", &node_options); + ret = rcl_node_init(&this->node, node_name, "", &this->context, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -39,10 +50,11 @@ class TestActionClientBaseFixture : public ::testing::Test { rcl_ret_t ret = rcl_node_fini(&this->node); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(&this->context); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } + rcl_context_t context; rcl_node_t node; }; diff --git a/rcl_action/test/rcl_action/test_action_communication.cpp b/rcl_action/test/rcl_action/test_action_communication.cpp index 3aae23c0a..a3bcb743a 100644 --- a/rcl_action/test/rcl_action/test_action_communication.cpp +++ b/rcl_action/test/rcl_action/test_action_communication.cpp @@ -37,11 +37,16 @@ class CLASSNAME (TestActionCommunication, RMW_IMPLEMENTATION) : public ::testing void SetUp() override { rcl_allocator_t allocator = rcl_get_default_allocator(); - rcl_ret_t ret = rcl_init(0, nullptr, allocator); + rcl_ret_t ret; + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, allocator); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->node = rcl_get_zero_initialized_node(); rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(&this->node, "test_action_communication_node", "", &node_options); + ret = rcl_node_init(&this->node, "test_action_communication_node", "", &context, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_clock_init(RCL_STEADY_TIME, &this->clock, &allocator); const rosidl_action_type_support_t * ts = ROSIDL_GET_ACTION_TYPE_SUPPORT( @@ -107,11 +112,11 @@ class CLASSNAME (TestActionCommunication, RMW_IMPLEMENTATION) : public ::testing ret = rcl_action_client_fini(&this->action_client, &this->node); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; ret = rcl_node_fini(&this->node); - EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; - ret = rcl_shutdown(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_wait_set_fini(&this->wait_set); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; + ret = rcl_shutdown(&context); + EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; rcl_reset_error(); } @@ -131,6 +136,7 @@ class CLASSNAME (TestActionCommunication, RMW_IMPLEMENTATION) : public ::testing rcl_action_client_t action_client; rcl_action_server_t action_server; + rcl_context_t context; rcl_node_t node; rcl_clock_t clock; diff --git a/rcl_action/test/rcl_action/test_action_server.cpp b/rcl_action/test/rcl_action/test_action_server.cpp index 8aa2da485..cfabf295b 100644 --- a/rcl_action/test/rcl_action/test_action_server.cpp +++ b/rcl_action/test/rcl_action/test_action_server.cpp @@ -26,12 +26,17 @@ TEST(TestActionServerInitFini, test_action_server_init_fini) { rcl_allocator_t allocator = rcl_get_default_allocator(); - rcl_ret_t ret = rcl_init(0, nullptr, allocator); + rcl_ret_t ret; + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, allocator); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(&node, "test_action_server_node", "", &node_options); + ret = rcl_node_init(&node, "test_action_server_node", "", &context, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_clock_t clock; ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); @@ -133,7 +138,7 @@ TEST(TestActionServerInitFini, test_action_server_init_fini) ret = rcl_node_fini(&node); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(&context); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -143,11 +148,16 @@ class TestActionServer : public ::testing::Test void SetUp() override { rcl_allocator_t allocator = rcl_get_default_allocator(); - rcl_ret_t ret = rcl_init(0, nullptr, allocator); + rcl_ret_t ret; + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, allocator); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; this->node = rcl_get_zero_initialized_node(); rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(&this->node, "test_action_server_node", "", &node_options); + ret = rcl_node_init(&this->node, "test_action_server_node", "", &context, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ret = rcl_clock_init(RCL_ROS_TIME, &this->clock, &allocator); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -170,7 +180,7 @@ class TestActionServer : public ::testing::Test EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; ret = rcl_node_fini(&this->node); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(&context); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } @@ -189,6 +199,7 @@ class TestActionServer : public ::testing::Test } rcl_action_server_t action_server; + rcl_context_t context; rcl_node_t node; rcl_clock_t clock; }; // class TestActionServer diff --git a/rcl_lifecycle/CMakeLists.txt b/rcl_lifecycle/CMakeLists.txt index 0933f105b..1c82a501e 100644 --- a/rcl_lifecycle/CMakeLists.txt +++ b/rcl_lifecycle/CMakeLists.txt @@ -61,6 +61,7 @@ if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) find_package(ament_lint_auto REQUIRED) find_package(rcl REQUIRED) + find_package(osrf_testing_tools_cpp REQUIRED) ament_lint_auto_find_test_dependencies() # Gtests @@ -70,6 +71,7 @@ if(BUILD_TESTING) if(TARGET test_default_state_machine) target_include_directories(test_default_state_machine PUBLIC ${rcl_INCLUDE_DIRS} + ${osrf_testing_tools_cpp_INCLUDE_DIRS} ) target_link_libraries(test_default_state_machine ${PROJECT_NAME}) endif() @@ -79,6 +81,7 @@ if(BUILD_TESTING) if(TARGET test_multiple_instances) target_include_directories(test_multiple_instances PUBLIC ${rcl_INCLUDE_DIRS} + ${osrf_testing_tools_cpp_INCLUDE_DIRS} ) target_link_libraries(test_multiple_instances ${PROJECT_NAME}) endif() diff --git a/rcl_lifecycle/package.xml b/rcl_lifecycle/package.xml index 5e52de490..16144e341 100644 --- a/rcl_lifecycle/package.xml +++ b/rcl_lifecycle/package.xml @@ -24,6 +24,7 @@ ament_cmake_gtest ament_lint_common ament_lint_auto + osrf_testing_tools_cpp ament_cmake diff --git a/rcl_lifecycle/test/test_default_state_machine.cpp b/rcl_lifecycle/test/test_default_state_machine.cpp index 2d27387fc..87e11d6a0 100644 --- a/rcl_lifecycle/test/test_default_state_machine.cpp +++ b/rcl_lifecycle/test/test_default_state_machine.cpp @@ -19,6 +19,8 @@ #include #include +#include "osrf_testing_tools_cpp/scope_exit.hpp" + #include "lifecycle_msgs/msg/state.h" #include "lifecycle_msgs/msg/transition.h" @@ -32,20 +34,30 @@ class TestDefaultStateMachine : public ::testing::Test { -protected: +public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; const rcl_allocator_t * allocator; - void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); const char * name = "test_state_machine_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; const rcl_node_options_t * node_ops = rcl_node_get_options(this->node_ptr); this->allocator = &node_ops->allocator; @@ -56,7 +68,10 @@ class TestDefaultStateMachine : public ::testing::Test rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } }; diff --git a/rcl_lifecycle/test/test_multiple_instances.cpp b/rcl_lifecycle/test/test_multiple_instances.cpp index df803dfdd..c227b7956 100644 --- a/rcl_lifecycle/test/test_multiple_instances.cpp +++ b/rcl_lifecycle/test/test_multiple_instances.cpp @@ -19,6 +19,8 @@ #include #include +#include "osrf_testing_tools_cpp/scope_exit.hpp" + #include "lifecycle_msgs/msg/state.h" #include "lifecycle_msgs/msg/transition.h" @@ -30,19 +32,30 @@ class TestMultipleInstances : public ::testing::Test { -protected: +public: + rcl_context_t * context_ptr; rcl_node_t * node_ptr; const rcl_allocator_t * allocator; void SetUp() { rcl_ret_t ret; - ret = rcl_init(0, nullptr, rcl_get_default_allocator()); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + { + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + this->context_ptr = new rcl_context_t; + *this->context_ptr = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, this->context_ptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); - const char * name = "test_multiple_instances_node"; + const char * name = "test_state_machine_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); - ret = rcl_node_init(this->node_ptr, name, "", &node_options); + ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; const rcl_node_options_t * node_ops = rcl_node_get_options(this->node_ptr); this->allocator = &node_ops->allocator; @@ -53,7 +66,10 @@ class TestMultipleInstances : public ::testing::Test rcl_ret_t ret = rcl_node_fini(this->node_ptr); delete this->node_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ret = rcl_shutdown(); + ret = rcl_shutdown(this->context_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_context_fini(this->context_ptr); + delete this->context_ptr; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } };