use new error handling API from rcutils (#314)

* use new error handling API from rcutils

Signed-off-by: William Woodall <william@osrfoundation.org>

* use semicolons after macros

Signed-off-by: William Woodall <william@osrfoundation.org>

* use new error handling API from rcutils

Signed-off-by: William Woodall <william@osrfoundation.org>

* minimize vertical whitespace

Signed-off-by: William Woodall <william@osrfoundation.org>

* use semicolons after macros

Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
William Woodall 2018-11-01 21:08:31 -05:00 committed by GitHub
parent 765de78140
commit 4d8cb487f8
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
64 changed files with 1131 additions and 1314 deletions

View file

@ -242,8 +242,6 @@ rcl_remove_ros_arguments(
* Uses Atomics | No * Uses Atomics | No
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] error_alloc an alocator to use if an error occurs.
* This allocator is not used to allocate args_out.
* \param[in] args The structure to be copied. * \param[in] args 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] args_out A zero-initialized arguments structure to be copied into. * \param[out] args_out A zero-initialized arguments structure to be copied into.
@ -256,7 +254,6 @@ RCL_PUBLIC
RCL_WARN_UNUSED RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_arguments_copy( rcl_arguments_copy(
rcl_allocator_t error_alloc,
const rcl_arguments_t * args, const rcl_arguments_t * args,
rcl_arguments_t * args_out); rcl_arguments_t * args_out);

View file

@ -55,7 +55,6 @@ RCL_WARN_UNUSED
rcl_client_t rcl_client_t
rcl_get_zero_initialized_client(void); rcl_get_zero_initialized_client(void);
/// Initialize a rcl client. /// Initialize a rcl client.
/** /**
* After calling this function on a rcl_client_t, it can be used to send * After calling this function on a rcl_client_t, it can be used to send
@ -378,7 +377,7 @@ rcl_client_get_rmw_handle(const rcl_client_t * client);
/// Check that the client is valid. /// Check that the client is valid.
/** /**
* The bool returned is `false` if client is invalid * The bool returned is `false` if client is invalid.
* The bool returned is `true` otherwise. * The bool returned is `true` otherwise.
* In the case where `false` is to be returned, an error message is set. * In the case where `false` is to be returned, an error message is set.
* This function cannot fail. * This function cannot fail.
@ -392,12 +391,11 @@ rcl_client_get_rmw_handle(const rcl_client_t * client);
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] client pointer to the rcl client * \param[in] client pointer to the rcl client
* \param[in] error_msg_allocator a valid allocator or `NULL`
* \return `true` if `client` is valid, otherwise `false` * \return `true` if `client` is valid, otherwise `false`
*/ */
RCL_PUBLIC RCL_PUBLIC
bool bool
rcl_client_is_valid(const rcl_client_t * client, rcl_allocator_t * error_msg_allocator); rcl_client_is_valid(const rcl_client_t * client);
#ifdef __cplusplus #ifdef __cplusplus
} }

View file

@ -18,35 +18,25 @@
#include "rcutils/error_handling.h" #include "rcutils/error_handling.h"
/// The error handling in RCL is just an alias to the error handling in rcutils. /// The error handling in RCL is just an alias to the error handling in rcutils.
/**
* Allocators given to functions in rcl are passed along to the error handling
* on a "best effort" basis.
* In some situations, like when NULL is passed for the allocator or something
* else that contains it, the allocator is not available to be passed to the
* RCL_SET_ERROR_MSG macro.
* In these cases, the default allocator rcl_get_default_allocator() is used.
* Since these are considered fatal errors, as opposed to errors that might
* occur during normal runtime, is should be okay to use the default allocator.
*/
typedef rcutils_error_state_t rcl_error_state_t; typedef rcutils_error_state_t rcl_error_state_t;
typedef rcutils_error_string_t rcl_error_string_t;
#define rcl_error_state_copy rcutils_error_state_copy #define rcl_initialize_error_handling_thread_local_storage \
rcutils_initialize_error_handling_thread_local_storage
#define rcl_error_state_fini rcutils_error_state_fini
#define rcl_set_error_state rcutils_set_error_state #define rcl_set_error_state rcutils_set_error_state
#define RCL_CHECK_ARGUMENT_FOR_NULL(argument, error_return_type, allocator) \ #define RCL_CHECK_ARGUMENT_FOR_NULL(argument, error_return_type) \
RCUTILS_CHECK_ARGUMENT_FOR_NULL(argument, error_return_type, allocator) RCUTILS_CHECK_ARGUMENT_FOR_NULL(argument, error_return_type)
#define RCL_CHECK_FOR_NULL_WITH_MSG(value, msg, error_statement, allocator) \ #define RCL_CHECK_FOR_NULL_WITH_MSG(value, msg, error_statement) \
RCUTILS_CHECK_FOR_NULL_WITH_MSG(value, msg, error_statement, allocator) RCUTILS_CHECK_FOR_NULL_WITH_MSG(value, msg, error_statement)
#define RCL_SET_ERROR_MSG(msg, allocator) RCUTILS_SET_ERROR_MSG(msg, allocator) #define RCL_SET_ERROR_MSG(msg) RCUTILS_SET_ERROR_MSG(msg)
#define RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, fmt_str, ...) \ #define RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(fmt_str, ...) \
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, fmt_str, __VA_ARGS__) RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(fmt_str, __VA_ARGS__)
#define rcl_error_is_set rcutils_error_is_set #define rcl_error_is_set rcutils_error_is_set
@ -54,8 +44,6 @@ typedef rcutils_error_state_t rcl_error_state_t;
#define rcl_get_error_string rcutils_get_error_string #define rcl_get_error_string rcutils_get_error_string
#define rcl_get_error_string_safe rcutils_get_error_string_safe
#define rcl_reset_error rcutils_reset_error #define rcl_reset_error rcutils_reset_error
#endif // RCL__ERROR_HANDLING_H_ #endif // RCL__ERROR_HANDLING_H_

View file

@ -87,19 +87,16 @@ typedef enum rcl_lexeme_t
* <hr> * <hr>
* Attribute | Adherence * Attribute | Adherence
* ------------------ | ------------- * ------------------ | -------------
* Allocates Memory | Yes [1] * Allocates Memory | No
* Thread-Safe | Yes * Thread-Safe | Yes
* Uses Atomics | No * Uses Atomics | No
* Lock-Free | Yes * Lock-Free | Yes
* <i>[1] Only allocates if an argument is invalid or an internal bug is detected.</i>
* *
* \param[in] text The string to analyze. * \param[in] text The string to analyze.
* \param[in] allocator An allocator to use if an error occurs.
* \param[out] lexeme The type of lexeme found in the string. * \param[out] lexeme The type of lexeme found in the string.
* \param[out] length The length of text in the string that constitutes the found lexeme. * \param[out] length The length of text in the string that constitutes the found lexeme.
* \return `RCL_RET_OK` if analysis is successful regardless whether a valid lexeme is found, or * \return `RCL_RET_OK` if analysis is successful regardless whether a valid lexeme is found, or
* \return `RCL_RET_INVALID_ARGUMENT` if any function arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any function arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERROR` if an internal bug is detected. * \return `RCL_RET_ERROR` if an internal bug is detected.
*/ */
RCL_PUBLIC RCL_PUBLIC
@ -107,7 +104,6 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_lexer_analyze( rcl_lexer_analyze(
const char * text, const char * text,
rcl_allocator_t allocator,
rcl_lexeme_t * lexeme, rcl_lexeme_t * lexeme,
size_t * length); size_t * length);

View file

@ -220,8 +220,6 @@ rcl_node_get_default_options(void);
* Uses Atomics | No * Uses Atomics | No
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] error_alloc an alocator to use if an error occurs.
* This allocator is not used to allocate the output.
* \param[in] options The structure to be copied. * \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. * \param[out] options_out An options structure containing default values.
@ -234,7 +232,6 @@ RCL_PUBLIC
RCL_WARN_UNUSED RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_node_options_copy( rcl_node_options_copy(
rcl_allocator_t error_alloc,
const rcl_node_options_t * options, const rcl_node_options_t * options,
rcl_node_options_t * options_out); rcl_node_options_t * options_out);
@ -242,10 +239,6 @@ rcl_node_options_copy(
/** /**
* Also return `false` if the node pointer is `NULL` or the allocator is invalid. * Also return `false` if the node pointer is `NULL` or the allocator is invalid.
* *
* The allocator needs to either be a valid allocator or `NULL`, in which case
* the default allocator will be used.
* The allocator is used when allocation is needed for an error message.
*
* A node is invalid if: * A node is invalid if:
* - the implementation is `NULL` (rcl_node_init not called or failed) * - the implementation is `NULL` (rcl_node_init not called or failed)
* - rcl_shutdown has been called since the node has been initialized * - rcl_shutdown has been called since the node has been initialized
@ -256,7 +249,7 @@ rcl_node_options_copy(
* Consider: * Consider:
* *
* ```c * ```c
* assert(rcl_node_is_valid(node, NULL)); // <-- thread 1 * assert(rcl_node_is_valid(node)); // <-- thread 1
* rcl_shutdown(); // <-- thread 2 * rcl_shutdown(); // <-- thread 2
* // use node as if valid // <-- thread 1 * // use node as if valid // <-- thread 1
* ``` * ```
@ -275,12 +268,11 @@ rcl_node_options_copy(
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i> * <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
* *
* \param[in] node rcl_node_t to be validated * \param[in] node rcl_node_t to be validated
* \param[in] error_msg_allocator a valid allocator or `NULL`
* \return `true` if the node and allocator are valid, otherwise `false`. * \return `true` if the node and allocator are valid, otherwise `false`.
*/ */
RCL_PUBLIC RCL_PUBLIC
bool bool
rcl_node_is_valid(const rcl_node_t * node, rcl_allocator_t * error_msg_allocator); rcl_node_is_valid(const rcl_node_t * node);
/// Return the name of the node. /// Return the name of the node.
/** /**

View file

@ -378,8 +378,7 @@ rcl_publisher_get_rmw_handle(const rcl_publisher_t * publisher);
/** /**
* The bool returned is `false` if `publisher` is invalid. * The bool returned is `false` if `publisher` is invalid.
* The bool returned is `true` otherwise. * The bool returned is `true` otherwise.
* In the case where `false` is to be returned, an * In the case where `false` is to be returned, an error message is set.
* error message is set.
* This function cannot fail. * This function cannot fail.
* *
* <hr> * <hr>
@ -391,14 +390,11 @@ rcl_publisher_get_rmw_handle(const rcl_publisher_t * publisher);
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] publisher pointer to the rcl publisher * \param[in] publisher pointer to the rcl publisher
* \param[in] error_msg_allocator a valid allocator or `NULL`
* \return `true` if `publisher` is valid, otherwise `false` * \return `true` if `publisher` is valid, otherwise `false`
*/ */
RCL_PUBLIC RCL_PUBLIC
bool bool
rcl_publisher_is_valid( rcl_publisher_is_valid(const rcl_publisher_t * publisher);
const rcl_publisher_t * publisher,
rcl_allocator_t * error_msg_allocator);
#ifdef __cplusplus #ifdef __cplusplus
} }

View file

@ -391,8 +391,7 @@ rcl_service_get_rmw_handle(const rcl_service_t * service);
/** /**
* The bool returned is `false` if `service` is invalid. * The bool returned is `false` if `service` is invalid.
* The bool returned is `true` otherwise. * The bool returned is `true` otherwise.
* In the case where `false` is to be returned, an * In the case where `false` is to be returned, an error message is set.
* error message is set.
* This function cannot fail. * This function cannot fail.
* *
* <hr> * <hr>
@ -404,12 +403,11 @@ rcl_service_get_rmw_handle(const rcl_service_t * service);
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] service pointer to the rcl service * \param[in] service pointer to the rcl service
* \param[in] error_msg_allocator a valid allocator or `NULL`
* \return `true` if `service` is valid, otherwise `false` * \return `true` if `service` is valid, otherwise `false`
*/ */
RCL_PUBLIC RCL_PUBLIC
bool bool
rcl_service_is_valid(const rcl_service_t * service, rcl_allocator_t * error_msg_allocator); rcl_service_is_valid(const rcl_service_t * service);
#ifdef __cplusplus #ifdef __cplusplus
} }

View file

@ -388,8 +388,7 @@ rcl_subscription_get_rmw_handle(const rcl_subscription_t * subscription);
/** /**
* The bool returned is `false` if `subscription` is invalid. * The bool returned is `false` if `subscription` is invalid.
* The bool returned is `true` otherwise. * The bool returned is `true` otherwise.
* In the case where `false` is to be returned, an * In the case where `false` is to be returned, an error message is set.
* error message is set.
* This function cannot fail. * This function cannot fail.
* *
* <hr> * <hr>
@ -401,14 +400,11 @@ rcl_subscription_get_rmw_handle(const rcl_subscription_t * subscription);
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] subscription pointer to the rcl subscription * \param[in] subscription pointer to the rcl subscription
* \param[in] error_msg_allocator a valid allocator or `NULL`
* \return `true` if `subscription` is valid, otherwise `false` * \return `true` if `subscription` is valid, otherwise `false`
*/ */
RCL_PUBLIC RCL_PUBLIC
bool bool
rcl_subscription_is_valid( rcl_subscription_is_valid(const rcl_subscription_t * subscription);
const rcl_subscription_t * subscription,
rcl_allocator_t * error_msg_allocator);
#ifdef __cplusplus #ifdef __cplusplus
} }

View file

@ -81,9 +81,9 @@ rcl_arguments_get_param_files(
char *** parameter_files) char *** parameter_files)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(parameter_files, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(parameter_files, RCL_RET_INVALID_ARGUMENT);
*(parameter_files) = allocator.allocate( *(parameter_files) = allocator.allocate(
sizeof(char *) * arguments->impl->num_param_files_args, allocator.state); sizeof(char *) * arguments->impl->num_param_files_args, allocator.state);
if (NULL == *parameter_files) { if (NULL == *parameter_files) {
@ -143,15 +143,15 @@ rcl_parse_arguments(
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
if (argc < 0) { if (argc < 0) {
RCL_SET_ERROR_MSG("Argument count cannot be negative", allocator); RCL_SET_ERROR_MSG("Argument count cannot be negative");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} else if (argc > 0) { } else if (argc > 0) {
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
} }
RCL_CHECK_ARGUMENT_FOR_NULL(args_output, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(args_output, RCL_RET_INVALID_ARGUMENT);
if (args_output->impl != NULL) { if (args_output->impl != NULL) {
RCL_SET_ERROR_MSG("Parse output is not zero-initialized", allocator); RCL_SET_ERROR_MSG("Parse output is not zero-initialized");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
@ -307,10 +307,10 @@ rcl_arguments_get_unparsed(
rcl_allocator_t allocator, rcl_allocator_t allocator,
int ** output_unparsed_indices) int ** output_unparsed_indices)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_indices, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT, allocator);
RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_indices, RCL_RET_INVALID_ARGUMENT, allocator);
*output_unparsed_indices = NULL; *output_unparsed_indices = NULL;
if (args->impl->num_unparsed_args) { if (args->impl->num_unparsed_args) {
@ -343,10 +343,10 @@ rcl_remove_ros_arguments(
int * nonros_argc, int * nonros_argc,
const char ** nonros_argv[]) const char ** nonros_argv[])
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argc, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT, allocator);
RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argc, RCL_RET_INVALID_ARGUMENT, allocator);
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT, allocator);
*nonros_argc = rcl_arguments_get_count_unparsed(args); *nonros_argc = rcl_arguments_get_count_unparsed(args);
*nonros_argv = NULL; *nonros_argv = NULL;
@ -379,16 +379,14 @@ rcl_remove_ros_arguments(
rcl_ret_t rcl_ret_t
rcl_arguments_copy( rcl_arguments_copy(
rcl_allocator_t error_alloc,
const rcl_arguments_t * args, const rcl_arguments_t * args,
rcl_arguments_t * args_out) rcl_arguments_t * args_out)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&error_alloc, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT, error_alloc); RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT, error_alloc); RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT, error_alloc);
if (NULL != args_out->impl) { if (NULL != args_out->impl) {
RCL_SET_ERROR_MSG("args_out must be zero initialized", error_alloc); RCL_SET_ERROR_MSG("args_out must be zero initialized");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
@ -411,7 +409,7 @@ rcl_arguments_copy(
sizeof(int) * args->impl->num_unparsed_args, allocator.state); sizeof(int) * args->impl->num_unparsed_args, allocator.state);
if (NULL == args_out->impl->unparsed_args) { if (NULL == args_out->impl->unparsed_args) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) { if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error", error_alloc); RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
} }
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -425,7 +423,7 @@ rcl_arguments_copy(
sizeof(rcl_remap_t) * args->impl->num_remap_rules, allocator.state); sizeof(rcl_remap_t) * args->impl->num_remap_rules, allocator.state);
if (NULL == args_out->impl->remap_rules) { if (NULL == args_out->impl->remap_rules) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) { if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error", error_alloc); RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
} }
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -433,10 +431,10 @@ rcl_arguments_copy(
for (int i = 0; i < args->impl->num_remap_rules; ++i) { for (int i = 0; i < args->impl->num_remap_rules; ++i) {
args_out->impl->remap_rules[i] = rcl_remap_get_zero_initialized(); args_out->impl->remap_rules[i] = rcl_remap_get_zero_initialized();
rcl_ret_t ret = rcl_remap_copy( rcl_ret_t ret = rcl_remap_copy(
error_alloc, &(args->impl->remap_rules[i]), &(args_out->impl->remap_rules[i])); &(args->impl->remap_rules[i]), &(args_out->impl->remap_rules[i]));
if (RCL_RET_OK != ret) { if (RCL_RET_OK != ret) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) { if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error", error_alloc); RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
} }
return ret; return ret;
} }
@ -447,7 +445,7 @@ rcl_arguments_copy(
sizeof(char *) * args->impl->num_param_files_args, allocator.state); sizeof(char *) * args->impl->num_param_files_args, allocator.state);
if (NULL == args_out->impl->parameter_files) { if (NULL == args_out->impl->parameter_files) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) { if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error", error_alloc); RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
} }
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -457,7 +455,7 @@ rcl_arguments_copy(
rcutils_strdup(args->impl->parameter_files[i], allocator); rcutils_strdup(args->impl->parameter_files[i], allocator);
if (NULL == args_out->impl->parameter_files[i]) { if (NULL == args_out->impl->parameter_files[i]) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) { if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error", error_alloc); RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
} }
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -472,11 +470,9 @@ rcl_ret_t
rcl_arguments_fini( rcl_arguments_fini(
rcl_arguments_t * args) rcl_arguments_t * args)
{ {
rcl_allocator_t alloc = rcl_get_default_allocator(); RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT, alloc);
if (args->impl) { if (args->impl) {
rcl_ret_t ret = RCL_RET_OK; rcl_ret_t ret = RCL_RET_OK;
alloc = args->impl->allocator;
if (args->impl->remap_rules) { if (args->impl->remap_rules) {
for (int i = 0; i < args->impl->num_remap_rules; ++i) { for (int i = 0; i < args->impl->num_remap_rules; ++i) {
rcl_ret_t remap_ret = rcl_remap_fini(&(args->impl->remap_rules[i])); rcl_ret_t remap_ret = rcl_remap_fini(&(args->impl->remap_rules[i]));
@ -510,7 +506,7 @@ rcl_arguments_fini(
args->impl = NULL; args->impl = NULL;
return ret; return ret;
} }
RCL_SET_ERROR_MSG("rcl_arguments_t finalized twice", alloc); RCL_SET_ERROR_MSG("rcl_arguments_t finalized twice");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -561,9 +557,7 @@ _rcl_parse_remap_fully_qualified_namespace(
*/ */
RCL_LOCAL RCL_LOCAL
rcl_ret_t rcl_ret_t
_rcl_parse_remap_replacement_token( _rcl_parse_remap_replacement_token(rcl_lexer_lookahead2_t * lex_lookahead)
rcl_lexer_lookahead2_t * lex_lookahead,
rcl_remap_t * rule)
{ {
rcl_ret_t ret; rcl_ret_t ret;
rcl_lexeme_t lexeme; rcl_lexeme_t lexeme;
@ -578,7 +572,7 @@ _rcl_parse_remap_replacement_token(
RCL_LEXEME_BR4 == lexeme || RCL_LEXEME_BR5 == lexeme || RCL_LEXEME_BR6 == lexeme || RCL_LEXEME_BR4 == lexeme || RCL_LEXEME_BR5 == lexeme || RCL_LEXEME_BR6 == lexeme ||
RCL_LEXEME_BR7 == lexeme || RCL_LEXEME_BR8 == lexeme || RCL_LEXEME_BR9 == lexeme) RCL_LEXEME_BR7 == lexeme || RCL_LEXEME_BR8 == lexeme || RCL_LEXEME_BR9 == lexeme)
{ {
RCL_SET_ERROR_MSG("Backreferences are not implemented", rule->allocator); RCL_SET_ERROR_MSG("Backreferences are not implemented");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} else if (RCL_LEXEME_TOKEN == lexeme) { } else if (RCL_LEXEME_TOKEN == lexeme) {
ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL); ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
@ -604,7 +598,7 @@ _rcl_parse_remap_replacement_name(
const char * replacement_start = rcl_lexer_lookahead2_get_text(lex_lookahead); const char * replacement_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
if (NULL == replacement_start) { if (NULL == replacement_start) {
RCL_SET_ERROR_MSG("failed to get start of replacement", rule->allocator); RCL_SET_ERROR_MSG("failed to get start of replacement");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -621,7 +615,7 @@ _rcl_parse_remap_replacement_name(
} }
// token ( '/' token )* // token ( '/' token )*
ret = _rcl_parse_remap_replacement_token(lex_lookahead, rule); ret = _rcl_parse_remap_replacement_token(lex_lookahead);
if (RCL_RET_OK != ret) { if (RCL_RET_OK != ret) {
return ret; return ret;
} }
@ -634,7 +628,7 @@ _rcl_parse_remap_replacement_name(
if (RCL_RET_WRONG_LEXEME == ret) { if (RCL_RET_WRONG_LEXEME == ret) {
return RCL_RET_INVALID_REMAP_RULE; return RCL_RET_INVALID_REMAP_RULE;
} }
ret = _rcl_parse_remap_replacement_token(lex_lookahead, rule); ret = _rcl_parse_remap_replacement_token(lex_lookahead);
if (RCL_RET_OK != ret) { if (RCL_RET_OK != ret) {
return ret; return ret;
} }
@ -649,7 +643,7 @@ _rcl_parse_remap_replacement_name(
size_t length = (size_t)(replacement_end - replacement_start); size_t length = (size_t)(replacement_end - replacement_start);
rule->replacement = rcutils_strndup(replacement_start, length, rule->allocator); rule->replacement = rcutils_strndup(replacement_start, length, rule->allocator);
if (NULL == rule->replacement) { if (NULL == rule->replacement) {
RCL_SET_ERROR_MSG("failed to copy replacement", rule->allocator); RCL_SET_ERROR_MSG("failed to copy replacement");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -662,9 +656,7 @@ _rcl_parse_remap_replacement_name(
*/ */
RCL_LOCAL RCL_LOCAL
rcl_ret_t rcl_ret_t
_rcl_parse_remap_match_token( _rcl_parse_remap_match_token(rcl_lexer_lookahead2_t * lex_lookahead)
rcl_lexer_lookahead2_t * lex_lookahead,
rcl_remap_t * rule)
{ {
rcl_ret_t ret; rcl_ret_t ret;
rcl_lexeme_t lexeme; rcl_lexeme_t lexeme;
@ -677,13 +669,13 @@ _rcl_parse_remap_match_token(
if (RCL_LEXEME_TOKEN == lexeme) { if (RCL_LEXEME_TOKEN == lexeme) {
ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL); ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
} else if (RCL_LEXEME_WILD_ONE == lexeme) { } else if (RCL_LEXEME_WILD_ONE == lexeme) {
RCL_SET_ERROR_MSG("Wildcard '*' is not implemented", rule->allocator); RCL_SET_ERROR_MSG("Wildcard '*' is not implemented");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} else if (RCL_LEXEME_WILD_MULTI == lexeme) { } else if (RCL_LEXEME_WILD_MULTI == lexeme) {
RCL_SET_ERROR_MSG("Wildcard '**' is not implemented", rule->allocator); RCL_SET_ERROR_MSG("Wildcard '**' is not implemented");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} else { } else {
RCL_SET_ERROR_MSG("Expecting token or wildcard", rule->allocator); RCL_SET_ERROR_MSG("Expecting token or wildcard");
ret = RCL_RET_INVALID_REMAP_RULE; ret = RCL_RET_INVALID_REMAP_RULE;
} }
@ -722,7 +714,7 @@ _rcl_parse_remap_match_name(
const char * match_start = rcl_lexer_lookahead2_get_text(lex_lookahead); const char * match_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
if (NULL == match_start) { if (NULL == match_start) {
RCL_SET_ERROR_MSG("failed to get start of match", rule->allocator); RCL_SET_ERROR_MSG("failed to get start of match");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -739,7 +731,7 @@ _rcl_parse_remap_match_name(
} }
// token ( '/' token )* // token ( '/' token )*
ret = _rcl_parse_remap_match_token(lex_lookahead, rule); ret = _rcl_parse_remap_match_token(lex_lookahead);
if (RCL_RET_OK != ret) { if (RCL_RET_OK != ret) {
return ret; return ret;
} }
@ -752,7 +744,7 @@ _rcl_parse_remap_match_name(
if (RCL_RET_WRONG_LEXEME == ret) { if (RCL_RET_WRONG_LEXEME == ret) {
return RCL_RET_INVALID_REMAP_RULE; return RCL_RET_INVALID_REMAP_RULE;
} }
ret = _rcl_parse_remap_match_token(lex_lookahead, rule); ret = _rcl_parse_remap_match_token(lex_lookahead);
if (RCL_RET_OK != ret) { if (RCL_RET_OK != ret) {
return ret; return ret;
} }
@ -767,7 +759,7 @@ _rcl_parse_remap_match_name(
size_t length = (size_t)(match_end - match_start); size_t length = (size_t)(match_end - match_start);
rule->match = rcutils_strndup(match_start, length, rule->allocator); rule->match = rcutils_strndup(match_start, length, rule->allocator);
if (NULL == rule->match) { if (NULL == rule->match) {
RCL_SET_ERROR_MSG("failed to copy match", rule->allocator); RCL_SET_ERROR_MSG("failed to copy match");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -828,7 +820,7 @@ _rcl_parse_remap_namespace_replacement(
// /foo/bar // /foo/bar
const char * ns_start = rcl_lexer_lookahead2_get_text(lex_lookahead); const char * ns_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
if (NULL == ns_start) { if (NULL == ns_start) {
RCL_SET_ERROR_MSG("failed to get start of namespace", rule->allocator); RCL_SET_ERROR_MSG("failed to get start of namespace");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
ret = _rcl_parse_remap_fully_qualified_namespace(lex_lookahead); ret = _rcl_parse_remap_fully_qualified_namespace(lex_lookahead);
@ -854,7 +846,7 @@ _rcl_parse_remap_namespace_replacement(
size_t length = (size_t)(ns_end - ns_start); size_t length = (size_t)(ns_end - ns_start);
rule->replacement = rcutils_strndup(ns_start, length, rule->allocator); rule->replacement = rcutils_strndup(ns_start, length, rule->allocator);
if (NULL == rule->replacement) { if (NULL == rule->replacement) {
RCL_SET_ERROR_MSG("failed to copy namespace", rule->allocator); RCL_SET_ERROR_MSG("failed to copy namespace");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -897,7 +889,7 @@ _rcl_parse_remap_nodename_replacement(
// copy the node name into the replacement side of the rule // copy the node name into the replacement side of the rule
rule->replacement = rcutils_strndup(node_name, length, rule->allocator); rule->replacement = rcutils_strndup(node_name, length, rule->allocator);
if (NULL == rule->replacement) { if (NULL == rule->replacement) {
RCL_SET_ERROR_MSG("failed to allocate node name", rule->allocator); RCL_SET_ERROR_MSG("failed to allocate node name");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -932,7 +924,7 @@ _rcl_parse_remap_nodename_prefix(
// copy the node name into the rule // copy the node name into the rule
rule->node_name = rcutils_strndup(node_name, length, rule->allocator); rule->node_name = rcutils_strndup(node_name, length, rule->allocator);
if (NULL == rule->node_name) { if (NULL == rule->node_name) {
RCL_SET_ERROR_MSG("failed to allocate node name", rule->allocator); RCL_SET_ERROR_MSG("failed to allocate node name");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -1007,11 +999,11 @@ _rcl_parse_log_level_rule(
rcl_allocator_t allocator, rcl_allocator_t allocator,
int * log_level) int * log_level)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(log_level, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(log_level, RCL_RET_INVALID_ARGUMENT);
if (strncmp(RCL_LOG_LEVEL_ARG_RULE, arg, strlen(RCL_LOG_LEVEL_ARG_RULE)) != 0) { if (strncmp(RCL_LOG_LEVEL_ARG_RULE, arg, strlen(RCL_LOG_LEVEL_ARG_RULE)) != 0) {
RCL_SET_ERROR_MSG("Argument does not start with '" RCL_LOG_LEVEL_ARG_RULE "'", allocator); RCL_SET_ERROR_MSG("Argument does not start with '" RCL_LOG_LEVEL_ARG_RULE "'");
return RCL_RET_INVALID_LOG_LEVEL_RULE; return RCL_RET_INVALID_LOG_LEVEL_RULE;
} }
rcutils_ret_t ret = rcutils_logging_severity_level_from_string( rcutils_ret_t ret = rcutils_logging_severity_level_from_string(
@ -1019,7 +1011,7 @@ _rcl_parse_log_level_rule(
if (RCUTILS_RET_OK == ret) { if (RCUTILS_RET_OK == ret) {
return RCL_RET_OK; return RCL_RET_OK;
} }
RCL_SET_ERROR_MSG("Argument does not use a valid severity level", allocator); RCL_SET_ERROR_MSG("Argument does not use a valid severity level");
return RCL_RET_INVALID_LOG_LEVEL_RULE; return RCL_RET_INVALID_LOG_LEVEL_RULE;
} }
@ -1030,8 +1022,8 @@ _rcl_parse_remap_rule(
rcl_allocator_t allocator, rcl_allocator_t allocator,
rcl_remap_t * output_rule) rcl_remap_t * output_rule)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT);
rcl_ret_t ret; rcl_ret_t ret;
@ -1065,20 +1057,20 @@ _rcl_parse_param_file_rule(
rcl_allocator_t allocator, rcl_allocator_t allocator,
char ** param_file) char ** param_file)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
const size_t param_prefix_len = strlen(RCL_PARAM_FILE_ARG_RULE); const size_t param_prefix_len = strlen(RCL_PARAM_FILE_ARG_RULE);
if (strncmp(RCL_PARAM_FILE_ARG_RULE, arg, param_prefix_len) == 0) { if (strncmp(RCL_PARAM_FILE_ARG_RULE, arg, param_prefix_len) == 0) {
size_t outlen = strlen(arg) - param_prefix_len; size_t outlen = strlen(arg) - param_prefix_len;
*param_file = allocator.allocate(sizeof(char) * (outlen + 1), allocator.state); *param_file = allocator.allocate(sizeof(char) * (outlen + 1), allocator.state);
if (NULL == param_file) { if (NULL == *param_file) {
RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to allocate memory for parameters file path\n"); RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to allocate memory for parameters file path\n");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
snprintf(*param_file, outlen + 1, "%s", arg + param_prefix_len); snprintf(*param_file, outlen + 1, "%s", arg + param_prefix_len);
return RCL_RET_OK; return RCL_RET_OK;
} }
RCL_SET_ERROR_MSG("Argument does not start with '" RCL_PARAM_FILE_ARG_RULE "'", allocator); RCL_SET_ERROR_MSG("Argument does not start with '" RCL_PARAM_FILE_ARG_RULE "'");
return RCL_RET_INVALID_PARAM_RULE; return RCL_RET_INVALID_PARAM_RULE;
} }

View file

@ -58,20 +58,20 @@ rcl_client_init(
rcl_ret_t fail_ret = RCL_RET_ERROR; rcl_ret_t fail_ret = RCL_RET_ERROR;
// check the options and allocator first, so the allocator can be passed to errors // check the options and allocator first, so the allocator can be passed to errors
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator; rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, allocator)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service_name, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(service_name, RCL_RET_INVALID_ARGUMENT);
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Initializing client for service name '%s'", service_name); ROS_PACKAGE_NAME, "Initializing client for service name '%s'", service_name);
if (client->impl) { if (client->impl) {
RCL_SET_ERROR_MSG("client already initialized, or memory was unintialized", *allocator); RCL_SET_ERROR_MSG("client already initialized, or memory was unintialized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Expand the given service name. // Expand the given service name.
@ -79,7 +79,7 @@ rcl_client_init(
rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map(); rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map();
rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator); rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator) RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) { if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) {
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -93,7 +93,7 @@ rcl_client_init(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"failed to fini string_map (%d) during error handling: %s\n", "failed to fini string_map (%d) during error handling: %s\n",
rcutils_ret, rcutils_ret,
rcutils_get_error_string_safe()); rcutils_get_error_string().str);
} }
if (ret == RCL_RET_BAD_ALLOC) { if (ret == RCL_RET_BAD_ALLOC) {
return ret; return ret;
@ -111,7 +111,7 @@ rcl_client_init(
&expanded_service_name); &expanded_service_name);
rcutils_ret = rcutils_string_map_fini(&substitutions_map); rcutils_ret = rcutils_string_map_fini(&substitutions_map);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator) RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
allocator->deallocate(expanded_service_name, allocator->state); allocator->deallocate(expanded_service_name, allocator->state);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -148,12 +148,12 @@ rcl_client_init(
int validation_result; int validation_result;
rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_service_name, &validation_result, NULL); rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_service_name, &validation_result, NULL);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
} }
if (validation_result != RMW_TOPIC_VALID) { if (validation_result != RMW_TOPIC_VALID) {
RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result), *allocator) RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result));
ret = RCL_RET_SERVICE_NAME_INVALID; ret = RCL_RET_SERVICE_NAME_INVALID;
goto cleanup; goto cleanup;
} }
@ -161,7 +161,7 @@ rcl_client_init(
client->impl = (rcl_client_impl_t *)allocator->allocate( client->impl = (rcl_client_impl_t *)allocator->allocate(
sizeof(rcl_client_impl_t), allocator->state); sizeof(rcl_client_impl_t), allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
client->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup, *allocator); client->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup);
// Fill out implementation struct. // Fill out implementation struct.
// rmw handle (create rmw client) // rmw handle (create rmw client)
// TODO(wjwwood): pass along the allocator to rmw when it supports it // TODO(wjwwood): pass along the allocator to rmw when it supports it
@ -171,7 +171,7 @@ rcl_client_init(
remapped_service_name, remapped_service_name,
&options->qos); &options->qos);
if (!client->impl->rmw_handle) { if (!client->impl->rmw_handle) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
goto fail; goto fail;
} }
// options // options
@ -201,9 +201,9 @@ rcl_client_fini(rcl_client_t * client, rcl_node_t * node)
(void)node; (void)node;
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing client"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing client");
rcl_ret_t result = RCL_RET_OK; rcl_ret_t result = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
if (client->impl) { if (client->impl) {
@ -214,7 +214,7 @@ rcl_client_fini(rcl_client_t * client, rcl_node_t * node)
} }
rmw_ret_t ret = rmw_destroy_client(rmw_node, client->impl->rmw_handle); rmw_ret_t ret = rmw_destroy_client(rmw_node, client->impl->rmw_handle);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR; result = RCL_RET_ERROR;
} }
allocator.deallocate(client->impl, allocator.state); allocator.deallocate(client->impl, allocator.state);
@ -237,7 +237,7 @@ rcl_client_get_default_options()
const char * const char *
rcl_client_get_service_name(const rcl_client_t * client) rcl_client_get_service_name(const rcl_client_t * client)
{ {
if (!rcl_client_is_valid(client, NULL)) { if (!rcl_client_is_valid(client)) {
return NULL; // error already set return NULL; // error already set
} }
return client->impl->rmw_handle->service_name; return client->impl->rmw_handle->service_name;
@ -248,7 +248,7 @@ rcl_client_get_service_name(const rcl_client_t * client)
const rcl_client_options_t * const rcl_client_options_t *
rcl_client_get_options(const rcl_client_t * client) rcl_client_get_options(const rcl_client_t * client)
{ {
if (!rcl_client_is_valid(client, NULL)) { if (!rcl_client_is_valid(client)) {
return NULL; // error already set return NULL; // error already set
} }
return _client_get_options(client); return _client_get_options(client);
@ -257,7 +257,7 @@ rcl_client_get_options(const rcl_client_t * client)
rmw_client_t * rmw_client_t *
rcl_client_get_rmw_handle(const rcl_client_t * client) rcl_client_get_rmw_handle(const rcl_client_t * client)
{ {
if (!rcl_client_is_valid(client, NULL)) { if (!rcl_client_is_valid(client)) {
return NULL; // error already set return NULL; // error already set
} }
return client->impl->rmw_handle; return client->impl->rmw_handle;
@ -267,17 +267,17 @@ rcl_ret_t
rcl_send_request(const rcl_client_t * client, const void * ros_request, int64_t * sequence_number) rcl_send_request(const rcl_client_t * client, const void * ros_request, int64_t * sequence_number)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Client sending service request"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Client sending service request");
if (!rcl_client_is_valid(client, NULL)) { if (!rcl_client_is_valid(client)) {
return RCL_RET_CLIENT_INVALID; return RCL_RET_CLIENT_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(ros_request, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(ros_request, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(
sequence_number, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); sequence_number, RCL_RET_INVALID_ARGUMENT);
*sequence_number = rcl_atomic_load_int64_t(&client->impl->sequence_number); *sequence_number = rcl_atomic_load_int64_t(&client->impl->sequence_number);
if (rmw_send_request( if (rmw_send_request(
client->impl->rmw_handle, ros_request, sequence_number) != RMW_RET_OK) client->impl->rmw_handle, ros_request, sequence_number) != RMW_RET_OK)
{ {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), client->impl->options.allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
rcl_atomic_exchange_int64_t(&client->impl->sequence_number, *sequence_number); rcl_atomic_exchange_int64_t(&client->impl->sequence_number, *sequence_number);
@ -291,19 +291,18 @@ rcl_take_response(
void * ros_response) void * ros_response)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Client taking service response"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Client taking service response");
if (!rcl_client_is_valid(client, NULL)) { if (!rcl_client_is_valid(client)) {
return RCL_RET_CLIENT_INVALID; return RCL_RET_CLIENT_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT);
request_header, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(ros_response, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(ros_response, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
bool taken = false; bool taken = false;
if (rmw_take_response( if (rmw_take_response(
client->impl->rmw_handle, request_header, ros_response, &taken) != RMW_RET_OK) client->impl->rmw_handle, request_header, ros_response, &taken) != RMW_RET_OK)
{ {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), client->impl->options.allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
@ -315,20 +314,17 @@ rcl_take_response(
} }
bool bool
rcl_client_is_valid(const rcl_client_t * client, rcl_allocator_t * error_msg_allocator) rcl_client_is_valid(const rcl_client_t * client)
{ {
const rcl_client_options_t * options; const rcl_client_options_t * options;
rcl_allocator_t alloc = RCL_CHECK_ARGUMENT_FOR_NULL(client, false);
error_msg_allocator ? *error_msg_allocator : rcl_get_default_allocator();
RCL_CHECK_ALLOCATOR_WITH_MSG(&alloc, "allocator is invalid", return false);
RCL_CHECK_ARGUMENT_FOR_NULL(client, false, alloc);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
client->impl, "client's rmw implementation is invalid", return false, alloc); client->impl, "client's rmw implementation is invalid", return false);
options = _client_get_options(client); options = _client_get_options(client);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
options, "client's options pointer is invalid", return false, alloc); options, "client's options pointer is invalid", return false);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
client->impl->rmw_handle, "client's rmw handle is invalid", return false, alloc); client->impl->rmw_handle, "client's rmw handle is invalid", return false);
return true; return true;
} }
#ifdef __cplusplus #ifdef __cplusplus

View file

@ -32,8 +32,8 @@ static char __env_buffer[WINDOWS_ENV_BUFFER_SIZE];
rcl_ret_t rcl_ret_t
rcl_impl_getenv(const char * env_name, const char ** env_value) rcl_impl_getenv(const char * env_name, const char ** env_value)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(env_name, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(env_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(env_value, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(env_value, RCL_RET_INVALID_ARGUMENT);
*env_value = NULL; *env_value = NULL;
#if !defined(_WIN32) #if !defined(_WIN32)
*env_value = getenv(env_name); *env_value = getenv(env_name);
@ -44,7 +44,7 @@ rcl_impl_getenv(const char * env_name, const char ** env_value)
size_t required_size; size_t required_size;
errno_t ret = getenv_s(&required_size, __env_buffer, sizeof(__env_buffer), env_name); errno_t ret = getenv_s(&required_size, __env_buffer, sizeof(__env_buffer), env_name);
if (ret != 0) { if (ret != 0) {
RCL_SET_ERROR_MSG("value in env variable too large to read in", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("value in env variable too large to read in");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
__env_buffer[WINDOWS_ENV_BUFFER_SIZE - 1] = '\0'; __env_buffer[WINDOWS_ENV_BUFFER_SIZE - 1] = '\0';

View file

@ -50,11 +50,11 @@ rcl_expand_topic_name(
char ** output_topic_name) char ** output_topic_name)
{ {
// check arguments that could be null // check arguments that could be null
RCL_CHECK_ARGUMENT_FOR_NULL(input_topic_name, RCL_RET_INVALID_ARGUMENT, allocator) RCL_CHECK_ARGUMENT_FOR_NULL(input_topic_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT, allocator) RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_namespace, RCL_RET_INVALID_ARGUMENT, allocator) RCL_CHECK_ARGUMENT_FOR_NULL(node_namespace, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(substitutions, RCL_RET_INVALID_ARGUMENT, allocator) RCL_CHECK_ARGUMENT_FOR_NULL(substitutions, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(output_topic_name, RCL_RET_INVALID_ARGUMENT, allocator) RCL_CHECK_ARGUMENT_FOR_NULL(output_topic_name, RCL_RET_INVALID_ARGUMENT);
// validate the input topic // validate the input topic
int validation_result; int validation_result;
rcl_ret_t ret = rcl_validate_topic_name(input_topic_name, &validation_result, NULL); rcl_ret_t ret = rcl_validate_topic_name(input_topic_name, &validation_result, NULL);
@ -63,14 +63,14 @@ rcl_expand_topic_name(
return ret; return ret;
} }
if (validation_result != RCL_TOPIC_NAME_VALID) { if (validation_result != RCL_TOPIC_NAME_VALID) {
RCL_SET_ERROR_MSG("topic name is invalid", allocator) RCL_SET_ERROR_MSG("topic name is invalid");
return RCL_RET_TOPIC_NAME_INVALID; return RCL_RET_TOPIC_NAME_INVALID;
} }
// validate the node name // validate the node name
rmw_ret_t rmw_ret; rmw_ret_t rmw_ret;
rmw_ret = rmw_validate_node_name(node_name, &validation_result, NULL); rmw_ret = rmw_validate_node_name(node_name, &validation_result, NULL);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator) RCL_SET_ERROR_MSG(rmw_get_error_string().str);
switch (rmw_ret) { switch (rmw_ret) {
case RMW_RET_INVALID_ARGUMENT: case RMW_RET_INVALID_ARGUMENT:
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
@ -81,13 +81,13 @@ rcl_expand_topic_name(
} }
} }
if (validation_result != RMW_NODE_NAME_VALID) { if (validation_result != RMW_NODE_NAME_VALID) {
RCL_SET_ERROR_MSG("node name is invalid", allocator) RCL_SET_ERROR_MSG("node name is invalid");
return RCL_RET_NODE_INVALID_NAME; return RCL_RET_NODE_INVALID_NAME;
} }
// validate the namespace // validate the namespace
rmw_ret = rmw_validate_namespace(node_namespace, &validation_result, NULL); rmw_ret = rmw_validate_namespace(node_namespace, &validation_result, NULL);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator) RCL_SET_ERROR_MSG(rmw_get_error_string().str);
switch (rmw_ret) { switch (rmw_ret) {
case RMW_RET_INVALID_ARGUMENT: case RMW_RET_INVALID_ARGUMENT:
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
@ -98,7 +98,7 @@ rcl_expand_topic_name(
} }
} }
if (validation_result != RMW_NODE_NAME_VALID) { if (validation_result != RMW_NODE_NAME_VALID) {
RCL_SET_ERROR_MSG("node namespace is invalid", allocator) RCL_SET_ERROR_MSG("node namespace is invalid");
return RCL_RET_NODE_INVALID_NAMESPACE; return RCL_RET_NODE_INVALID_NAMESPACE;
} }
// check if the topic has substitutions to be made // check if the topic has substitutions to be made
@ -111,7 +111,7 @@ rcl_expand_topic_name(
*output_topic_name = rcutils_strdup(input_topic_name, allocator); *output_topic_name = rcutils_strdup(input_topic_name, allocator);
if (!*output_topic_name) { if (!*output_topic_name) {
*output_topic_name = NULL; *output_topic_name = NULL;
RCL_SET_ERROR_MSG("failed to allocate memory for output topic", allocator) RCL_SET_ERROR_MSG("failed to allocate memory for output topic");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -126,7 +126,7 @@ rcl_expand_topic_name(
rcutils_format_string(allocator, fmt, node_namespace, node_name, input_topic_name + 1); rcutils_format_string(allocator, fmt, node_namespace, node_name, input_topic_name + 1);
if (!local_output) { if (!local_output) {
*output_topic_name = NULL; *output_topic_name = NULL;
RCL_SET_ERROR_MSG("failed to allocate memory for output topic", allocator) RCL_SET_ERROR_MSG("failed to allocate memory for output topic");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
} }
@ -168,7 +168,6 @@ rcl_expand_topic_name(
rcutils_strndup(next_opening_brace, substitution_substr_len, allocator); rcutils_strndup(next_opening_brace, substitution_substr_len, allocator);
if (unmatched_substitution) { if (unmatched_substitution) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING( RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
allocator,
"unknown substitution: %s", unmatched_substitution); "unknown substitution: %s", unmatched_substitution);
} else { } else {
RCUTILS_SAFE_FWRITE_TO_STDERR("failed to allocate memory for unmatched substitution\n"); RCUTILS_SAFE_FWRITE_TO_STDERR("failed to allocate memory for unmatched substitution\n");
@ -184,7 +183,7 @@ rcl_expand_topic_name(
rcutils_strndup(next_opening_brace, substitution_substr_len, allocator); rcutils_strndup(next_opening_brace, substitution_substr_len, allocator);
if (!next_substitution) { if (!next_substitution) {
*output_topic_name = NULL; *output_topic_name = NULL;
RCL_SET_ERROR_MSG("failed to allocate memory for substitution", allocator) RCL_SET_ERROR_MSG("failed to allocate memory for substitution");
allocator.deallocate(local_output, allocator.state); allocator.deallocate(local_output, allocator.state);
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -194,7 +193,7 @@ rcl_expand_topic_name(
allocator.deallocate(original_local_output, allocator.state); // free no matter what allocator.deallocate(original_local_output, allocator.state); // free no matter what
if (!local_output) { if (!local_output) {
*output_topic_name = NULL; *output_topic_name = NULL;
RCL_SET_ERROR_MSG("failed to allocate memory for expanded topic", allocator) RCL_SET_ERROR_MSG("failed to allocate memory for expanded topic");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
current_output = local_output; current_output = local_output;
@ -217,7 +216,7 @@ rcl_expand_topic_name(
} }
if (!local_output) { if (!local_output) {
*output_topic_name = NULL; *output_topic_name = NULL;
RCL_SET_ERROR_MSG("failed to allocate memory for output topic", allocator) RCL_SET_ERROR_MSG("failed to allocate memory for output topic");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
} }
@ -226,7 +225,7 @@ rcl_expand_topic_name(
local_output = rcutils_strdup(input_topic_name, allocator); local_output = rcutils_strdup(input_topic_name, allocator);
if (!local_output) { if (!local_output) {
*output_topic_name = NULL; *output_topic_name = NULL;
RCL_SET_ERROR_MSG("failed to allocate memory for output topic", allocator) RCL_SET_ERROR_MSG("failed to allocate memory for output topic");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
} }
@ -238,8 +237,7 @@ rcl_expand_topic_name(
rcl_ret_t rcl_ret_t
rcl_get_default_topic_name_substitutions(rcutils_string_map_t * string_map) rcl_get_default_topic_name_substitutions(rcutils_string_map_t * string_map)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(string_map, RCL_RET_INVALID_ARGUMENT);
string_map, RCL_RET_INVALID_ARGUMENT, rcutils_get_default_allocator())
// right now there are no default substitutions // right now there are no default substitutions

View file

@ -36,12 +36,12 @@ rcl_get_topic_names_and_types(
bool no_demangle, bool no_demangle,
rcl_names_and_types_t * topic_names_and_types) rcl_names_and_types_t * topic_names_and_types)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()) RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, allocator)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT, *allocator) RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret; rmw_ret_t rmw_ret;
rmw_ret = rmw_names_and_types_check_zero(topic_names_and_types); rmw_ret = rmw_names_and_types_check_zero(topic_names_and_types);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
@ -63,11 +63,11 @@ rcl_get_service_names_and_types(
rcl_allocator_t * allocator, rcl_allocator_t * allocator,
rcl_names_and_types_t * service_names_and_types) rcl_names_and_types_t * service_names_and_types)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, allocator)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(service_names_and_types, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(service_names_and_types, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret; rmw_ret_t rmw_ret;
rmw_ret = rmw_names_and_types_check_zero(service_names_and_types); rmw_ret = rmw_names_and_types_check_zero(service_names_and_types);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
@ -85,8 +85,7 @@ rcl_get_service_names_and_types(
rcl_ret_t rcl_ret_t
rcl_names_and_types_fini(rcl_names_and_types_t * topic_names_and_types) rcl_names_and_types_fini(rcl_names_and_types_t * topic_names_and_types)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT);
topic_names_and_types, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
rmw_ret_t rmw_ret = rmw_names_and_types_fini(topic_names_and_types); rmw_ret_t rmw_ret = rmw_names_and_types_fini(topic_names_and_types);
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
} }
@ -98,29 +97,29 @@ rcl_get_node_names(
rcutils_string_array_t * node_names, rcutils_string_array_t * node_names,
rcutils_string_array_t * node_namespaces) rcutils_string_array_t * node_namespaces)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, &allocator)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(node_names, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node_names, RCL_RET_INVALID_ARGUMENT);
if (node_names->size != 0) { if (node_names->size != 0) {
RCL_SET_ERROR_MSG("node_names size is not zero", allocator); RCL_SET_ERROR_MSG("node_names size is not zero");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
if (node_names->data) { if (node_names->data) {
RCL_SET_ERROR_MSG("node_names is not null", allocator); RCL_SET_ERROR_MSG("node_names is not null");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(node_namespaces, RCL_CHECK_ARGUMENT_FOR_NULL(node_namespaces, RCL_RET_INVALID_ARGUMENT);
RCL_RET_INVALID_ARGUMENT, allocator);
if (node_namespaces->size != 0) { if (node_namespaces->size != 0) {
RCL_SET_ERROR_MSG("node_namespaces size is not zero", allocator); RCL_SET_ERROR_MSG("node_namespaces size is not zero");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
if (node_namespaces->data) { if (node_namespaces->data) {
RCL_SET_ERROR_MSG("node_namespaces is not null", allocator); RCL_SET_ERROR_MSG("node_namespaces is not null");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
(void)allocator; // to be used in rmw_get_node_names in the future
rmw_ret_t rmw_ret = rmw_get_node_names( rmw_ret_t rmw_ret = rmw_get_node_names(
rcl_node_get_rmw_handle(node), rcl_node_get_rmw_handle(node),
node_names, node_names,
@ -134,16 +133,16 @@ rcl_count_publishers(
const char * topic_name, const char * topic_name,
size_t * count) size_t * count)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
const rcl_node_options_t * node_options = rcl_node_get_options(node); const rcl_node_options_t * node_options = rcl_node_get_options(node);
if (!node_options) { if (!node_options) {
return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so
} }
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, node_options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT, node_options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret = rmw_count_publishers(rcl_node_get_rmw_handle(node), topic_name, count); rmw_ret_t rmw_ret = rmw_count_publishers(rcl_node_get_rmw_handle(node), topic_name, count);
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
} }
@ -154,16 +153,16 @@ rcl_count_subscribers(
const char * topic_name, const char * topic_name,
size_t * count) size_t * count)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
const rcl_node_options_t * node_options = rcl_node_get_options(node); const rcl_node_options_t * node_options = rcl_node_get_options(node);
if (!node_options) { if (!node_options) {
return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so
} }
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, node_options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT, node_options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(count, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret = rmw_count_subscribers(rcl_node_get_rmw_handle(node), topic_name, count); rmw_ret_t rmw_ret = rmw_count_subscribers(rcl_node_get_rmw_handle(node), topic_name, count);
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
} }
@ -174,16 +173,16 @@ rcl_service_server_is_available(
const rcl_client_t * client, const rcl_client_t * client,
bool * is_available) bool * is_available)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
const rcl_node_options_t * node_options = rcl_node_get_options(node); const rcl_node_options_t * node_options = rcl_node_get_options(node);
if (!node_options) { if (!node_options) {
return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so return RCL_RET_NODE_INVALID; // shouldn't happen, but error is already set if so
} }
RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT, node_options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(client, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(is_available, RCL_RET_INVALID_ARGUMENT, node_options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(is_available, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t rmw_ret = rmw_service_server_is_available( rmw_ret_t rmw_ret = rmw_service_server_is_available(
rcl_node_get_rmw_handle(node), rcl_node_get_rmw_handle(node),
rcl_client_get_rmw_handle(client), rcl_client_get_rmw_handle(client),

View file

@ -49,23 +49,22 @@ __rcl_guard_condition_init_from_rmw_impl(
// Perform argument validation. // Perform argument validation.
const rcl_allocator_t * allocator = &options.allocator; const rcl_allocator_t * allocator = &options.allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT);
// Ensure the guard_condition handle is zero initialized. // Ensure the guard_condition handle is zero initialized.
if (guard_condition->impl) { if (guard_condition->impl) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("guard_condition already initialized, or memory was unintialized");
"guard_condition already initialized, or memory was unintialized", *allocator);
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Make sure rcl has been initialized. // Make sure rcl has been initialized.
if (!rcl_ok()) { if (!rcl_ok()) {
RCL_SET_ERROR_MSG("rcl_init() has not been called", *allocator); RCL_SET_ERROR_MSG("rcl_init() has not been called");
return RCL_RET_NOT_INIT; return RCL_RET_NOT_INIT;
} }
// Allocate space for the guard condition impl. // Allocate space for the guard condition impl.
guard_condition->impl = (rcl_guard_condition_impl_t *)allocator->allocate( guard_condition->impl = (rcl_guard_condition_impl_t *)allocator->allocate(
sizeof(rcl_guard_condition_impl_t), allocator->state); sizeof(rcl_guard_condition_impl_t), allocator->state);
if (!guard_condition->impl) { if (!guard_condition->impl) {
RCL_SET_ERROR_MSG("allocating memory failed", *allocator); RCL_SET_ERROR_MSG("allocating memory failed");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
// Create the rmw guard condition. // Create the rmw guard condition.
@ -79,7 +78,7 @@ __rcl_guard_condition_init_from_rmw_impl(
if (!guard_condition->impl->rmw_handle) { if (!guard_condition->impl->rmw_handle) {
// Deallocate impl and exit. // Deallocate impl and exit.
allocator->deallocate(guard_condition->impl, allocator->state); allocator->deallocate(guard_condition->impl, allocator->state);
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
guard_condition->impl->allocated_rmw_guard_condition = true; guard_condition->impl->allocated_rmw_guard_condition = true;
@ -111,15 +110,14 @@ rcl_ret_t
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition) rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition)
{ {
// Perform argument validation. // Perform argument validation.
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT);
guard_condition, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
rcl_ret_t result = RCL_RET_OK; rcl_ret_t result = RCL_RET_OK;
if (guard_condition->impl) { if (guard_condition->impl) {
// assuming the allocator is valid because it is checked in rcl_guard_condition_init() // assuming the allocator is valid because it is checked in rcl_guard_condition_init()
rcl_allocator_t allocator = guard_condition->impl->options.allocator; rcl_allocator_t allocator = guard_condition->impl->options.allocator;
if (guard_condition->impl->rmw_handle && guard_condition->impl->allocated_rmw_guard_condition) { if (guard_condition->impl->rmw_handle && guard_condition->impl->allocated_rmw_guard_condition) {
if (rmw_destroy_guard_condition(guard_condition->impl->rmw_handle) != RMW_RET_OK) { if (rmw_destroy_guard_condition(guard_condition->impl->rmw_handle) != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR; result = RCL_RET_ERROR;
} }
} }
@ -147,7 +145,7 @@ rcl_trigger_guard_condition(rcl_guard_condition_t * guard_condition)
} }
// Trigger the guard condition. // Trigger the guard condition.
if (rmw_trigger_guard_condition(guard_condition->impl->rmw_handle) != RMW_RET_OK) { if (rmw_trigger_guard_condition(guard_condition->impl->rmw_handle) != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), options->allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -157,12 +155,11 @@ const rcl_guard_condition_options_t *
rcl_guard_condition_get_options(const rcl_guard_condition_t * guard_condition) rcl_guard_condition_get_options(const rcl_guard_condition_t * guard_condition)
{ {
// Perform argument validation. // Perform argument validation.
RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, NULL, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, NULL);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
guard_condition->impl, guard_condition->impl,
"guard condition implementation is invalid", "guard condition implementation is invalid",
return NULL, return NULL);
rcl_get_default_allocator());
return &guard_condition->impl->options; return &guard_condition->impl->options;
} }

View file

@ -578,14 +578,12 @@ static const rcl_lexeme_t g_terminals[LAST_TERMINAL + 1] = {
rcl_ret_t rcl_ret_t
rcl_lexer_analyze( rcl_lexer_analyze(
const char * text, const char * text,
rcl_allocator_t alloc,
rcl_lexeme_t * lexeme, rcl_lexeme_t * lexeme,
size_t * length) size_t * length)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&alloc, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(text, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(text, RCL_RET_INVALID_ARGUMENT, alloc); RCL_CHECK_ARGUMENT_FOR_NULL(lexeme, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(lexeme, RCL_RET_INVALID_ARGUMENT, alloc); RCL_CHECK_ARGUMENT_FOR_NULL(length, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(length, RCL_RET_INVALID_ARGUMENT, alloc);
*length = 0u; *length = 0u;
@ -604,7 +602,7 @@ rcl_lexer_analyze(
do { do {
if (next_state > LAST_STATE) { if (next_state > LAST_STATE) {
// Should never happen // Should never happen
RCL_SET_ERROR_MSG("Internal lexer bug: next state does not exist", alloc); RCL_SET_ERROR_MSG("Internal lexer bug: next state does not exist");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
state = &(g_states[next_state]); state = &(g_states[next_state]);
@ -638,7 +636,7 @@ rcl_lexer_analyze(
// Go backwards N chars // Go backwards N chars
if (movement - 1u > *length) { if (movement - 1u > *length) {
// Should never happen // Should never happen
RCL_SET_ERROR_MSG("Internal lexer bug: movement would read before start of string", alloc); RCL_SET_ERROR_MSG("Internal lexer bug: movement would read before start of string");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
*length -= movement - 1u; *length -= movement - 1u;
@ -647,7 +645,7 @@ rcl_lexer_analyze(
if (FIRST_TERMINAL > next_state || next_state - FIRST_TERMINAL > LAST_TERMINAL) { if (FIRST_TERMINAL > next_state || next_state - FIRST_TERMINAL > LAST_TERMINAL) {
// Should never happen // Should never happen
RCL_SET_ERROR_MSG("Internal lexer bug: terminal state does not exist", alloc); RCL_SET_ERROR_MSG("Internal lexer bug: terminal state does not exist");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
*lexeme = g_terminals[next_state - FIRST_TERMINAL]; *lexeme = g_terminals[next_state - FIRST_TERMINAL];

View file

@ -49,16 +49,16 @@ rcl_lexer_lookahead2_init(
rcl_allocator_t allocator) rcl_allocator_t allocator)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(text, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(text, RCL_RET_INVALID_ARGUMENT);
if (NULL != buffer->impl) { if (NULL != buffer->impl) {
RCL_SET_ERROR_MSG("buffer must be zero initialized", allocator); RCL_SET_ERROR_MSG("buffer must be zero initialized");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
buffer->impl = allocator.allocate(sizeof(struct rcl_lexer_lookahead2_impl_t), allocator.state); buffer->impl = allocator.allocate(sizeof(struct rcl_lexer_lookahead2_impl_t), allocator.state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
buffer->impl, "Failed to allocate lookahead impl", return RCL_RET_BAD_ALLOC, allocator); buffer->impl, "Failed to allocate lookahead impl", return RCL_RET_BAD_ALLOC);
buffer->impl->text = text; buffer->impl->text = text;
buffer->impl->text_idx = 0u; buffer->impl->text_idx = 0u;
@ -77,10 +77,9 @@ rcl_ret_t
rcl_lexer_lookahead2_fini( rcl_lexer_lookahead2_fini(
rcl_lexer_lookahead2_t * buffer) rcl_lexer_lookahead2_t * buffer)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
buffer->impl, "buffer finalized twice", return RCL_RET_INVALID_ARGUMENT, buffer->impl, "buffer finalized twice", return RCL_RET_INVALID_ARGUMENT);
rcl_get_default_allocator());
RCL_CHECK_ALLOCATOR_WITH_MSG( RCL_CHECK_ALLOCATOR_WITH_MSG(
&(buffer->impl->allocator), "invalid allocator", return RCL_RET_INVALID_ARGUMENT); &(buffer->impl->allocator), "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
@ -94,11 +93,10 @@ rcl_lexer_lookahead2_peek(
rcl_lexer_lookahead2_t * buffer, rcl_lexer_lookahead2_t * buffer,
rcl_lexeme_t * next_type) rcl_lexeme_t * next_type)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
buffer->impl, "buffer not initialized", return RCL_RET_INVALID_ARGUMENT, buffer->impl, "buffer not initialized", return RCL_RET_INVALID_ARGUMENT);
rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(next_type, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(next_type, RCL_RET_INVALID_ARGUMENT, buffer->impl->allocator);
rcl_ret_t ret; rcl_ret_t ret;
size_t length; size_t length;
@ -107,7 +105,6 @@ rcl_lexer_lookahead2_peek(
// No buffered lexeme; get one // No buffered lexeme; get one
ret = rcl_lexer_analyze( ret = rcl_lexer_analyze(
rcl_lexer_lookahead2_get_text(buffer), rcl_lexer_lookahead2_get_text(buffer),
buffer->impl->allocator,
&(buffer->impl->type[0]), &(buffer->impl->type[0]),
&length); &length);
@ -135,7 +132,7 @@ rcl_lexer_lookahead2_peek2(
if (RCL_RET_OK != ret) { if (RCL_RET_OK != ret) {
return ret; return ret;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(next_type2, RCL_RET_INVALID_ARGUMENT, buffer->impl->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(next_type2, RCL_RET_INVALID_ARGUMENT);
size_t length; size_t length;
@ -143,7 +140,6 @@ rcl_lexer_lookahead2_peek2(
// No buffered lexeme; get one // No buffered lexeme; get one
ret = rcl_lexer_analyze( ret = rcl_lexer_analyze(
&(buffer->impl->text[buffer->impl->end[0]]), &(buffer->impl->text[buffer->impl->end[0]]),
buffer->impl->allocator,
&(buffer->impl->type[1]), &(buffer->impl->type[1]),
&length); &length);
@ -165,15 +161,14 @@ rcl_lexer_lookahead2_accept(
const char ** lexeme_text, const char ** lexeme_text,
size_t * lexeme_text_length) size_t * lexeme_text_length)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(buffer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
buffer->impl, "buffer not initialized", return RCL_RET_INVALID_ARGUMENT, buffer->impl, "buffer not initialized", return RCL_RET_INVALID_ARGUMENT);
rcl_get_default_allocator());
if ( if (
(NULL == lexeme_text && NULL != lexeme_text_length) || (NULL == lexeme_text && NULL != lexeme_text_length) ||
(NULL != lexeme_text && NULL == lexeme_text_length)) (NULL != lexeme_text && NULL == lexeme_text_length))
{ {
RCL_SET_ERROR_MSG("text and length must both be set or both be NULL", buffer->impl->allocator); RCL_SET_ERROR_MSG("text and length must both be set or both be NULL");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
@ -187,7 +182,7 @@ rcl_lexer_lookahead2_accept(
} }
if (buffer->impl->text_idx >= buffer->impl->end[0]) { if (buffer->impl->text_idx >= buffer->impl->end[0]) {
RCL_SET_ERROR_MSG("no lexeme to accept", buffer->impl->allocator); RCL_SET_ERROR_MSG("no lexeme to accept");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -224,12 +219,12 @@ rcl_lexer_lookahead2_expect(
if (type != lexeme) { if (type != lexeme) {
if (RCL_LEXEME_NONE == lexeme || RCL_LEXEME_EOF == lexeme) { if (RCL_LEXEME_NONE == lexeme || RCL_LEXEME_EOF == lexeme) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING( RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
buffer->impl->allocator, "Expected lexeme type (%d) not found, search ended at index %lu", "Expected lexeme type (%d) not found, search ended at index %lu",
type, buffer->impl->text_idx); type, buffer->impl->text_idx);
return RCL_RET_WRONG_LEXEME; return RCL_RET_WRONG_LEXEME;
} }
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING( RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
buffer->impl->allocator, "Expected lexeme type %d, got %d at index %lu", type, lexeme, "Expected lexeme type %d, got %d at index %lu", type, lexeme,
buffer->impl->text_idx); buffer->impl->text_idx);
return RCL_RET_WRONG_LEXEME; return RCL_RET_WRONG_LEXEME;
} }

View file

@ -147,34 +147,34 @@ rcl_node_init(
char * remapped_node_name = NULL; char * remapped_node_name = NULL;
// Check options and allocator first, so allocator can be used for errors. // Check options and allocator first, so allocator can be used for errors.
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = &options->allocator; const rcl_allocator_t * allocator = &options->allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(name, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(namespace_, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(namespace_, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Initializing node '%s' in namespace '%s'", name, namespace_); ROS_PACKAGE_NAME, "Initializing node '%s' in namespace '%s'", name, namespace_);
if (node->impl) { if (node->impl) {
RCL_SET_ERROR_MSG("node already initialized, or struct memory was unintialized", *allocator); RCL_SET_ERROR_MSG("node already initialized, or struct memory was unintialized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Make sure rcl has been initialized. // Make sure rcl has been initialized.
if (!rcl_ok()) { if (!rcl_ok()) {
RCL_SET_ERROR_MSG("rcl_init() has not been called", *allocator); RCL_SET_ERROR_MSG("rcl_init() has not been called");
return RCL_RET_NOT_INIT; return RCL_RET_NOT_INIT;
} }
// Make sure the node name is valid before allocating memory. // Make sure the node name is valid before allocating memory.
int validation_result = 0; int validation_result = 0;
ret = rmw_validate_node_name(name, &validation_result, NULL); ret = rmw_validate_node_name(name, &validation_result, NULL);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return ret; return ret;
} }
if (validation_result != RMW_NODE_NAME_VALID) { if (validation_result != RMW_NODE_NAME_VALID) {
const char * msg = rmw_node_name_validation_result_string(validation_result); const char * msg = rmw_node_name_validation_result_string(validation_result);
RCL_SET_ERROR_MSG(msg, *allocator); RCL_SET_ERROR_MSG(msg);
return RCL_RET_NODE_INVALID_NAME; return RCL_RET_NODE_INVALID_NAME;
} }
@ -190,26 +190,23 @@ rcl_node_init(
// If the namespace does not start with a /, add one. // If the namespace does not start with a /, add one.
if (namespace_length > 0 && namespace_[0] != '/') { if (namespace_length > 0 && namespace_[0] != '/') {
// TODO(wjwwood): replace with generic strcat that takes an allocator once available local_namespace_ = rcutils_format_string(*allocator, "/%s", namespace_);
// length + 2, because new leading / and terminating \0
char * temp = (char *)allocator->allocate(namespace_length + 2, allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
temp, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup, *allocator); local_namespace_,
temp[0] = '/'; "failed to format node namespace string",
memcpy(temp + 1, namespace_, strlen(namespace_) + 1); ret = RCL_RET_BAD_ALLOC; goto cleanup);
local_namespace_ = temp;
should_free_local_namespace_ = true; should_free_local_namespace_ = true;
} }
// Make sure the node namespace is valid. // Make sure the node namespace is valid.
validation_result = 0; validation_result = 0;
ret = rmw_validate_namespace(local_namespace_, &validation_result, NULL); ret = rmw_validate_namespace(local_namespace_, &validation_result, NULL);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
goto cleanup; goto cleanup;
} }
if (validation_result != RMW_NAMESPACE_VALID) { if (validation_result != RMW_NAMESPACE_VALID) {
const char * msg = rmw_namespace_validation_result_string(validation_result); const char * msg = rmw_namespace_validation_result_string(validation_result);
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING((*allocator), "%s, result: %d", msg, validation_result); RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("%s, result: %d", msg, validation_result);
ret = RCL_RET_NODE_INVALID_NAMESPACE; ret = RCL_RET_NODE_INVALID_NAMESPACE;
goto cleanup; goto cleanup;
@ -218,13 +215,13 @@ rcl_node_init(
// Allocate space for the implementation struct. // Allocate space for the implementation struct.
node->impl = (rcl_node_impl_t *)allocator->allocate(sizeof(rcl_node_impl_t), allocator->state); node->impl = (rcl_node_impl_t *)allocator->allocate(sizeof(rcl_node_impl_t), allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
node->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup, *allocator); node->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup);
node->impl->rmw_node_handle = NULL; node->impl->rmw_node_handle = NULL;
node->impl->graph_guard_condition = NULL; node->impl->graph_guard_condition = NULL;
node->impl->logger_name = NULL; node->impl->logger_name = NULL;
node->impl->options = rcl_node_get_default_options(); node->impl->options = rcl_node_get_default_options();
// Initialize node impl. // Initialize node impl.
ret = rcl_node_options_copy(*allocator, options, &(node->impl->options)); ret = rcl_node_options_copy(options, &(node->impl->options));
if (RCL_RET_OK != ret) { if (RCL_RET_OK != ret) {
goto fail; goto fail;
} }
@ -259,7 +256,7 @@ rcl_node_init(
// node logger name // node logger name
node->impl->logger_name = rcl_create_node_logger_name(name, local_namespace_, allocator); node->impl->logger_name = rcl_create_node_logger_name(name, local_namespace_, allocator);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
node->impl->logger_name, "creating logger name failed", goto fail, *allocator); node->impl->logger_name, "creating logger name failed", goto fail);
// node rmw_node_handle // node rmw_node_handle
if (node->impl->options.domain_id == RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID) { if (node->impl->options.domain_id == RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID) {
@ -271,7 +268,7 @@ rcl_node_init(
if (ros_domain_id) { if (ros_domain_id) {
unsigned long number = strtoul(ros_domain_id, NULL, 0); // NOLINT(runtime/int) unsigned long number = strtoul(ros_domain_id, NULL, 0); // NOLINT(runtime/int)
if (number == ULONG_MAX) { if (number == ULONG_MAX) {
RCL_SET_ERROR_MSG("failed to interpret ROS_DOMAIN_ID as integral number", *allocator); RCL_SET_ERROR_MSG("failed to interpret ROS_DOMAIN_ID as integral number");
goto fail; goto fail;
} }
domain_id = (size_t)number; domain_id = (size_t)number;
@ -289,7 +286,7 @@ rcl_node_init(
if (rcutils_get_env(ROS_SECURITY_ENABLE_VAR_NAME, &ros_security_enable)) { if (rcutils_get_env(ROS_SECURITY_ENABLE_VAR_NAME, &ros_security_enable)) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG(
"Environment variable " RCUTILS_STRINGIFY(ROS_SECURITY_ENABLE_VAR_NAME) "Environment variable " RCUTILS_STRINGIFY(ROS_SECURITY_ENABLE_VAR_NAME)
" could not be read", rcl_get_default_allocator()); " could not be read");
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto fail; goto fail;
} }
@ -301,7 +298,7 @@ rcl_node_init(
if (rcutils_get_env(ROS_SECURITY_STRATEGY_VAR_NAME, &ros_enforce_security)) { if (rcutils_get_env(ROS_SECURITY_STRATEGY_VAR_NAME, &ros_enforce_security)) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG(
"Environment variable " RCUTILS_STRINGIFY(ROS_SECURITY_STRATEGY_VAR_NAME) "Environment variable " RCUTILS_STRINGIFY(ROS_SECURITY_STRATEGY_VAR_NAME)
" could not be read", rcl_get_default_allocator()); " could not be read");
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto fail; goto fail;
} }
@ -323,7 +320,7 @@ rcl_node_init(
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG(
"SECURITY ERROR: unable to find a folder matching the node name in the " "SECURITY ERROR: unable to find a folder matching the node name in the "
RCUTILS_STRINGIFY(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME) RCUTILS_STRINGIFY(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME)
" directory while the requested security strategy requires it", *allocator); " directory while the requested security strategy requires it");
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
} }
@ -333,22 +330,20 @@ rcl_node_init(
name, local_namespace_, domain_id, &node_security_options); name, local_namespace_, domain_id, &node_security_options);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
node->impl->rmw_node_handle, rmw_get_error_string_safe(), goto fail, *allocator); node->impl->rmw_node_handle, rmw_get_error_string().str, goto fail);
// instance id // instance id
node->impl->rcl_instance_id = rcl_get_instance_id(); node->impl->rcl_instance_id = rcl_get_instance_id();
// graph guard condition // graph guard condition
rmw_graph_guard_condition = rmw_node_get_graph_guard_condition(node->impl->rmw_node_handle); rmw_graph_guard_condition = rmw_node_get_graph_guard_condition(node->impl->rmw_node_handle);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
rmw_graph_guard_condition, rmw_get_error_string_safe(), goto fail, *allocator); rmw_graph_guard_condition, rmw_get_error_string().str, goto fail);
node->impl->graph_guard_condition = (rcl_guard_condition_t *)allocator->allocate( node->impl->graph_guard_condition = (rcl_guard_condition_t *)allocator->allocate(
sizeof(rcl_guard_condition_t), allocator->state); sizeof(rcl_guard_condition_t), allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
node->impl->graph_guard_condition, node->impl->graph_guard_condition,
"allocating memory failed", "allocating memory failed",
goto fail, goto fail);
*allocator
);
*node->impl->graph_guard_condition = rcl_get_zero_initialized_guard_condition(); *node->impl->graph_guard_condition = rcl_get_zero_initialized_guard_condition();
graph_guard_condition_options.allocator = *allocator; graph_guard_condition_options.allocator = *allocator;
ret = rcl_guard_condition_init_from_rmw( ret = rcl_guard_condition_init_from_rmw(
@ -372,7 +367,7 @@ fail:
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"failed to fini rmw node in error recovery: %s", rmw_get_error_string_safe() "failed to fini rmw node in error recovery: %s", rmw_get_error_string().str
); );
} }
} }
@ -381,7 +376,7 @@ fail:
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"failed to fini guard condition in error recovery: %s", rcl_get_error_string_safe() "failed to fini guard condition in error recovery: %s", rcl_get_error_string().str
); );
} }
allocator->deallocate(node->impl->graph_guard_condition, allocator->state); allocator->deallocate(node->impl->graph_guard_condition, allocator->state);
@ -391,7 +386,7 @@ fail:
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"failed to fini arguments in error recovery: %s", rcl_get_error_string_safe() "failed to fini arguments in error recovery: %s", rcl_get_error_string().str
); );
} }
} }
@ -416,7 +411,7 @@ rcl_ret_t
rcl_node_fini(rcl_node_t * node) rcl_node_fini(rcl_node_t * node)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing node"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing node");
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!node->impl) { if (!node->impl) {
// Repeat calls to fini or calling fini on a zero initialized node is ok. // Repeat calls to fini or calling fini on a zero initialized node is ok.
return RCL_RET_OK; return RCL_RET_OK;
@ -425,12 +420,12 @@ rcl_node_fini(rcl_node_t * node)
rcl_ret_t result = RCL_RET_OK; rcl_ret_t result = RCL_RET_OK;
rmw_ret_t rmw_ret = rmw_destroy_node(node->impl->rmw_node_handle); rmw_ret_t rmw_ret = rmw_destroy_node(node->impl->rmw_node_handle);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR; result = RCL_RET_ERROR;
} }
rcl_ret_t rcl_ret = rcl_guard_condition_fini(node->impl->graph_guard_condition); rcl_ret_t rcl_ret = rcl_guard_condition_fini(node->impl->graph_guard_condition);
if (rcl_ret != RCL_RET_OK) { if (rcl_ret != RCL_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR; result = RCL_RET_ERROR;
} }
allocator.deallocate(node->impl->graph_guard_condition, allocator.state); allocator.deallocate(node->impl->graph_guard_condition, allocator.state);
@ -449,20 +444,17 @@ rcl_node_fini(rcl_node_t * node)
} }
bool bool
rcl_node_is_valid(const rcl_node_t * node, rcl_allocator_t * error_msg_allocator) rcl_node_is_valid(const rcl_node_t * node)
{ {
rcl_allocator_t alloc = error_msg_allocator ? *error_msg_allocator : rcl_get_default_allocator(); RCL_CHECK_ARGUMENT_FOR_NULL(node, false);
RCL_CHECK_ALLOCATOR_WITH_MSG(&alloc, "allocator is invalid", return false);
RCL_CHECK_ARGUMENT_FOR_NULL(node, false, alloc);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
node->impl, "rcl node implementation is invalid", return false, alloc); node->impl, "rcl node implementation is invalid", return false);
if (node->impl->rcl_instance_id != rcl_get_instance_id()) { if (node->impl->rcl_instance_id != rcl_get_instance_id()) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("rcl node is invalid, rcl instance id does not match");
"rcl node is invalid, rcl instance id does not match", alloc);
return false; return false;
} }
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
node->impl->rmw_node_handle, "rcl node's rmw handle is invalid", return false, alloc); node->impl->rmw_node_handle, "rcl node's rmw handle is invalid", return false);
return true; return true;
} }
@ -482,24 +474,20 @@ rcl_node_get_default_options()
rcl_ret_t rcl_ret_t
rcl_node_options_copy( rcl_node_options_copy(
rcl_allocator_t error_alloc,
const rcl_node_options_t * options, const rcl_node_options_t * options,
rcl_node_options_t * options_out) rcl_node_options_t * options_out)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&error_alloc, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT, error_alloc); RCL_CHECK_ARGUMENT_FOR_NULL(options_out, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(options_out, RCL_RET_INVALID_ARGUMENT, error_alloc);
if (options_out == options) { if (options_out == options) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("Attempted to copy options into itself");
"Attempted to copy options into itself", error_alloc);
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
options_out->domain_id = options->domain_id; options_out->domain_id = options->domain_id;
options_out->allocator = options->allocator; options_out->allocator = options->allocator;
options_out->use_global_arguments = options->use_global_arguments; options_out->use_global_arguments = options->use_global_arguments;
if (NULL != options->arguments.impl) { if (NULL != options->arguments.impl) {
rcl_ret_t ret = rcl_arguments_copy( rcl_ret_t ret = rcl_arguments_copy(&(options->arguments), &(options_out->arguments));
error_alloc, &(options->arguments), &(options_out->arguments));
return ret; return ret;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -508,7 +496,7 @@ rcl_node_options_copy(
const char * const char *
rcl_node_get_name(const rcl_node_t * node) rcl_node_get_name(const rcl_node_t * node)
{ {
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return NULL; return NULL;
} }
return node->impl->rmw_node_handle->name; return node->impl->rmw_node_handle->name;
@ -517,7 +505,7 @@ rcl_node_get_name(const rcl_node_t * node)
const char * const char *
rcl_node_get_namespace(const rcl_node_t * node) rcl_node_get_namespace(const rcl_node_t * node)
{ {
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return NULL; return NULL;
} }
return node->impl->rmw_node_handle->namespace_; return node->impl->rmw_node_handle->namespace_;
@ -526,7 +514,7 @@ rcl_node_get_namespace(const rcl_node_t * node)
const rcl_node_options_t * const rcl_node_options_t *
rcl_node_get_options(const rcl_node_t * node) rcl_node_get_options(const rcl_node_t * node)
{ {
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return NULL; return NULL;
} }
return &node->impl->options; return &node->impl->options;
@ -535,12 +523,12 @@ rcl_node_get_options(const rcl_node_t * node)
rcl_ret_t rcl_ret_t
rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id) rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
const rcl_node_options_t * node_options = rcl_node_get_options(node); const rcl_node_options_t * node_options = rcl_node_get_options(node);
if (!node_options) { if (!node_options) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(domain_id, RCL_RET_INVALID_ARGUMENT, node_options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(domain_id, RCL_RET_INVALID_ARGUMENT);
*domain_id = node->impl->actual_domain_id; *domain_id = node->impl->actual_domain_id;
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -548,7 +536,7 @@ rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id)
rmw_node_t * rmw_node_t *
rcl_node_get_rmw_handle(const rcl_node_t * node) rcl_node_get_rmw_handle(const rcl_node_t * node)
{ {
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return NULL; return NULL;
} }
return node->impl->rmw_node_handle; return node->impl->rmw_node_handle;
@ -557,16 +545,15 @@ rcl_node_get_rmw_handle(const rcl_node_t * node)
uint64_t uint64_t
rcl_node_get_rcl_instance_id(const rcl_node_t * node) rcl_node_get_rcl_instance_id(const rcl_node_t * node)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node, 0, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, 0);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(node->impl, "node implementation is invalid", return 0);
node->impl, "node implementation is invalid", return 0, rcl_get_default_allocator());
return node->impl->rcl_instance_id; return node->impl->rcl_instance_id;
} }
const struct rcl_guard_condition_t * const struct rcl_guard_condition_t *
rcl_node_get_graph_guard_condition(const rcl_node_t * node) rcl_node_get_graph_guard_condition(const rcl_node_t * node)
{ {
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return NULL; return NULL;
} }
return node->impl->graph_guard_condition; return node->impl->graph_guard_condition;
@ -575,7 +562,7 @@ rcl_node_get_graph_guard_condition(const rcl_node_t * node)
const char * const char *
rcl_node_get_logger_name(const rcl_node_t * node) rcl_node_get_logger_name(const rcl_node_t * node)
{ {
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return NULL; return NULL;
} }
return node->impl->logger_name; return node->impl->logger_name;

View file

@ -55,22 +55,21 @@ rcl_publisher_init(
rcl_ret_t fail_ret = RCL_RET_ERROR; rcl_ret_t fail_ret = RCL_RET_ERROR;
// Check options and allocator first, so allocator can be used with errors. // Check options and allocator first, so allocator can be used with errors.
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator; rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(publisher, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(publisher, RCL_RET_INVALID_ARGUMENT);
if (publisher->impl) { if (publisher->impl) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("publisher already initialized, or memory was unintialized");
"publisher already initialized, or memory was unintialized", *allocator);
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, allocator)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Initializing publisher for topic name '%s'", topic_name); ROS_PACKAGE_NAME, "Initializing publisher for topic name '%s'", topic_name);
// Expand the given topic name. // Expand the given topic name.
@ -78,7 +77,7 @@ rcl_publisher_init(
rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map(); rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map();
rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator); rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator) RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) { if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) {
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -92,7 +91,7 @@ rcl_publisher_init(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"failed to fini string_map (%d) during error handling: %s", "failed to fini string_map (%d) during error handling: %s",
rcutils_ret, rcutils_ret,
rcutils_get_error_string_safe()); rcutils_get_error_string().str);
} }
if (ret == RCL_RET_BAD_ALLOC) { if (ret == RCL_RET_BAD_ALLOC) {
return ret; return ret;
@ -110,7 +109,7 @@ rcl_publisher_init(
&expanded_topic_name); &expanded_topic_name);
rcutils_ret = rcutils_string_map_fini(&substitutions_map); rcutils_ret = rcutils_string_map_fini(&substitutions_map);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
} }
@ -147,12 +146,12 @@ rcl_publisher_init(
int validation_result; int validation_result;
rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_topic_name, &validation_result, NULL); rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_topic_name, &validation_result, NULL);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
} }
if (validation_result != RMW_TOPIC_VALID) { if (validation_result != RMW_TOPIC_VALID) {
RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result), *allocator) RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result));
ret = RCL_RET_TOPIC_NAME_INVALID; ret = RCL_RET_TOPIC_NAME_INVALID;
goto cleanup; goto cleanup;
} }
@ -160,7 +159,7 @@ rcl_publisher_init(
publisher->impl = (rcl_publisher_impl_t *)allocator->allocate( publisher->impl = (rcl_publisher_impl_t *)allocator->allocate(
sizeof(rcl_publisher_impl_t), allocator->state); sizeof(rcl_publisher_impl_t), allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
publisher->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup, *allocator); publisher->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup);
// Fill out implementation struct. // Fill out implementation struct.
// rmw handle (create rmw publisher) // rmw handle (create rmw publisher)
// TODO(wjwwood): pass along the allocator to rmw when it supports it // TODO(wjwwood): pass along the allocator to rmw when it supports it
@ -170,7 +169,7 @@ rcl_publisher_init(
remapped_topic_name, remapped_topic_name,
&(options->qos)); &(options->qos));
RCL_CHECK_FOR_NULL_WITH_MSG(publisher->impl->rmw_handle, RCL_CHECK_FOR_NULL_WITH_MSG(publisher->impl->rmw_handle,
rmw_get_error_string_safe(), goto fail, *allocator); rmw_get_error_string().str, goto fail);
// options // options
publisher->impl->options = *options; publisher->impl->options = *options;
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Publisher initialized"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Publisher initialized");
@ -195,9 +194,9 @@ rcl_ret_t
rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node) rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node)
{ {
rcl_ret_t result = RCL_RET_OK; rcl_ret_t result = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(publisher, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(publisher, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing publisher"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing publisher");
@ -210,7 +209,7 @@ rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node)
rmw_ret_t ret = rmw_ret_t ret =
rmw_destroy_publisher(rmw_node, publisher->impl->rmw_handle); rmw_destroy_publisher(rmw_node, publisher->impl->rmw_handle);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR; result = RCL_RET_ERROR;
} }
allocator.deallocate(publisher->impl, allocator.state); allocator.deallocate(publisher->impl, allocator.state);
@ -234,11 +233,11 @@ rcl_ret_t
rcl_publish(const rcl_publisher_t * publisher, const void * ros_message) rcl_publish(const rcl_publisher_t * publisher, const void * ros_message)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Publisher publishing message"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Publisher publishing message");
if (!rcl_publisher_is_valid(publisher, NULL)) { if (!rcl_publisher_is_valid(publisher)) {
return RCL_RET_PUBLISHER_INVALID; return RCL_RET_PUBLISHER_INVALID;
} }
if (rmw_publish(publisher->impl->rmw_handle, ros_message) != RMW_RET_OK) { if (rmw_publish(publisher->impl->rmw_handle, ros_message) != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), rcl_get_default_allocator()); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -248,12 +247,12 @@ rcl_ret_t
rcl_publish_serialized_message( rcl_publish_serialized_message(
const rcl_publisher_t * publisher, const rcl_serialized_message_t * serialized_message) const rcl_publisher_t * publisher, const rcl_serialized_message_t * serialized_message)
{ {
if (!rcl_publisher_is_valid(publisher, NULL)) { if (!rcl_publisher_is_valid(publisher)) {
return RCL_RET_PUBLISHER_INVALID; return RCL_RET_PUBLISHER_INVALID;
} }
rmw_ret_t ret = rmw_publish_serialized_message(publisher->impl->rmw_handle, serialized_message); rmw_ret_t ret = rmw_publish_serialized_message(publisher->impl->rmw_handle, serialized_message);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), rcl_get_default_allocator()); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
if (ret == RMW_RET_BAD_ALLOC) { if (ret == RMW_RET_BAD_ALLOC) {
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -265,7 +264,7 @@ rcl_publish_serialized_message(
const char * const char *
rcl_publisher_get_topic_name(const rcl_publisher_t * publisher) rcl_publisher_get_topic_name(const rcl_publisher_t * publisher)
{ {
if (!rcl_publisher_is_valid(publisher, NULL)) { if (!rcl_publisher_is_valid(publisher)) {
return NULL; return NULL;
} }
return publisher->impl->rmw_handle->topic_name; return publisher->impl->rmw_handle->topic_name;
@ -276,7 +275,7 @@ rcl_publisher_get_topic_name(const rcl_publisher_t * publisher)
const rcl_publisher_options_t * const rcl_publisher_options_t *
rcl_publisher_get_options(const rcl_publisher_t * publisher) rcl_publisher_get_options(const rcl_publisher_t * publisher)
{ {
if (!rcl_publisher_is_valid(publisher, NULL)) { if (!rcl_publisher_is_valid(publisher)) {
return NULL; return NULL;
} }
return _publisher_get_options(publisher); return _publisher_get_options(publisher);
@ -285,29 +284,24 @@ rcl_publisher_get_options(const rcl_publisher_t * publisher)
rmw_publisher_t * rmw_publisher_t *
rcl_publisher_get_rmw_handle(const rcl_publisher_t * publisher) rcl_publisher_get_rmw_handle(const rcl_publisher_t * publisher)
{ {
if (!rcl_publisher_is_valid(publisher, NULL)) { if (!rcl_publisher_is_valid(publisher)) {
return NULL; return NULL;
} }
return publisher->impl->rmw_handle; return publisher->impl->rmw_handle;
} }
bool bool
rcl_publisher_is_valid( rcl_publisher_is_valid(const rcl_publisher_t * publisher)
const rcl_publisher_t * publisher,
rcl_allocator_t * error_msg_allocator)
{ {
const rcl_publisher_options_t * options; const rcl_publisher_options_t * options;
rcl_allocator_t alloc = RCL_CHECK_ARGUMENT_FOR_NULL(publisher, false);
error_msg_allocator ? *error_msg_allocator : rcl_get_default_allocator();
RCL_CHECK_ALLOCATOR_WITH_MSG(&alloc, "allocator is invalid", return false);
RCL_CHECK_ARGUMENT_FOR_NULL(publisher, false, alloc);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
publisher->impl, "publisher implementation is invalid", return false, alloc); publisher->impl, "publisher implementation is invalid", return false);
options = _publisher_get_options(publisher); options = _publisher_get_options(publisher);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
options, "publisher's options pointer is invalid", return false, alloc); options, "publisher's options pointer is invalid", return false);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
publisher->impl->rmw_handle, "publisher's rmw handle is invalid", return false, alloc); publisher->impl->rmw_handle, "publisher's rmw handle is invalid", return false);
return true; return true;
} }

View file

@ -69,10 +69,10 @@ rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator)
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
if (argc > 0) { if (argc > 0) {
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
} }
if (rcl_atomic_exchange_bool(&__rcl_is_initialized, true)) { if (rcl_atomic_exchange_bool(&__rcl_is_initialized, true)) {
RCL_SET_ERROR_MSG("rcl_init called while already initialized", allocator); RCL_SET_ERROR_MSG("rcl_init called while already initialized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
@ -89,7 +89,7 @@ rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator)
// Initialize rmw_init. // Initialize rmw_init.
rmw_ret_t rmw_ret = rmw_init(); rmw_ret_t rmw_ret = rmw_init();
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
fail_ret = RCL_RET_ERROR; fail_ret = RCL_RET_ERROR;
goto fail; goto fail;
} }
@ -98,7 +98,7 @@ rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator)
__rcl_argc = argc; __rcl_argc = argc;
__rcl_argv = (char **)__rcl_allocator.allocate(sizeof(char *) * argc, __rcl_allocator.state); __rcl_argv = (char **)__rcl_allocator.allocate(sizeof(char *) * argc, __rcl_allocator.state);
if (!__rcl_argv) { if (!__rcl_argv) {
RCL_SET_ERROR_MSG("allocation failed", allocator); RCL_SET_ERROR_MSG("allocation failed");
fail_ret = RCL_RET_BAD_ALLOC; fail_ret = RCL_RET_BAD_ALLOC;
goto fail; goto fail;
} }
@ -107,7 +107,7 @@ rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator)
for (i = 0; i < argc; ++i) { for (i = 0; i < argc; ++i) {
__rcl_argv[i] = (char *)__rcl_allocator.allocate(strlen(argv[i]), __rcl_allocator.state); __rcl_argv[i] = (char *)__rcl_allocator.allocate(strlen(argv[i]), __rcl_allocator.state);
if (!__rcl_argv[i]) { if (!__rcl_argv[i]) {
RCL_SET_ERROR_MSG("allocation failed", allocator); RCL_SET_ERROR_MSG("allocation failed");
fail_ret = RCL_RET_BAD_ALLOC; fail_ret = RCL_RET_BAD_ALLOC;
goto fail; goto fail;
} }
@ -127,7 +127,7 @@ rcl_init(int argc, char const * const * argv, rcl_allocator_t allocator)
if (rcl_atomic_load_uint64_t(&__rcl_instance_id) == 0) { if (rcl_atomic_load_uint64_t(&__rcl_instance_id) == 0) {
// Roll over occurred. // Roll over occurred.
__rcl_next_unique_id--; // roll back to avoid the next call succeeding. __rcl_next_unique_id--; // roll back to avoid the next call succeeding.
RCL_SET_ERROR_MSG("unique rcl instance ids exhausted", allocator); RCL_SET_ERROR_MSG("unique rcl instance ids exhausted");
goto fail; goto fail;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -142,7 +142,7 @@ rcl_shutdown()
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Shutting down"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Shutting down");
if (!rcl_ok()) { if (!rcl_ok()) {
// must use default allocator here because __rcl_allocator may not be set yet // must use default allocator here because __rcl_allocator may not be set yet
RCL_SET_ERROR_MSG("rcl_shutdown called before rcl_init", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("rcl_shutdown called before rcl_init");
return RCL_RET_NOT_INIT; return RCL_RET_NOT_INIT;
} }
__clean_up_init(); __clean_up_init();

View file

@ -41,13 +41,11 @@ rcl_remap_get_zero_initialized()
rcl_ret_t rcl_ret_t
rcl_remap_copy( rcl_remap_copy(
rcl_allocator_t error_alloc,
const rcl_remap_t * rule, const rcl_remap_t * rule,
rcl_remap_t * rule_out) rcl_remap_t * rule_out)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&error_alloc, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(rule, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(rule, RCL_RET_INVALID_ARGUMENT, error_alloc); RCL_CHECK_ARGUMENT_FOR_NULL(rule_out, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(rule_out, RCL_RET_INVALID_ARGUMENT, error_alloc);
rcl_allocator_t allocator = rule->allocator; rcl_allocator_t allocator = rule->allocator;
rule_out->allocator = allocator; rule_out->allocator = allocator;
@ -73,7 +71,7 @@ rcl_remap_copy(
return RCL_RET_OK; return RCL_RET_OK;
fail: fail:
if (RCL_RET_OK != rcl_remap_fini(rule_out)) { if (RCL_RET_OK != rcl_remap_fini(rule_out)) {
RCL_SET_ERROR_MSG("Error while finalizing remap rule due to another error", error_alloc); RCL_SET_ERROR_MSG("Error while finalizing remap rule due to another error");
} }
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -170,8 +168,8 @@ _rcl_remap_name(
rcl_allocator_t allocator, rcl_allocator_t allocator,
char ** output_name) char ** output_name)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(output_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(output_name, RCL_RET_INVALID_ARGUMENT);
if (NULL != local_arguments && NULL == local_arguments->impl) { if (NULL != local_arguments && NULL == local_arguments->impl) {
local_arguments = NULL; local_arguments = NULL;
} }
@ -179,7 +177,7 @@ _rcl_remap_name(
global_arguments = NULL; global_arguments = NULL;
} }
if (NULL == local_arguments && NULL == global_arguments) { if (NULL == local_arguments && NULL == global_arguments) {
RCL_SET_ERROR_MSG("local_arguments invalid and not using global arguments", allocator); RCL_SET_ERROR_MSG("local_arguments invalid and not using global arguments");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
@ -218,7 +216,7 @@ _rcl_remap_name(
*output_name = rcutils_strdup(rule->replacement, allocator); *output_name = rcutils_strdup(rule->replacement, allocator);
} }
if (NULL == *output_name) { if (NULL == *output_name) {
RCL_SET_ERROR_MSG("Failed to set output", allocator); RCL_SET_ERROR_MSG("Failed to set output");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
} }
@ -236,7 +234,7 @@ rcl_remap_topic_name(
char ** output_name) char ** output_name)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
rcutils_string_map_t substitutions = rcutils_get_zero_initialized_string_map(); rcutils_string_map_t substitutions = rcutils_get_zero_initialized_string_map();
rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions, 0, allocator); rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions, 0, allocator);
@ -266,7 +264,7 @@ rcl_remap_service_name(
char ** output_name) char ** output_name)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(service_name, RCL_RET_INVALID_ARGUMENT);
rcutils_string_map_t substitutions = rcutils_get_zero_initialized_string_map(); rcutils_string_map_t substitutions = rcutils_get_zero_initialized_string_map();
rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions, 0, allocator); rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions, 0, allocator);

View file

@ -15,7 +15,10 @@
#ifndef RCL__REMAP_IMPL_H_ #ifndef RCL__REMAP_IMPL_H_
#define RCL__REMAP_IMPL_H_ #define RCL__REMAP_IMPL_H_
#include "rcl/allocator.h"
#include "rcl/macros.h"
#include "rcl/types.h" #include "rcl/types.h"
#include "rcl/visibility_control.h"
#ifdef __cplusplus #ifdef __cplusplus
extern "C" extern "C"
@ -61,8 +64,6 @@ rcl_remap_get_zero_initialized();
* Uses Atomics | No * Uses Atomics | No
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] error_alloc an alocator to use if an error occurs.
* This allocator is not used to allocate rule_out.
* \param[in] rule The structure to be copied. * \param[in] rule 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] rule_out A zero-initialized rcl_remap_t structure to be copied into. * \param[out] rule_out A zero-initialized rcl_remap_t structure to be copied into.
@ -75,7 +76,6 @@ RCL_PUBLIC
RCL_WARN_UNUSED RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_remap_copy( rcl_remap_copy(
rcl_allocator_t error_alloc,
const rcl_remap_t * rule, const rcl_remap_t * rule,
rcl_remap_t * rule_out); rcl_remap_t * rule_out);

View file

@ -64,7 +64,7 @@ INITIALIZER(initialize) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"Error getting environment variable 'RMW_IMPLEMENTATION': %s", "Error getting environment variable 'RMW_IMPLEMENTATION': %s",
rcl_get_error_string_safe() rcl_get_error_string().str
); );
exit(ret); exit(ret);
} }
@ -84,7 +84,7 @@ INITIALIZER(initialize) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"Error getting environment variable 'RCL_ASSERT_RMW_ID_MATCHES': %s", "Error getting environment variable 'RCL_ASSERT_RMW_ID_MATCHES': %s",
rcl_get_error_string_safe() rcl_get_error_string().str
); );
exit(ret); exit(ret);
} }

View file

@ -54,21 +54,21 @@ rcl_service_init(
rcl_ret_t fail_ret = RCL_RET_ERROR; rcl_ret_t fail_ret = RCL_RET_ERROR;
// Check options and allocator first, so the allocator can be used in errors. // Check options and allocator first, so the allocator can be used in errors.
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator; rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(service, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, allocator)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(service_name, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(service_name, RCL_RET_INVALID_ARGUMENT);
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Initializing service for service name '%s'", service_name); ROS_PACKAGE_NAME, "Initializing service for service name '%s'", service_name);
if (service->impl) { if (service->impl) {
RCL_SET_ERROR_MSG("service already initialized, or memory was unintialized", *allocator); RCL_SET_ERROR_MSG("service already initialized, or memory was unintialized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Expand the given service name. // Expand the given service name.
@ -76,7 +76,7 @@ rcl_service_init(
rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map(); rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map();
rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator); rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator) RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) { if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) {
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -90,7 +90,7 @@ rcl_service_init(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"failed to fini string_map (%d) during error handling: %s", "failed to fini string_map (%d) during error handling: %s",
rcutils_ret, rcutils_ret,
rcutils_get_error_string_safe()); rcutils_get_error_string().str);
} }
if (ret == RCL_RET_BAD_ALLOC) { if (ret == RCL_RET_BAD_ALLOC) {
return ret; return ret;
@ -108,7 +108,7 @@ rcl_service_init(
&expanded_service_name); &expanded_service_name);
rcutils_ret = rcutils_string_map_fini(&substitutions_map); rcutils_ret = rcutils_string_map_fini(&substitutions_map);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator) RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
return RCL_RET_ERROR; return RCL_RET_ERROR;
@ -146,12 +146,12 @@ rcl_service_init(
int validation_result; int validation_result;
rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_service_name, &validation_result, NULL); rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_service_name, &validation_result, NULL);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
} }
if (validation_result != RMW_TOPIC_VALID) { if (validation_result != RMW_TOPIC_VALID) {
RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result), *allocator) RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result));
ret = RCL_RET_SERVICE_NAME_INVALID; ret = RCL_RET_SERVICE_NAME_INVALID;
goto cleanup; goto cleanup;
} }
@ -159,7 +159,7 @@ rcl_service_init(
service->impl = (rcl_service_impl_t *)allocator->allocate( service->impl = (rcl_service_impl_t *)allocator->allocate(
sizeof(rcl_service_impl_t), allocator->state); sizeof(rcl_service_impl_t), allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
service->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup, *allocator); service->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup);
if (RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL == options->qos.durability) { if (RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL == options->qos.durability) {
RCUTILS_LOG_WARN_NAMED( RCUTILS_LOG_WARN_NAMED(
@ -176,7 +176,7 @@ rcl_service_init(
remapped_service_name, remapped_service_name,
&options->qos); &options->qos);
if (!service->impl->rmw_handle) { if (!service->impl->rmw_handle) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
goto fail; goto fail;
} }
// options // options
@ -205,9 +205,9 @@ rcl_service_fini(rcl_service_t * service, rcl_node_t * node)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing service"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing service");
rcl_ret_t result = RCL_RET_OK; rcl_ret_t result = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(service, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(service, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
if (service->impl) { if (service->impl) {
@ -218,7 +218,7 @@ rcl_service_fini(rcl_service_t * service, rcl_node_t * node)
} }
rmw_ret_t ret = rmw_destroy_service(rmw_node, service->impl->rmw_handle); rmw_ret_t ret = rmw_destroy_service(rmw_node, service->impl->rmw_handle);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR; result = RCL_RET_ERROR;
} }
allocator.deallocate(service->impl, allocator.state); allocator.deallocate(service->impl, allocator.state);
@ -245,8 +245,7 @@ rcl_service_get_service_name(const rcl_service_t * service)
if (!options) { if (!options) {
return NULL; return NULL;
} }
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(service->impl->rmw_handle, "service is invalid", return NULL);
service->impl->rmw_handle, "service is invalid", return NULL, options->allocator);
return service->impl->rmw_handle->service_name; return service->impl->rmw_handle->service_name;
} }
@ -255,7 +254,7 @@ rcl_service_get_service_name(const rcl_service_t * service)
const rcl_service_options_t * const rcl_service_options_t *
rcl_service_get_options(const rcl_service_t * service) rcl_service_get_options(const rcl_service_t * service)
{ {
if (!rcl_service_is_valid(service, NULL)) { if (!rcl_service_is_valid(service)) {
return NULL; return NULL;
} }
return _service_get_options(service); return _service_get_options(service);
@ -264,7 +263,7 @@ rcl_service_get_options(const rcl_service_t * service)
rmw_service_t * rmw_service_t *
rcl_service_get_rmw_handle(const rcl_service_t * service) rcl_service_get_rmw_handle(const rcl_service_t * service)
{ {
if (!rcl_service_is_valid(service, NULL)) { if (!rcl_service_is_valid(service)) {
return NULL; return NULL;
} }
return service->impl->rmw_handle; return service->impl->rmw_handle;
@ -279,15 +278,15 @@ rcl_take_request(
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Service server taking service request"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Service server taking service request");
const rcl_service_options_t * options = rcl_service_get_options(service); const rcl_service_options_t * options = rcl_service_get_options(service);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
options, "Failed to get service options", return RCL_RET_ERROR, rcl_get_default_allocator()); options, "Failed to get service options", return RCL_RET_ERROR);
RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT, options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(ros_request, RCL_RET_INVALID_ARGUMENT, options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(ros_request, RCL_RET_INVALID_ARGUMENT);
bool taken = false; bool taken = false;
if (rmw_take_request( if (rmw_take_request(
service->impl->rmw_handle, request_header, ros_request, &taken) != RMW_RET_OK) service->impl->rmw_handle, request_header, ros_request, &taken) != RMW_RET_OK)
{ {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), options->allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
@ -307,34 +306,31 @@ rcl_send_response(
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Sending service response"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Sending service response");
const rcl_service_options_t * options = rcl_service_get_options(service); const rcl_service_options_t * options = rcl_service_get_options(service);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
options, "Failed to get service options", return RCL_RET_ERROR, rcl_get_default_allocator()); options, "Failed to get service options", return RCL_RET_ERROR);
RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT, options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(request_header, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(ros_response, RCL_RET_INVALID_ARGUMENT, options->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(ros_response, RCL_RET_INVALID_ARGUMENT);
if (rmw_send_response( if (rmw_send_response(
service->impl->rmw_handle, request_header, ros_response) != RMW_RET_OK) service->impl->rmw_handle, request_header, ros_response) != RMW_RET_OK)
{ {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), options->allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
return RCL_RET_OK; return RCL_RET_OK;
} }
bool bool
rcl_service_is_valid(const rcl_service_t * service, rcl_allocator_t * error_msg_allocator) rcl_service_is_valid(const rcl_service_t * service)
{ {
const rcl_service_options_t * options; const rcl_service_options_t * options;
rcl_allocator_t alloc = RCL_CHECK_ARGUMENT_FOR_NULL(service, false);
error_msg_allocator ? *error_msg_allocator : rcl_get_default_allocator();
RCL_CHECK_ALLOCATOR_WITH_MSG(&alloc, "allocator is invalid", return false);
RCL_CHECK_ARGUMENT_FOR_NULL(service, false, alloc);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
service->impl, "service's implementation is invalid", return false, alloc); service->impl, "service's implementation is invalid", return false);
options = _service_get_options(service); options = _service_get_options(service);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
options, "service's options pointer is invalid", return false, alloc); options, "service's options pointer is invalid", return false);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
service->impl->rmw_handle, "service's rmw handle is invalid", return false, alloc); service->impl->rmw_handle, "service's rmw handle is invalid", return false);
return true; return true;
} }

View file

@ -53,21 +53,21 @@ rcl_subscription_init(
rcl_ret_t fail_ret = RCL_RET_ERROR; rcl_ret_t fail_ret = RCL_RET_ERROR;
// Check options and allocator first, so the allocator can be used in errors. // Check options and allocator first, so the allocator can be used in errors.
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator; rcl_allocator_t * allocator = (rcl_allocator_t *)&options->allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, allocator)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(type_support, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, *allocator); RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Initializing subscription for topic name '%s'", topic_name); ROS_PACKAGE_NAME, "Initializing subscription for topic name '%s'", topic_name);
if (subscription->impl) { if (subscription->impl) {
RCL_SET_ERROR_MSG("subscription already initialized, or memory was uninitialized", *allocator); RCL_SET_ERROR_MSG("subscription already initialized, or memory was uninitialized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Expand the given topic name. // Expand the given topic name.
@ -75,7 +75,7 @@ rcl_subscription_init(
rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map(); rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map();
rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator); rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator) RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) { if (rcutils_ret == RCUTILS_RET_BAD_ALLOC) {
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -89,7 +89,7 @@ rcl_subscription_init(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"failed to fini string_map (%d) during error handling: %s", "failed to fini string_map (%d) during error handling: %s",
rcutils_ret, rcutils_ret,
rcutils_get_error_string_safe()); rcutils_get_error_string().str);
} }
if (ret == RCL_RET_BAD_ALLOC) { if (ret == RCL_RET_BAD_ALLOC) {
return ret; return ret;
@ -107,7 +107,7 @@ rcl_subscription_init(
&expanded_topic_name); &expanded_topic_name);
rcutils_ret = rcutils_string_map_fini(&substitutions_map); rcutils_ret = rcutils_string_map_fini(&substitutions_map);
if (rcutils_ret != RCUTILS_RET_OK) { if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string_safe(), *allocator) RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
} }
@ -144,12 +144,12 @@ rcl_subscription_init(
int validation_result; int validation_result;
rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_topic_name, &validation_result, NULL); rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_topic_name, &validation_result, NULL);
if (rmw_ret != RMW_RET_OK) { if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
ret = RCL_RET_ERROR; ret = RCL_RET_ERROR;
goto cleanup; goto cleanup;
} }
if (validation_result != RMW_TOPIC_VALID) { if (validation_result != RMW_TOPIC_VALID) {
RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result), *allocator) RCL_SET_ERROR_MSG(rmw_full_topic_name_validation_result_string(validation_result));
ret = RCL_RET_TOPIC_NAME_INVALID; ret = RCL_RET_TOPIC_NAME_INVALID;
goto cleanup; goto cleanup;
} }
@ -157,8 +157,7 @@ rcl_subscription_init(
subscription->impl = (rcl_subscription_impl_t *)allocator->allocate( subscription->impl = (rcl_subscription_impl_t *)allocator->allocate(
sizeof(rcl_subscription_impl_t), allocator->state); sizeof(rcl_subscription_impl_t), allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
subscription->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup, subscription->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup);
*allocator);
// Fill out the implemenation struct. // Fill out the implemenation struct.
// rmw_handle // rmw_handle
// TODO(wjwwood): pass allocator once supported in rmw api. // TODO(wjwwood): pass allocator once supported in rmw api.
@ -169,7 +168,7 @@ rcl_subscription_init(
&(options->qos), &(options->qos),
options->ignore_local_publications); options->ignore_local_publications);
if (!subscription->impl->rmw_handle) { if (!subscription->impl->rmw_handle) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), *allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
goto fail; goto fail;
} }
// options // options
@ -198,9 +197,9 @@ rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing subscription"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Finalizing subscription");
rcl_ret_t result = RCL_RET_OK; rcl_ret_t result = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(subscription, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
if (!rcl_node_is_valid(node, NULL)) { if (!rcl_node_is_valid(node)) {
return RCL_RET_NODE_INVALID; return RCL_RET_NODE_INVALID;
} }
if (subscription->impl) { if (subscription->impl) {
@ -212,7 +211,7 @@ rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node)
rmw_ret_t ret = rmw_ret_t ret =
rmw_destroy_subscription(rmw_node, subscription->impl->rmw_handle); rmw_destroy_subscription(rmw_node, subscription->impl->rmw_handle);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR; result = RCL_RET_ERROR;
} }
allocator.deallocate(subscription->impl, allocator.state); allocator.deallocate(subscription->impl, allocator.state);
@ -241,12 +240,11 @@ rcl_take(
rmw_message_info_t * message_info) rmw_message_info_t * message_info)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking message"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking message");
rcl_allocator_t error_allocator = rcl_get_default_allocator(); if (!rcl_subscription_is_valid(subscription)) {
if (!rcl_subscription_is_valid(subscription, &error_allocator)) {
return RCL_RET_SUBSCRIPTION_INVALID; // error message already set return RCL_RET_SUBSCRIPTION_INVALID; // error message already set
} }
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(
ros_message, RCL_RET_INVALID_ARGUMENT, error_allocator); ros_message, RCL_RET_INVALID_ARGUMENT);
// If message_info is NULL, use a place holder which can be discarded. // If message_info is NULL, use a place holder which can be discarded.
rmw_message_info_t dummy_message_info; rmw_message_info_t dummy_message_info;
rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info; rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
@ -255,7 +253,7 @@ rcl_take(
rmw_ret_t ret = rmw_ret_t ret =
rmw_take_with_info(subscription->impl->rmw_handle, ros_message, &taken, message_info_local); rmw_take_with_info(subscription->impl->rmw_handle, ros_message, &taken, message_info_local);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), error_allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
@ -273,12 +271,10 @@ rcl_take_serialized_message(
rmw_message_info_t * message_info) rmw_message_info_t * message_info)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking serialized message"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking serialized message");
rcl_allocator_t error_allocator = rcl_get_default_allocator(); if (!rcl_subscription_is_valid(subscription)) {
if (!rcl_subscription_is_valid(subscription, &error_allocator)) {
return RCL_RET_SUBSCRIPTION_INVALID; // error message already set return RCL_RET_SUBSCRIPTION_INVALID; // error message already set
} }
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(serialized_message, RCL_RET_INVALID_ARGUMENT);
serialized_message, RCL_RET_INVALID_ARGUMENT, error_allocator);
// If message_info is NULL, use a place holder which can be discarded. // If message_info is NULL, use a place holder which can be discarded.
rmw_message_info_t dummy_message_info; rmw_message_info_t dummy_message_info;
rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info; rmw_message_info_t * message_info_local = message_info ? message_info : &dummy_message_info;
@ -287,7 +283,7 @@ rcl_take_serialized_message(
rmw_ret_t ret = rmw_take_serialized_message_with_info( rmw_ret_t ret = rmw_take_serialized_message_with_info(
subscription->impl->rmw_handle, serialized_message, &taken, message_info_local); subscription->impl->rmw_handle, serialized_message, &taken, message_info_local);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), error_allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
if (ret == RMW_RET_BAD_ALLOC) { if (ret == RMW_RET_BAD_ALLOC) {
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -304,7 +300,7 @@ rcl_take_serialized_message(
const char * const char *
rcl_subscription_get_topic_name(const rcl_subscription_t * subscription) rcl_subscription_get_topic_name(const rcl_subscription_t * subscription)
{ {
if (!rcl_subscription_is_valid(subscription, NULL)) { if (!rcl_subscription_is_valid(subscription)) {
return NULL; return NULL;
} }
return subscription->impl->rmw_handle->topic_name; return subscription->impl->rmw_handle->topic_name;
@ -315,7 +311,7 @@ rcl_subscription_get_topic_name(const rcl_subscription_t * subscription)
const rcl_subscription_options_t * const rcl_subscription_options_t *
rcl_subscription_get_options(const rcl_subscription_t * subscription) rcl_subscription_get_options(const rcl_subscription_t * subscription)
{ {
if (!rcl_subscription_is_valid(subscription, NULL)) { if (!rcl_subscription_is_valid(subscription)) {
return NULL; return NULL;
} }
return _subscription_get_options(subscription); return _subscription_get_options(subscription);
@ -324,35 +320,28 @@ rcl_subscription_get_options(const rcl_subscription_t * subscription)
rmw_subscription_t * rmw_subscription_t *
rcl_subscription_get_rmw_handle(const rcl_subscription_t * subscription) rcl_subscription_get_rmw_handle(const rcl_subscription_t * subscription)
{ {
if (!rcl_subscription_is_valid(subscription, NULL)) { if (!rcl_subscription_is_valid(subscription)) {
return NULL; return NULL;
} }
return subscription->impl->rmw_handle; return subscription->impl->rmw_handle;
} }
bool bool
rcl_subscription_is_valid( rcl_subscription_is_valid(const rcl_subscription_t * subscription)
const rcl_subscription_t * subscription,
rcl_allocator_t * error_msg_allocator)
{ {
const rcl_subscription_options_t * options; const rcl_subscription_options_t * options;
rcl_allocator_t alloc = RCL_CHECK_ARGUMENT_FOR_NULL(subscription, false);
error_msg_allocator ? *error_msg_allocator : rcl_get_default_allocator();
RCL_CHECK_ALLOCATOR_WITH_MSG(&alloc, "allocator is invalid", return false);
RCL_CHECK_ARGUMENT_FOR_NULL(subscription, false, rcl_get_default_allocator());
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
subscription->impl, subscription->impl,
"subscription's implementation is invalid", "subscription's implementation is invalid",
return false, return false);
alloc);
options = _subscription_get_options(subscription); options = _subscription_get_options(subscription);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
options, "subscription's option pointer is invalid", return false, alloc); options, "subscription's option pointer is invalid", return false);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
subscription->impl->rmw_handle, subscription->impl->rmw_handle,
"subscription's rmw handle is invalid", "subscription's rmw handle is invalid",
return false, return false);
alloc);
return true; return true;
} }

View file

@ -91,8 +91,7 @@ rcl_clock_init(
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
switch (clock_type) { switch (clock_type) {
case RCL_CLOCK_UNINITIALIZED: case RCL_CLOCK_UNINITIALIZED:
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
rcl_init_generic_clock(clock); rcl_init_generic_clock(clock);
return RCL_RET_OK; return RCL_RET_OK;
case RCL_ROS_TIME: case RCL_ROS_TIME:
@ -122,7 +121,7 @@ rcl_ret_t
rcl_clock_fini( rcl_clock_fini(
rcl_clock_t * clock) rcl_clock_t * clock)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&clock->allocator, "clock has invalid allocator", RCL_CHECK_ALLOCATOR_WITH_MSG(&clock->allocator, "clock has invalid allocator",
return RCL_RET_ERROR); return RCL_RET_ERROR);
switch (clock->type) { switch (clock->type) {
@ -144,8 +143,8 @@ rcl_ros_clock_init(
rcl_clock_t * clock, rcl_clock_t * clock,
rcl_allocator_t * allocator) rcl_allocator_t * allocator)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
rcl_init_generic_clock(clock); rcl_init_generic_clock(clock);
clock->data = allocator->allocate(sizeof(rcl_ros_clock_storage_t), allocator->state); clock->data = allocator->allocate(sizeof(rcl_ros_clock_storage_t), allocator->state);
rcl_ros_clock_storage_t * storage = (rcl_ros_clock_storage_t *)clock->data; rcl_ros_clock_storage_t * storage = (rcl_ros_clock_storage_t *)clock->data;
@ -162,14 +161,14 @@ rcl_ret_t
rcl_ros_clock_fini( rcl_ros_clock_fini(
rcl_clock_t * clock) rcl_clock_t * clock)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
if (clock->type != RCL_ROS_TIME) { if (clock->type != RCL_ROS_TIME) {
RCL_SET_ERROR_MSG("clock not of type RCL_ROS_TIME", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("clock not of type RCL_ROS_TIME");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
_rcl_clock_generic_fini(clock); _rcl_clock_generic_fini(clock);
if (!clock->data) { if (!clock->data) {
RCL_SET_ERROR_MSG("clock data invalid", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("clock data invalid");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
clock->allocator.deallocate((rcl_ros_clock_storage_t *)clock->data, clock->allocator.state); clock->allocator.deallocate((rcl_ros_clock_storage_t *)clock->data, clock->allocator.state);
@ -181,8 +180,8 @@ rcl_steady_clock_init(
rcl_clock_t * clock, rcl_clock_t * clock,
rcl_allocator_t * allocator) rcl_allocator_t * allocator)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
rcl_init_generic_clock(clock); rcl_init_generic_clock(clock);
clock->get_now = rcl_get_steady_time; clock->get_now = rcl_get_steady_time;
clock->type = RCL_STEADY_TIME; clock->type = RCL_STEADY_TIME;
@ -194,9 +193,9 @@ rcl_ret_t
rcl_steady_clock_fini( rcl_steady_clock_fini(
rcl_clock_t * clock) rcl_clock_t * clock)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
if (clock->type != RCL_STEADY_TIME) { if (clock->type != RCL_STEADY_TIME) {
RCL_SET_ERROR_MSG("clock not of type RCL_STEADY_TIME", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("clock not of type RCL_STEADY_TIME");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
_rcl_clock_generic_fini(clock); _rcl_clock_generic_fini(clock);
@ -208,8 +207,8 @@ rcl_system_clock_init(
rcl_clock_t * clock, rcl_clock_t * clock,
rcl_allocator_t * allocator) rcl_allocator_t * allocator)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
rcl_init_generic_clock(clock); rcl_init_generic_clock(clock);
clock->get_now = rcl_get_system_time; clock->get_now = rcl_get_system_time;
clock->type = RCL_SYSTEM_TIME; clock->type = RCL_SYSTEM_TIME;
@ -221,9 +220,9 @@ rcl_ret_t
rcl_system_clock_fini( rcl_system_clock_fini(
rcl_clock_t * clock) rcl_clock_t * clock)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
if (clock->type != RCL_SYSTEM_TIME) { if (clock->type != RCL_SYSTEM_TIME) {
RCL_SET_ERROR_MSG("clock not of type RCL_SYSTEM_TIME", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("clock not of type RCL_SYSTEM_TIME");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
_rcl_clock_generic_fini(clock); _rcl_clock_generic_fini(clock);
@ -235,9 +234,7 @@ rcl_difference_times(
rcl_time_point_t * start, rcl_time_point_t * finish, rcl_duration_t * delta) rcl_time_point_t * start, rcl_time_point_t * finish, rcl_duration_t * delta)
{ {
if (start->clock_type != finish->clock_type) { if (start->clock_type != finish->clock_type) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("Cannot difference between time points with clocks types.");
"Cannot difference between time points with clocks types.",
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (finish->nanoseconds < start->nanoseconds) { if (finish->nanoseconds < start->nanoseconds) {
@ -252,15 +249,12 @@ rcl_difference_times(
rcl_ret_t rcl_ret_t
rcl_clock_get_now(rcl_clock_t * clock, rcl_time_point_value_t * time_point_value) rcl_clock_get_now(rcl_clock_t * clock, rcl_time_point_value_t * time_point_value)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(time_point_value, RCL_RET_INVALID_ARGUMENT);
time_point_value, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator());
if (clock->type && clock->get_now) { if (clock->type && clock->get_now) {
return clock->get_now(clock->data, time_point_value); return clock->get_now(clock->data, time_point_value);
} }
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("Clock is not initialized or does not have get_now registered.");
"Clock is not initialized or does not have get_now registered.",
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -288,16 +282,14 @@ _rcl_clock_call_callbacks(
rcl_ret_t rcl_ret_t
rcl_enable_ros_time_override(rcl_clock_t * clock) rcl_enable_ros_time_override(rcl_clock_t * clock)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
if (clock->type != RCL_ROS_TIME) { if (clock->type != RCL_ROS_TIME) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("Clock is not of type RCL_ROS_TIME, cannot enable override.");
"Clock is not of type RCL_ROS_TIME, cannot enable override.", rcl_get_default_allocator())
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
rcl_ros_clock_storage_t * storage = (rcl_ros_clock_storage_t *)clock->data; rcl_ros_clock_storage_t * storage = (rcl_ros_clock_storage_t *)clock->data;
if (!storage) { if (!storage) {
RCL_SET_ERROR_MSG("Clock storage is not initialized, cannot enable override.", RCL_SET_ERROR_MSG("Clock storage is not initialized, cannot enable override.");
rcl_get_default_allocator())
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (!storage->active) { if (!storage->active) {
@ -314,17 +306,15 @@ rcl_enable_ros_time_override(rcl_clock_t * clock)
rcl_ret_t rcl_ret_t
rcl_disable_ros_time_override(rcl_clock_t * clock) rcl_disable_ros_time_override(rcl_clock_t * clock)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
if (clock->type != RCL_ROS_TIME) { if (clock->type != RCL_ROS_TIME) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("Clock is not of type RCL_ROS_TIME, cannot disable override.");
"Clock is not of type RCL_ROS_TIME, cannot disable override.", rcl_get_default_allocator())
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
rcl_ros_clock_storage_t * storage = \ rcl_ros_clock_storage_t * storage = \
(rcl_ros_clock_storage_t *)clock->data; (rcl_ros_clock_storage_t *)clock->data;
if (!storage) { if (!storage) {
RCL_SET_ERROR_MSG("Clock storage is not initialized, cannot disable override.", RCL_SET_ERROR_MSG("Clock storage is not initialized, cannot disable override.");
rcl_get_default_allocator())
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (storage->active) { if (storage->active) {
@ -343,19 +333,16 @@ rcl_is_enabled_ros_time_override(
rcl_clock_t * clock, rcl_clock_t * clock,
bool * is_enabled) bool * is_enabled)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(is_enabled, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(is_enabled, RCL_RET_INVALID_ARGUMENT);
if (clock->type != RCL_ROS_TIME) { if (clock->type != RCL_ROS_TIME) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("Clock is not of type RCL_ROS_TIME, cannot query override state.");
"Clock is not of type RCL_ROS_TIME, cannot query override state.",
rcl_get_default_allocator())
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
rcl_ros_clock_storage_t * storage = \ rcl_ros_clock_storage_t * storage = \
(rcl_ros_clock_storage_t *)clock->data; (rcl_ros_clock_storage_t *)clock->data;
if (!storage) { if (!storage) {
RCL_SET_ERROR_MSG("Clock storage is not initialized, cannot query override state.", RCL_SET_ERROR_MSG("Clock storage is not initialized, cannot query override state.");
rcl_get_default_allocator())
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
*is_enabled = storage->active; *is_enabled = storage->active;
@ -367,10 +354,9 @@ rcl_set_ros_time_override(
rcl_clock_t * clock, rcl_clock_t * clock,
rcl_time_point_value_t time_value) rcl_time_point_value_t time_value)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
if (clock->type != RCL_ROS_TIME) { if (clock->type != RCL_ROS_TIME) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("Clock is not of type RCL_ROS_TIME, cannot set time override.");
"Clock is not of type RCL_ROS_TIME, cannot set time override.", rcl_get_default_allocator())
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
rcl_time_jump_t time_jump; rcl_time_jump_t time_jump;
@ -398,16 +384,16 @@ rcl_clock_add_jump_callback(
void * user_data) void * user_data)
{ {
// Make sure parameters are valid // Make sure parameters are valid
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&(clock->allocator), "invalid allocator", RCL_CHECK_ALLOCATOR_WITH_MSG(&(clock->allocator), "invalid allocator",
return RCL_RET_INVALID_ARGUMENT); return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(callback, RCL_RET_INVALID_ARGUMENT, clock->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(callback, RCL_RET_INVALID_ARGUMENT);
if (threshold.min_forward.nanoseconds < 0) { if (threshold.min_forward.nanoseconds < 0) {
RCL_SET_ERROR_MSG("forward jump threshold must be positive or zero", clock->allocator); RCL_SET_ERROR_MSG("forward jump threshold must be positive or zero");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
if (threshold.min_backward.nanoseconds > 0) { if (threshold.min_backward.nanoseconds > 0) {
RCL_SET_ERROR_MSG("backward jump threshold must be negative or zero", clock->allocator); RCL_SET_ERROR_MSG("backward jump threshold must be negative or zero");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
@ -415,7 +401,7 @@ rcl_clock_add_jump_callback(
for (size_t cb_idx = 0; cb_idx < clock->num_jump_callbacks; ++cb_idx) { for (size_t cb_idx = 0; cb_idx < clock->num_jump_callbacks; ++cb_idx) {
const rcl_jump_callback_info_t * info = &(clock->jump_callbacks[cb_idx]); const rcl_jump_callback_info_t * info = &(clock->jump_callbacks[cb_idx]);
if (info->callback == callback && info->user_data == user_data) { if (info->callback == callback && info->user_data == user_data) {
RCL_SET_ERROR_MSG("callback/user_data are already added to this clock", clock->allocator); RCL_SET_ERROR_MSG("callback/user_data are already added to this clock");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
} }
@ -425,7 +411,7 @@ rcl_clock_add_jump_callback(
clock->jump_callbacks, sizeof(rcl_jump_callback_info_t) * (clock->num_jump_callbacks + 1), clock->jump_callbacks, sizeof(rcl_jump_callback_info_t) * (clock->num_jump_callbacks + 1),
clock->allocator.state); clock->allocator.state);
if (NULL == callbacks) { if (NULL == callbacks) {
RCL_SET_ERROR_MSG("Failed to realloc jump callbacks", clock->allocator); RCL_SET_ERROR_MSG("Failed to realloc jump callbacks");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
clock->jump_callbacks = callbacks; clock->jump_callbacks = callbacks;
@ -441,10 +427,10 @@ rcl_clock_remove_jump_callback(
rcl_clock_t * clock, rcl_jump_callback_t callback, void * user_data) rcl_clock_t * clock, rcl_jump_callback_t callback, void * user_data)
{ {
// Make sure parameters are valid // Make sure parameters are valid
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&(clock->allocator), "invalid allocator", RCL_CHECK_ALLOCATOR_WITH_MSG(&(clock->allocator), "invalid allocator",
return RCL_RET_INVALID_ARGUMENT); return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(callback, RCL_RET_INVALID_ARGUMENT, clock->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(callback, RCL_RET_INVALID_ARGUMENT);
// Delete callback if found, moving all callbacks after back one // Delete callback if found, moving all callbacks after back one
bool found_callback = false; bool found_callback = false;
@ -457,7 +443,7 @@ rcl_clock_remove_jump_callback(
} }
} }
if (!found_callback) { if (!found_callback) {
RCL_SET_ERROR_MSG("jump callback was not found", clock->allocator); RCL_SET_ERROR_MSG("jump callback was not found");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -470,7 +456,7 @@ rcl_clock_remove_jump_callback(
clock->jump_callbacks, sizeof(rcl_jump_callback_info_t) * (clock->num_jump_callbacks - 1), clock->jump_callbacks, sizeof(rcl_jump_callback_info_t) * (clock->num_jump_callbacks - 1),
clock->allocator.state); clock->allocator.state);
if (NULL == callbacks) { if (NULL == callbacks) {
RCL_SET_ERROR_MSG("Failed to shrink jump callbacks", clock->allocator); RCL_SET_ERROR_MSG("Failed to shrink jump callbacks");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
clock->jump_callbacks = callbacks; clock->jump_callbacks = callbacks;

View file

@ -128,16 +128,16 @@ rcl_timer_init(
rcl_allocator_t allocator) rcl_allocator_t allocator)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
if (period < 0) { if (period < 0) {
RCL_SET_ERROR_MSG("timer period must be non-negative", allocator); RCL_SET_ERROR_MSG("timer period must be non-negative");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Initializing timer with period: %" PRIu64 "ns", period); ROS_PACKAGE_NAME, "Initializing timer with period: %" PRIu64 "ns", period);
if (timer->impl) { if (timer->impl) {
RCL_SET_ERROR_MSG("timer already initailized, or memory was uninitialized", allocator); RCL_SET_ERROR_MSG("timer already initailized, or memory was uninitialized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
rcl_time_point_value_t now; rcl_time_point_value_t now;
@ -186,7 +186,7 @@ rcl_timer_init(
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to remove callback after bad alloc"); RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to remove callback after bad alloc");
} }
RCL_SET_ERROR_MSG("allocating memory failed", allocator); RCL_SET_ERROR_MSG("allocating memory failed");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
*timer->impl = impl; *timer->impl = impl;
@ -204,7 +204,7 @@ rcl_timer_fini(rcl_timer_t * timer)
rcl_allocator_t allocator = timer->impl->allocator; rcl_allocator_t allocator = timer->impl->allocator;
rcl_ret_t fail_ret = rcl_guard_condition_fini(&(timer->impl->guard_condition)); rcl_ret_t fail_ret = rcl_guard_condition_fini(&(timer->impl->guard_condition));
if (RCL_RET_OK != fail_ret) { if (RCL_RET_OK != fail_ret) {
RCL_SET_ERROR_MSG("Failure to fini guard condition", allocator); RCL_SET_ERROR_MSG("Failure to fini guard condition");
} }
if (RCL_ROS_TIME == timer->impl->clock->type) { if (RCL_ROS_TIME == timer->impl->clock->type) {
fail_ret = rcl_clock_remove_jump_callback(timer->impl->clock, _rcl_timer_time_jump, timer); fail_ret = rcl_clock_remove_jump_callback(timer->impl->clock, _rcl_timer_time_jump, timer);
@ -222,9 +222,9 @@ RCL_WARN_UNUSED
rcl_ret_t rcl_ret_t
rcl_timer_clock(rcl_timer_t * timer, rcl_clock_t ** clock) rcl_timer_clock(rcl_timer_t * timer, rcl_clock_t ** clock)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(clock, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(timer->impl, RCL_RET_TIMER_INVALID, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer->impl, RCL_RET_TIMER_INVALID);
*clock = timer->impl->clock; *clock = timer->impl->clock;
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -233,13 +233,9 @@ rcl_ret_t
rcl_timer_call(rcl_timer_t * timer) rcl_timer_call(rcl_timer_t * timer)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Calling timer"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Calling timer");
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = rcl_timer_get_allocator(timer);
if (!allocator) {
return RCL_RET_TIMER_INVALID;
}
if (rcl_atomic_load_bool(&timer->impl->canceled)) { if (rcl_atomic_load_bool(&timer->impl->canceled)) {
RCL_SET_ERROR_MSG("timer is canceled", *allocator); RCL_SET_ERROR_MSG("timer is canceled");
return RCL_RET_TIMER_CANCELED; return RCL_RET_TIMER_CANCELED;
} }
rcl_time_point_value_t now; rcl_time_point_value_t now;
@ -248,7 +244,7 @@ rcl_timer_call(rcl_timer_t * timer)
return now_ret; // rcl error state should already be set. return now_ret; // rcl error state should already be set.
} }
if (now < 0) { if (now < 0) {
RCL_SET_ERROR_MSG("clock now returned negative time point value", *allocator); RCL_SET_ERROR_MSG("clock now returned negative time point value");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
rcl_time_point_value_t previous_ns = rcl_time_point_value_t previous_ns =
@ -287,12 +283,8 @@ rcl_timer_call(rcl_timer_t * timer)
rcl_ret_t rcl_ret_t
rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready) rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = rcl_timer_get_allocator(timer); RCL_CHECK_ARGUMENT_FOR_NULL(is_ready, RCL_RET_INVALID_ARGUMENT);
if (!allocator) {
return RCL_RET_TIMER_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(is_ready, RCL_RET_INVALID_ARGUMENT, *allocator);
int64_t time_until_next_call; int64_t time_until_next_call;
rcl_ret_t ret = rcl_timer_get_time_until_next_call(timer, &time_until_next_call); rcl_ret_t ret = rcl_timer_get_time_until_next_call(timer, &time_until_next_call);
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
@ -305,12 +297,8 @@ rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready)
rcl_ret_t rcl_ret_t
rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_until_next_call) rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_until_next_call)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = rcl_timer_get_allocator(timer); RCL_CHECK_ARGUMENT_FOR_NULL(time_until_next_call, RCL_RET_INVALID_ARGUMENT);
if (!allocator) {
return RCL_RET_TIMER_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(time_until_next_call, RCL_RET_INVALID_ARGUMENT, *allocator);
rcl_time_point_value_t now; rcl_time_point_value_t now;
rcl_ret_t ret = rcl_clock_get_now(timer->impl->clock, &now); rcl_ret_t ret = rcl_clock_get_now(timer->impl->clock, &now);
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
@ -326,12 +314,8 @@ rcl_timer_get_time_since_last_call(
const rcl_timer_t * timer, const rcl_timer_t * timer,
rcl_time_point_value_t * time_since_last_call) rcl_time_point_value_t * time_since_last_call)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = rcl_timer_get_allocator(timer); RCL_CHECK_ARGUMENT_FOR_NULL(time_since_last_call, RCL_RET_INVALID_ARGUMENT);
if (!allocator) {
return RCL_RET_TIMER_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(time_since_last_call, RCL_RET_INVALID_ARGUMENT, *allocator);
rcl_time_point_value_t now; rcl_time_point_value_t now;
rcl_ret_t ret = rcl_clock_get_now(timer->impl->clock, &now); rcl_ret_t ret = rcl_clock_get_now(timer->impl->clock, &now);
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
@ -345,12 +329,8 @@ rcl_timer_get_time_since_last_call(
rcl_ret_t rcl_ret_t
rcl_timer_get_period(const rcl_timer_t * timer, int64_t * period) rcl_timer_get_period(const rcl_timer_t * timer, int64_t * period)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = rcl_timer_get_allocator(timer); RCL_CHECK_ARGUMENT_FOR_NULL(period, RCL_RET_INVALID_ARGUMENT);
if (!allocator) {
return RCL_RET_TIMER_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(period, RCL_RET_INVALID_ARGUMENT, *allocator);
*period = rcl_atomic_load_uint64_t(&timer->impl->period); *period = rcl_atomic_load_uint64_t(&timer->impl->period);
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -358,12 +338,8 @@ rcl_timer_get_period(const rcl_timer_t * timer, int64_t * period)
rcl_ret_t rcl_ret_t
rcl_timer_exchange_period(const rcl_timer_t * timer, int64_t new_period, int64_t * old_period) rcl_timer_exchange_period(const rcl_timer_t * timer, int64_t new_period, int64_t * old_period)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = rcl_timer_get_allocator(timer); RCL_CHECK_ARGUMENT_FOR_NULL(old_period, RCL_RET_INVALID_ARGUMENT);
if (!allocator) {
return RCL_RET_TIMER_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(old_period, RCL_RET_INVALID_ARGUMENT, *allocator);
*old_period = rcl_atomic_exchange_uint64_t(&timer->impl->period, new_period); *old_period = rcl_atomic_exchange_uint64_t(&timer->impl->period, new_period);
RCUTILS_LOG_DEBUG_NAMED( RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Updated timer period from '%" PRIu64 "ns' to '%" PRIu64 "ns'", ROS_PACKAGE_NAME, "Updated timer period from '%" PRIu64 "ns' to '%" PRIu64 "ns'",
@ -374,9 +350,8 @@ rcl_timer_exchange_period(const rcl_timer_t * timer, int64_t new_period, int64_t
rcl_timer_callback_t rcl_timer_callback_t
rcl_timer_get_callback(const rcl_timer_t * timer) rcl_timer_get_callback(const rcl_timer_t * timer)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return NULL);
timer->impl, "timer is invalid", return NULL, rcl_get_default_allocator());
return (rcl_timer_callback_t)rcl_atomic_load_uintptr_t(&timer->impl->callback); return (rcl_timer_callback_t)rcl_atomic_load_uintptr_t(&timer->impl->callback);
} }
@ -384,9 +359,8 @@ rcl_timer_callback_t
rcl_timer_exchange_callback(rcl_timer_t * timer, const rcl_timer_callback_t new_callback) rcl_timer_exchange_callback(rcl_timer_t * timer, const rcl_timer_callback_t new_callback)
{ {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Updating timer callback"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Updating timer callback");
RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return NULL);
timer->impl, "timer is invalid", return NULL, rcl_get_default_allocator());
return (rcl_timer_callback_t)rcl_atomic_exchange_uintptr_t( return (rcl_timer_callback_t)rcl_atomic_exchange_uintptr_t(
&timer->impl->callback, (uintptr_t)new_callback); &timer->impl->callback, (uintptr_t)new_callback);
} }
@ -394,9 +368,8 @@ rcl_timer_exchange_callback(rcl_timer_t * timer, const rcl_timer_callback_t new_
rcl_ret_t rcl_ret_t
rcl_timer_cancel(rcl_timer_t * timer) rcl_timer_cancel(rcl_timer_t * timer)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return RCL_RET_TIMER_INVALID);
timer->impl, "timer is invalid", return RCL_RET_TIMER_INVALID, rcl_get_default_allocator());
rcl_atomic_store(&timer->impl->canceled, true); rcl_atomic_store(&timer->impl->canceled, true);
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Timer canceled"); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Timer canceled");
return RCL_RET_OK; return RCL_RET_OK;
@ -405,12 +378,8 @@ rcl_timer_cancel(rcl_timer_t * timer)
rcl_ret_t rcl_ret_t
rcl_timer_is_canceled(const rcl_timer_t * timer, bool * is_canceled) rcl_timer_is_canceled(const rcl_timer_t * timer, bool * is_canceled)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = rcl_timer_get_allocator(timer); RCL_CHECK_ARGUMENT_FOR_NULL(is_canceled, RCL_RET_INVALID_ARGUMENT);
if (!allocator) {
return RCL_RET_TIMER_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(is_canceled, RCL_RET_INVALID_ARGUMENT, *allocator);
*is_canceled = rcl_atomic_load_bool(&timer->impl->canceled); *is_canceled = rcl_atomic_load_bool(&timer->impl->canceled);
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -418,9 +387,8 @@ rcl_timer_is_canceled(const rcl_timer_t * timer, bool * is_canceled)
rcl_ret_t rcl_ret_t
rcl_timer_reset(rcl_timer_t * timer) rcl_timer_reset(rcl_timer_t * timer)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return RCL_RET_TIMER_INVALID);
timer->impl, "timer is invalid", return RCL_RET_TIMER_INVALID, rcl_get_default_allocator());
rcl_time_point_value_t now; rcl_time_point_value_t now;
rcl_ret_t now_ret = rcl_clock_get_now(timer->impl->clock, &now); rcl_ret_t now_ret = rcl_clock_get_now(timer->impl->clock, &now);
if (now_ret != RCL_RET_OK) { if (now_ret != RCL_RET_OK) {
@ -436,9 +404,8 @@ rcl_timer_reset(rcl_timer_t * timer)
const rcl_allocator_t * const rcl_allocator_t *
rcl_timer_get_allocator(const rcl_timer_t * timer) rcl_timer_get_allocator(const rcl_timer_t * timer)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(timer, NULL);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(timer->impl, "timer is invalid", return NULL);
timer->impl, "timer is invalid", return NULL, rcl_get_default_allocator());
return &timer->impl->allocator; return &timer->impl->allocator;
} }

View file

@ -32,8 +32,7 @@ rcl_validate_topic_name(
int * validation_result, int * validation_result,
size_t * invalid_index) size_t * invalid_index)
{ {
rcl_allocator_t allocator = rcutils_get_default_allocator(); RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, allocator)
return rcl_validate_topic_name_with_size( return rcl_validate_topic_name_with_size(
topic_name, strlen(topic_name), validation_result, invalid_index); topic_name, strlen(topic_name), validation_result, invalid_index);
} }
@ -45,9 +44,8 @@ rcl_validate_topic_name_with_size(
int * validation_result, int * validation_result,
size_t * invalid_index) size_t * invalid_index)
{ {
rcl_allocator_t allocator = rcutils_get_default_allocator(); RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(topic_name, RCL_RET_INVALID_ARGUMENT, allocator) RCL_CHECK_ARGUMENT_FOR_NULL(validation_result, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(validation_result, RCL_RET_INVALID_ARGUMENT, allocator)
if (topic_name_length == 0) { if (topic_name_length == 0) {
*validation_result = RCL_TOPIC_NAME_INVALID_IS_EMPTY_STRING; *validation_result = RCL_TOPIC_NAME_INVALID_IS_EMPTY_STRING;

View file

@ -108,16 +108,16 @@ rcl_wait_set_init(
rcl_ret_t fail_ret = RCL_RET_ERROR; rcl_ret_t fail_ret = RCL_RET_ERROR;
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT);
if (__wait_set_is_valid(wait_set)) { if (__wait_set_is_valid(wait_set)) {
RCL_SET_ERROR_MSG("wait_set already initialized, or memory was uninitialized.", allocator); RCL_SET_ERROR_MSG("wait_set already initialized, or memory was uninitialized.");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Allocate space for the implementation struct. // Allocate space for the implementation struct.
wait_set->impl = (rcl_wait_set_impl_t *)allocator.allocate( wait_set->impl = (rcl_wait_set_impl_t *)allocator.allocate(
sizeof(rcl_wait_set_impl_t), allocator.state); sizeof(rcl_wait_set_impl_t), allocator.state);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
wait_set->impl, "allocating memory failed", return RCL_RET_BAD_ALLOC, allocator); wait_set->impl, "allocating memory failed", return RCL_RET_BAD_ALLOC);
memset(wait_set->impl, 0, sizeof(rcl_wait_set_impl_t)); memset(wait_set->impl, 0, sizeof(rcl_wait_set_impl_t));
wait_set->impl->rmw_subscriptions.subscribers = NULL; wait_set->impl->rmw_subscriptions.subscribers = NULL;
wait_set->impl->rmw_subscriptions.subscriber_count = 0; wait_set->impl->rmw_subscriptions.subscriber_count = 0;
@ -161,12 +161,12 @@ rcl_ret_t
rcl_wait_set_fini(rcl_wait_set_t * wait_set) rcl_wait_set_fini(rcl_wait_set_t * wait_set)
{ {
rcl_ret_t result = RCL_RET_OK; rcl_ret_t result = RCL_RET_OK;
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT);
if (__wait_set_is_valid(wait_set)) { if (__wait_set_is_valid(wait_set)) {
rmw_ret_t ret = rmw_destroy_wait_set(wait_set->impl->rmw_wait_set); rmw_ret_t ret = rmw_destroy_wait_set(wait_set->impl->rmw_wait_set);
if (ret != RMW_RET_OK) { if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), wait_set->impl->allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_WAIT_SET_INVALID; result = RCL_RET_WAIT_SET_INVALID;
} }
__wait_set_clean_up(wait_set, wait_set->impl->allocator); __wait_set_clean_up(wait_set, wait_set->impl->allocator);
@ -177,25 +177,25 @@ rcl_wait_set_fini(rcl_wait_set_t * wait_set)
rcl_ret_t rcl_ret_t
rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * allocator) rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * allocator)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT);
if (!__wait_set_is_valid(wait_set)) { if (!__wait_set_is_valid(wait_set)) {
RCL_SET_ERROR_MSG("wait set is invalid", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("wait set is invalid");
return RCL_RET_WAIT_SET_INVALID; return RCL_RET_WAIT_SET_INVALID;
} }
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, wait_set->impl->allocator); RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
*allocator = wait_set->impl->allocator; *allocator = wait_set->impl->allocator;
return RCL_RET_OK; return RCL_RET_OK;
} }
#define SET_ADD(Type) \ #define SET_ADD(Type) \
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); \ RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT); \
if (!__wait_set_is_valid(wait_set)) { \ if (!__wait_set_is_valid(wait_set)) { \
RCL_SET_ERROR_MSG("wait set is invalid", rcl_get_default_allocator()); \ RCL_SET_ERROR_MSG("wait set is invalid"); \
return RCL_RET_WAIT_SET_INVALID; \ return RCL_RET_WAIT_SET_INVALID; \
} \ } \
RCL_CHECK_ARGUMENT_FOR_NULL(Type, RCL_RET_INVALID_ARGUMENT, wait_set->impl->allocator); \ RCL_CHECK_ARGUMENT_FOR_NULL(Type, RCL_RET_INVALID_ARGUMENT); \
if (!(wait_set->impl->Type ## _index < wait_set->size_of_ ## Type ## s)) { \ if (!(wait_set->impl->Type ## _index < wait_set->size_of_ ## Type ## s)) { \
RCL_SET_ERROR_MSG(#Type "s set is full", wait_set->impl->allocator); \ RCL_SET_ERROR_MSG(#Type "s set is full"); \
return RCL_RET_WAIT_SET_FULL; \ return RCL_RET_WAIT_SET_FULL; \
} \ } \
size_t current_index = wait_set->impl->Type ## _index++; \ size_t current_index = wait_set->impl->Type ## _index++; \
@ -205,7 +205,7 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al
/* Also place into rmw storage. */ \ /* Also place into rmw storage. */ \
rmw_ ## Type ## _t * rmw_handle = rcl_ ## Type ## _get_rmw_handle(Type); \ rmw_ ## Type ## _t * rmw_handle = rcl_ ## Type ## _get_rmw_handle(Type); \
RCL_CHECK_FOR_NULL_WITH_MSG( \ RCL_CHECK_FOR_NULL_WITH_MSG( \
rmw_handle, rcl_get_error_string_safe(), return RCL_RET_ERROR, wait_set->impl->allocator); \ rmw_handle, rcl_get_error_string().str, return RCL_RET_ERROR); \
wait_set->impl->RMWStorage[current_index] = rmw_handle->data; \ wait_set->impl->RMWStorage[current_index] = rmw_handle->data; \
wait_set->impl->RMWCount++; wait_set->impl->RMWCount++;
@ -248,8 +248,7 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al
(void *)wait_set->Type ## s, sizeof(rcl_ ## Type ## _t *) * Type ## s_size, \ (void *)wait_set->Type ## s, sizeof(rcl_ ## Type ## _t *) * Type ## s_size, \
allocator.state); \ allocator.state); \
RCL_CHECK_FOR_NULL_WITH_MSG( \ RCL_CHECK_FOR_NULL_WITH_MSG( \
wait_set->Type ## s, "allocating memory failed", \ wait_set->Type ## s, "allocating memory failed", return RCL_RET_BAD_ALLOC); \
return RCL_RET_BAD_ALLOC, wait_set->impl->allocator); \
memset((void *)wait_set->Type ## s, 0, sizeof(rcl_ ## Type ## _t *) * Type ## s_size); \ memset((void *)wait_set->Type ## s, 0, sizeof(rcl_ ## Type ## _t *) * Type ## s_size); \
wait_set->size_of_ ## Type ## s = Type ## s_size; \ wait_set->size_of_ ## Type ## s = Type ## s_size; \
ExtraRealloc \ ExtraRealloc \
@ -272,7 +271,7 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al
if (!wait_set->impl->RMWStorage) { \ if (!wait_set->impl->RMWStorage) { \
allocator.deallocate((void *)wait_set->Type ## s, allocator.state); \ allocator.deallocate((void *)wait_set->Type ## s, allocator.state); \
wait_set->size_of_ ## Type ## s = 0; \ wait_set->size_of_ ## Type ## s = 0; \
RCL_SET_ERROR_MSG("allocating memory failed", wait_set->impl->allocator); \ RCL_SET_ERROR_MSG("allocating memory failed"); \
return RCL_RET_BAD_ALLOC; \ return RCL_RET_BAD_ALLOC; \
} \ } \
memset(wait_set->impl->RMWStorage, 0, sizeof(void *) * Type ## s_size); memset(wait_set->impl->RMWStorage, 0, sizeof(void *) * Type ## s_size);
@ -300,9 +299,8 @@ rcl_wait_set_add_subscription(
rcl_ret_t rcl_ret_t
rcl_wait_set_clear(rcl_wait_set_t * wait_set) rcl_wait_set_clear(rcl_wait_set_t * wait_set)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(wait_set->impl, RCL_RET_WAIT_SET_INVALID);
wait_set->impl, RCL_RET_WAIT_SET_INVALID, rcl_get_default_allocator());
SET_CLEAR(subscription); SET_CLEAR(subscription);
SET_CLEAR(guard_condition); SET_CLEAR(guard_condition);
@ -344,9 +342,8 @@ rcl_wait_set_resize(
size_t clients_size, size_t clients_size,
size_t services_size) size_t services_size)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(wait_set->impl, RCL_RET_WAIT_SET_INVALID);
wait_set->impl, RCL_RET_WAIT_SET_INVALID, rcl_get_default_allocator());
SET_RESIZE( SET_RESIZE(
subscription, subscription,
SET_RESIZE_RMW_DEALLOC( SET_RESIZE_RMW_DEALLOC(
@ -381,7 +378,7 @@ rcl_wait_set_resize(
(void *)wait_set->timers, wait_set->impl->allocator.state); (void *)wait_set->timers, wait_set->impl->allocator.state);
wait_set->size_of_timers = 0u; wait_set->size_of_timers = 0u;
wait_set->timers = NULL; wait_set->timers = NULL;
RCL_SET_ERROR_MSG("allocating memory failed", wait_set->impl->allocator); RCL_SET_ERROR_MSG("allocating memory failed");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
memset(rmw_gcs->guard_conditions, 0, sizeof(void *) * num_rmw_gc); memset(rmw_gcs->guard_conditions, 0, sizeof(void *) * num_rmw_gc);
@ -427,7 +424,7 @@ rcl_wait_set_add_timer(
const size_t index = wait_set->size_of_guard_conditions + (wait_set->impl->timer_index - 1); const size_t index = wait_set->size_of_guard_conditions + (wait_set->impl->timer_index - 1);
rmw_guard_condition_t * rmw_handle = rcl_guard_condition_get_rmw_handle(guard_condition); rmw_guard_condition_t * rmw_handle = rcl_guard_condition_get_rmw_handle(guard_condition);
RCL_CHECK_FOR_NULL_WITH_MSG( RCL_CHECK_FOR_NULL_WITH_MSG(
rmw_handle, rcl_get_error_string_safe(), return RCL_RET_ERROR, wait_set->impl->allocator); rmw_handle, rcl_get_error_string().str, return RCL_RET_ERROR);
wait_set->impl->rmw_guard_conditions.guard_conditions[index] = rmw_handle->data; wait_set->impl->rmw_guard_conditions.guard_conditions[index] = rmw_handle->data;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -456,9 +453,9 @@ rcl_wait_set_add_service(
rcl_ret_t rcl_ret_t
rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout) rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()); RCL_CHECK_ARGUMENT_FOR_NULL(wait_set, RCL_RET_INVALID_ARGUMENT);
if (!__wait_set_is_valid(wait_set)) { if (!__wait_set_is_valid(wait_set)) {
RCL_SET_ERROR_MSG("wait set is invalid", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("wait set is invalid");
return RCL_RET_WAIT_SET_INVALID; return RCL_RET_WAIT_SET_INVALID;
} }
if ( if (
@ -468,7 +465,7 @@ rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout)
wait_set->size_of_clients == 0 && wait_set->size_of_clients == 0 &&
wait_set->size_of_services == 0) wait_set->size_of_services == 0)
{ {
RCL_SET_ERROR_MSG("wait set is empty", wait_set->impl->allocator); RCL_SET_ERROR_MSG("wait set is empty");
return RCL_RET_WAIT_SET_EMPTY; return RCL_RET_WAIT_SET_EMPTY;
} }
// Calculate the timeout argument. // Calculate the timeout argument.
@ -574,7 +571,7 @@ rcl_wait(rcl_wait_set_t * wait_set, int64_t timeout)
} }
// Check for timeout, return RCL_RET_TIMEOUT only if it wasn't a timer. // Check for timeout, return RCL_RET_TIMEOUT only if it wasn't a timer.
if (ret != RMW_RET_OK && ret != RMW_RET_TIMEOUT) { if (ret != RMW_RET_OK && ret != RMW_RET_TIMEOUT) {
RCL_SET_ERROR_MSG(rmw_get_error_string_safe(), wait_set->impl->allocator); RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
// Set corresponding rcl subscription handles NULL. // Set corresponding rcl subscription handles NULL.

View file

@ -50,12 +50,12 @@ destroy_args(int argc, char ** args)
argc = (sizeof(const_argv) / sizeof(const char *)); \ argc = (sizeof(const_argv) / sizeof(const char *)); \
argv = copy_args(argc, const_argv); \ 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, rcl_get_default_allocator()); \
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \
} \ } \
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ \ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ \
destroy_args(argc, argv); \ destroy_args(argc, argv); \
rcl_ret_t ret = rcl_shutdown(); \ rcl_ret_t ret = rcl_shutdown(); \
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \
}) })
#define SCOPE_ARGS(local_arguments, ...) \ #define SCOPE_ARGS(local_arguments, ...) \
@ -65,7 +65,7 @@ destroy_args(int argc, char ** args)
unsigned int local_argc = (sizeof(local_argv) / sizeof(const char *)); \ unsigned int local_argc = (sizeof(local_argv) / sizeof(const char *)); \
rcl_ret_t ret = rcl_parse_arguments( \ rcl_ret_t ret = rcl_parse_arguments( \
local_argc, local_argv, rcl_get_default_allocator(), &local_arguments); \ local_argc, local_argv, rcl_get_default_allocator(), &local_arguments); \
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \
} \ } \
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ \ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ \
ASSERT_EQ(RCL_RET_OK, rcl_arguments_fini(&local_arguments)); \ ASSERT_EQ(RCL_RET_OK, rcl_arguments_fini(&local_arguments)); \

View file

@ -43,7 +43,7 @@ wait_for_server_to_be_available(
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, ROS_PACKAGE_NAME,
"Error in rcl_service_server_is_available: %s", "Error in rcl_service_server_is_available: %s",
rcl_get_error_string_safe()); rcl_get_error_string().str);
return false; return false;
} }
if (is_ready) { if (is_ready) {
@ -64,13 +64,13 @@ wait_for_client_to_be_ready(
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 1, 0, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 1, 0, rcl_get_default_allocator());
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait set init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait set init: %s", rcl_get_error_string().str);
return false; return false;
} }
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string().str);
throw std::runtime_error("error while waiting for client"); throw std::runtime_error("error while waiting for client");
} }
}); });
@ -79,12 +79,12 @@ wait_for_client_to_be_ready(
++iteration; ++iteration;
if (rcl_wait_set_clear(&wait_set) != RCL_RET_OK) { if (rcl_wait_set_clear(&wait_set) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait_set_clear: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait_set_clear: %s", rcl_get_error_string().str);
return false; return false;
} }
if (rcl_wait_set_add_client(&wait_set, client) != RCL_RET_OK) { if (rcl_wait_set_add_client(&wait_set, client) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait_set_add_client: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait_set_add_client: %s", rcl_get_error_string().str);
return false; return false;
} }
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms));
@ -92,7 +92,7 @@ wait_for_client_to_be_ready(
continue; continue;
} }
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Error in wait: %s", rcl_get_error_string_safe()); RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Error in wait: %s", rcl_get_error_string().str);
return false; return false;
} }
for (size_t i = 0; i < wait_set.size_of_clients; ++i) { for (size_t i = 0; i < wait_set.size_of_clients; ++i) {
@ -110,7 +110,7 @@ int main(int argc, char ** argv)
{ {
if (rcl_init(argc, argv, rcl_get_default_allocator()) != RCL_RET_OK) { if (rcl_init(argc, argv, rcl_get_default_allocator()) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in rcl init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in rcl init: %s", rcl_get_error_string().str);
return -1; return -1;
} }
rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_t node = rcl_get_zero_initialized_node();
@ -118,13 +118,13 @@ int main(int argc, char ** argv)
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string().str);
return -1; return -1;
} }
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
if (rcl_node_fini(&node) != RCL_RET_OK) { if (rcl_node_fini(&node) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string().str);
main_ret = -1; main_ret = -1;
} }
}); });
@ -138,14 +138,14 @@ int main(int argc, char ** argv)
rcl_ret_t ret = rcl_client_init(&client, &node, ts, service_name, &client_options); rcl_ret_t ret = rcl_client_init(&client, &node, ts, service_name, &client_options);
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in client init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in client init: %s", rcl_get_error_string().str);
return -1; return -1;
} }
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
if (rcl_client_fini(&client, &node)) { if (rcl_client_fini(&client, &node)) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in client fini: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in client fini: %s", rcl_get_error_string().str);
main_ret = -1; main_ret = -1;
} }
}); });
@ -168,7 +168,7 @@ int main(int argc, char ** argv)
if (rcl_send_request(&client, &client_request, &sequence_number)) { if (rcl_send_request(&client, &client_request, &sequence_number)) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in send request: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in send request: %s", rcl_get_error_string().str);
return -1; return -1;
} }
@ -193,7 +193,7 @@ int main(int argc, char ** argv)
rmw_request_id_t header; rmw_request_id_t header;
if (rcl_take_response(&client, &header, &client_response) != RCL_RET_OK) { if (rcl_take_response(&client, &header, &client_response) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in send response: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in send response: %s", rcl_get_error_string().str);
return -1; return -1;
} }

View file

@ -37,13 +37,13 @@ wait_for_service_to_be_ready(
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 1, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 1, rcl_get_default_allocator());
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait set init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait set init: %s", rcl_get_error_string().str);
return false; return false;
} }
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) { if (rcl_wait_set_fini(&wait_set) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait set fini: %s", rcl_get_error_string().str);
throw std::runtime_error("error waiting for service to be ready"); throw std::runtime_error("error waiting for service to be ready");
} }
}); });
@ -52,12 +52,12 @@ wait_for_service_to_be_ready(
++iteration; ++iteration;
if (rcl_wait_set_clear(&wait_set) != RCL_RET_OK) { if (rcl_wait_set_clear(&wait_set) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait_set_clear: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait_set_clear: %s", rcl_get_error_string().str);
return false; return false;
} }
if (rcl_wait_set_add_service(&wait_set, service) != RCL_RET_OK) { if (rcl_wait_set_add_service(&wait_set, service) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in wait_set_add_service: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in wait_set_add_service: %s", rcl_get_error_string().str);
return false; return false;
} }
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms));
@ -65,7 +65,7 @@ wait_for_service_to_be_ready(
continue; continue;
} }
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Error in wait: %s", rcl_get_error_string_safe()); RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Error in wait: %s", rcl_get_error_string().str);
return false; return false;
} }
for (size_t i = 0; i < wait_set.size_of_services; ++i) { for (size_t i = 0; i < wait_set.size_of_services; ++i) {
@ -83,7 +83,7 @@ int main(int argc, char ** argv)
{ {
if (rcl_init(argc, argv, rcl_get_default_allocator()) != RCL_RET_OK) { if (rcl_init(argc, argv, rcl_get_default_allocator()) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in rcl init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in rcl init: %s", rcl_get_error_string().str);
return -1; return -1;
} }
rcl_node_t node = rcl_get_zero_initialized_node(); rcl_node_t node = rcl_get_zero_initialized_node();
@ -91,13 +91,13 @@ int main(int argc, char ** argv)
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in node init: %s", rcl_get_error_string().str);
return -1; return -1;
} }
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
if (rcl_node_fini(&node) != RCL_RET_OK) { if (rcl_node_fini(&node) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in node fini: %s", rcl_get_error_string().str);
main_ret = -1; main_ret = -1;
} }
}); });
@ -111,14 +111,14 @@ int main(int argc, char ** argv)
rcl_ret_t ret = rcl_service_init(&service, &node, ts, service_name, &service_options); rcl_ret_t ret = rcl_service_init(&service, &node, ts, service_name, &service_options);
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in service init: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in service init: %s", rcl_get_error_string().str);
return -1; return -1;
} }
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
if (rcl_service_fini(&service, &node)) { if (rcl_service_fini(&service, &node)) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in service fini: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in service fini: %s", rcl_get_error_string().str);
main_ret = -1; main_ret = -1;
} }
}); });
@ -153,7 +153,7 @@ int main(int argc, char ** argv)
// TODO(jacquelinekay) May have to check for timeout error codes // TODO(jacquelinekay) May have to check for timeout error codes
if (rcl_take_request(&service, &header, &service_request) != RCL_RET_OK) { if (rcl_take_request(&service, &header, &service_request) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in take_request: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in take_request: %s", rcl_get_error_string().str);
return -1; return -1;
} }
@ -161,7 +161,7 @@ int main(int argc, char ** argv)
service_response.uint64_value = service_request.uint8_value + service_request.uint32_value; service_response.uint64_value = service_request.uint8_value + service_request.uint32_value;
if (rcl_send_response(&service, &header, &service_response) != RCL_RET_OK) { if (rcl_send_response(&service, &header, &service_response) != RCL_RET_OK) {
RCUTILS_LOG_ERROR_NAMED( RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME, "Error in send_response: %s", rcl_get_error_string_safe()); ROS_PACKAGE_NAME, "Error in send_response: %s", rcl_get_error_string().str);
return -1; return -1;
} }
// Our scope exits should take care of fini for everything // Our scope exits should take care of fini for everything

View file

@ -74,7 +74,7 @@ is_valid_arg(const char * arg)
const char * argv[] = {arg}; const char * argv[] = {arg};
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret = rcl_parse_arguments(1, argv, rcl_get_default_allocator(), &parsed_args); rcl_ret_t ret = rcl_parse_arguments(1, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
bool is_valid = 0 == rcl_arguments_get_count_unparsed(&parsed_args); bool is_valid = 0 == rcl_arguments_get_count_unparsed(&parsed_args);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
return is_valid; return is_valid;
@ -139,7 +139,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_inval
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) {
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret = rcl_parse_arguments(0, NULL, rcl_get_default_allocator(), &parsed_args); rcl_ret_t ret = rcl_parse_arguments(0, NULL, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&parsed_args)); EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&parsed_args));
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
} }
@ -148,7 +148,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args) {
int argc = 1; int argc = 1;
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret = rcl_parse_arguments(argc, NULL, rcl_get_default_allocator(), &parsed_args); rcl_ret_t ret = rcl_parse_arguments(argc, NULL, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
} }
@ -156,7 +156,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args_outpu
const char * argv[] = {"process_name"}; const char * argv[] = {"process_name"};
int argc = sizeof(argv) / sizeof(const char *); int argc = sizeof(argv) / sizeof(const char *);
rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), NULL); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), NULL);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
} }
@ -166,7 +166,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap) {
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_UNPARSED(parsed_args, 0); EXPECT_UNPARSED(parsed_args, 0);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
} }
@ -177,7 +177,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_mix_valid_inval
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_UNPARSED(parsed_args, 0, 1, 3); EXPECT_UNPARSED(parsed_args, 0, 1, 3);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
} }
@ -189,11 +189,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments();
ret = rcl_arguments_copy(rcl_get_default_allocator(), &parsed_args, &copied_args); ret = rcl_arguments_copy(&parsed_args, &copied_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_UNPARSED(parsed_args, 0, 1); EXPECT_UNPARSED(parsed_args, 0, 1);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
@ -208,7 +208,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_two_namespace)
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_UNPARSED(parsed_args, 0); EXPECT_UNPARSED(parsed_args, 0);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
} }
@ -268,7 +268,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int nonros_argc = 0; int nonros_argc = 0;
const char ** nonros_argv = NULL; const char ** nonros_argv = NULL;
@ -280,7 +280,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args
&nonros_argc, &nonros_argc,
&nonros_argv); &nonros_argv);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ASSERT_EQ(nonros_argc, 4); ASSERT_EQ(nonros_argc, 4);
EXPECT_STREQ(nonros_argv[0], "process_name"); EXPECT_STREQ(nonros_argv[0], "process_name");
EXPECT_STREQ(nonros_argv[1], "-d"); EXPECT_STREQ(nonros_argv[1], "-d");
@ -310,7 +310,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args
&nonros_argc, &nonros_argc,
&nonros_argv); &nonros_argv);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
if (NULL != nonros_argv) { if (NULL != nonros_argv) {
alloc.deallocate(nonros_argv, alloc.state); alloc.deallocate(nonros_argv, alloc.state);
@ -326,7 +326,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args);
EXPECT_EQ(0, parameter_filecount); EXPECT_EQ(0, parameter_filecount);
@ -344,13 +344,13 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args);
EXPECT_EQ(1, parameter_filecount); EXPECT_EQ(1, parameter_filecount);
char ** parameter_files = NULL; char ** parameter_files = NULL;
ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files); ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("parameter_filepath", parameter_files[0]); EXPECT_STREQ("parameter_filepath", parameter_files[0]);
for (int i = 0; i < parameter_filecount; ++i) { for (int i = 0; i < parameter_filecount; ++i) {
@ -372,13 +372,13 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args);
EXPECT_EQ(2, parameter_filecount); EXPECT_EQ(2, parameter_filecount);
char ** parameter_files = NULL; char ** parameter_files = NULL;
ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files); ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("parameter_filepath1", parameter_files[0]); EXPECT_STREQ("parameter_filepath1", parameter_files[0]);
EXPECT_STREQ("parameter_filepath2", parameter_files[1]); EXPECT_STREQ("parameter_filepath2", parameter_files[1]);
for (int i = 0; i < parameter_filecount; ++i) { for (int i = 0; i < parameter_filecount; ++i) {

View file

@ -33,22 +33,22 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_client_node"; const char * name = "test_client_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
void TearDown() void TearDown()
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -68,12 +68,12 @@ TEST_F(TestClientFixture, test_client_nominal) {
ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &client_options); ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &client_options);
// Check the return code of initialization and that the service name matches what's expected // Check the return code of initialization and that the service name matches what's expected
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0); EXPECT_EQ(strcmp(rcl_client_get_service_name(&client), expected_topic_name), 0);
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
// Initialize the client request. // Initialize the client request.
@ -86,7 +86,7 @@ TEST_F(TestClientFixture, test_client_nominal) {
int64_t sequence_number = 0; int64_t sequence_number = 0;
ret = rcl_send_request(&client, &req, &sequence_number); ret = rcl_send_request(&client, &req, &sequence_number);
EXPECT_EQ(sequence_number, 1); EXPECT_EQ(sequence_number, 1);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
@ -104,55 +104,55 @@ TEST_F(TestClientFixture, test_client_init_fini) {
// Try passing null for client in init. // Try passing null for client in init.
ret = rcl_client_init(nullptr, this->node_ptr, ts, topic_name, &default_client_options); ret = rcl_client_init(nullptr, this->node_ptr, ts, topic_name, &default_client_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for a node pointer in init. // Try passing null for a node pointer in init.
client = rcl_get_zero_initialized_client(); client = rcl_get_zero_initialized_client();
ret = rcl_client_init(&client, nullptr, ts, topic_name, &default_client_options); ret = rcl_client_init(&client, nullptr, ts, topic_name, &default_client_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Check if null publisher is valid // Check if null publisher is valid
EXPECT_FALSE(rcl_client_is_valid(nullptr, nullptr)); EXPECT_FALSE(rcl_client_is_valid(nullptr));
rcl_reset_error(); rcl_reset_error();
// Check if zero initialized client is valid // Check if zero initialized client is valid
client = rcl_get_zero_initialized_client(); client = rcl_get_zero_initialized_client();
EXPECT_FALSE(rcl_client_is_valid(&client, nullptr)); EXPECT_FALSE(rcl_client_is_valid(&client));
rcl_reset_error(); rcl_reset_error();
// Check that a valid client is valid // Check that a valid client is valid
client = rcl_get_zero_initialized_client(); client = rcl_get_zero_initialized_client();
ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &default_client_options); ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, &default_client_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_TRUE(rcl_client_is_valid(&client, nullptr)); EXPECT_TRUE(rcl_client_is_valid(&client));
rcl_reset_error(); rcl_reset_error();
// Try passing an invalid (uninitialized) node in init. // Try passing an invalid (uninitialized) node in init.
client = rcl_get_zero_initialized_client(); client = rcl_get_zero_initialized_client();
rcl_node_t invalid_node = rcl_get_zero_initialized_node(); rcl_node_t invalid_node = rcl_get_zero_initialized_node();
ret = rcl_client_init(&client, &invalid_node, ts, topic_name, &default_client_options); ret = rcl_client_init(&client, &invalid_node, ts, topic_name, &default_client_options);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for the type support in init. // Try passing null for the type support in init.
client = rcl_get_zero_initialized_client(); client = rcl_get_zero_initialized_client();
ret = rcl_client_init( ret = rcl_client_init(
&client, this->node_ptr, nullptr, topic_name, &default_client_options); &client, this->node_ptr, nullptr, topic_name, &default_client_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for the topic name in init. // Try passing null for the topic name in init.
client = rcl_get_zero_initialized_client(); client = rcl_get_zero_initialized_client();
ret = rcl_client_init(&client, this->node_ptr, ts, nullptr, &default_client_options); ret = rcl_client_init(&client, this->node_ptr, ts, nullptr, &default_client_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for the options in init. // Try passing null for the options in init.
client = rcl_get_zero_initialized_client(); client = rcl_get_zero_initialized_client();
ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, nullptr); ret = rcl_client_init(&client, this->node_ptr, ts, topic_name, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing options with an invalid allocate in allocator with init. // Try passing options with an invalid allocate in allocator with init.
@ -162,7 +162,7 @@ TEST_F(TestClientFixture, test_client_init_fini) {
client_options_with_invalid_allocator.allocator.allocate = nullptr; client_options_with_invalid_allocator.allocator.allocate = nullptr;
ret = rcl_client_init( ret = rcl_client_init(
&client, this->node_ptr, ts, topic_name, &client_options_with_invalid_allocator); &client, this->node_ptr, ts, topic_name, &client_options_with_invalid_allocator);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing options with an invalid deallocate in allocator with init. // Try passing options with an invalid deallocate in allocator with init.
@ -171,7 +171,7 @@ TEST_F(TestClientFixture, test_client_init_fini) {
client_options_with_invalid_allocator.allocator.deallocate = nullptr; client_options_with_invalid_allocator.allocator.deallocate = nullptr;
ret = rcl_client_init( ret = rcl_client_init(
&client, this->node_ptr, ts, topic_name, &client_options_with_invalid_allocator); &client, this->node_ptr, ts, topic_name, &client_options_with_invalid_allocator);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// An allocator with an invalid realloc will probably work (so we will not test it). // An allocator with an invalid realloc will probably work (so we will not test it).
@ -184,6 +184,6 @@ TEST_F(TestClientFixture, test_client_init_fini) {
client_options_with_failing_allocator.allocator.reallocate = failing_realloc; client_options_with_failing_allocator.allocator.reallocate = failing_realloc;
ret = rcl_client_init( ret = rcl_client_init(
&client, this->node_ptr, ts, topic_name, &client_options_with_failing_allocator); &client, this->node_ptr, ts, topic_name, &client_options_with_failing_allocator);
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
} }

View file

@ -42,7 +42,7 @@ TEST(test_expand_topic_name, normal) {
std::string expected = std::string(ns) + "/" + node + "/chatter"; std::string expected = std::string(ns) + "/" + node + "/chatter";
char * expanded_topic; char * expanded_topic;
ret = rcl_expand_topic_name(topic, node, ns, &subs, allocator, &expanded_topic); ret = rcl_expand_topic_name(topic, node, ns, &subs, allocator, &expanded_topic);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ(expected.c_str(), expanded_topic); EXPECT_STREQ(expected.c_str(), expanded_topic);
} }
} }
@ -172,7 +172,7 @@ TEST(test_expand_topic_name, various_valid_topics) {
"' and namespace '" << ns << "'"; "' and namespace '" << ns << "'";
EXPECT_EQ(RCL_RET_OK, ret) << EXPECT_EQ(RCL_RET_OK, ret) <<
ss.str() << ss.str() <<
", it failed with '" << ret << "': " << rcl_get_error_string_safe(); ", it failed with '" << ret << "': " << rcl_get_error_string().str;
EXPECT_STREQ(expected.c_str(), expanded_topic) << ss.str() << " strings did not match.\n"; EXPECT_STREQ(expected.c_str(), expanded_topic) << ss.str() << " strings did not match.\n";
} }
} }
@ -216,7 +216,7 @@ TEST(test_expand_topic_name, custom_substitution) {
const char * node = "my_node"; const char * node = "my_node";
char * expanded_topic; char * expanded_topic;
ret = rcl_expand_topic_name(topic, node, ns, &subs, allocator, &expanded_topic); ret = rcl_expand_topic_name(topic, node, ns, &subs, allocator, &expanded_topic);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/my_ns/pong", expanded_topic); EXPECT_STREQ("/my_ns/pong", expanded_topic);
} }
} }

View file

@ -48,14 +48,14 @@ public:
TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) { TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) {
auto ret = rcl_init(0, nullptr, rcl_get_default_allocator()); auto ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
auto node1_ptr = new rcl_node_t; auto node1_ptr = new rcl_node_t;
*node1_ptr = rcl_get_zero_initialized_node(); *node1_ptr = rcl_get_zero_initialized_node();
const char * node1_name = "node1"; const char * node1_name = "node1";
const char * node1_namespace = "/"; const char * node1_namespace = "/";
rcl_node_options_t node1_options = rcl_node_get_default_options(); 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, &node1_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
auto node2_ptr = new rcl_node_t; auto node2_ptr = new rcl_node_t;
*node2_ptr = rcl_get_zero_initialized_node(); *node2_ptr = rcl_get_zero_initialized_node();
@ -63,7 +63,7 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
const char * node2_namespace = "/"; const char * node2_namespace = "/";
rcl_node_options_t node2_options = rcl_node_get_default_options(); 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, &node2_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
auto node3_ptr = new rcl_node_t; auto node3_ptr = new rcl_node_t;
*node3_ptr = rcl_get_zero_initialized_node(); *node3_ptr = rcl_get_zero_initialized_node();
@ -71,7 +71,7 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
const char * node3_namespace = "/ns"; const char * node3_namespace = "/ns";
rcl_node_options_t node3_options = rcl_node_get_default_options(); 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, &node3_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
auto node4_ptr = new rcl_node_t; auto node4_ptr = new rcl_node_t;
*node4_ptr = rcl_get_zero_initialized_node(); *node4_ptr = rcl_get_zero_initialized_node();
@ -79,14 +79,14 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
const char * node4_namespace = "/ns/ns"; const char * node4_namespace = "/ns/ns";
rcl_node_options_t node4_options = rcl_node_get_default_options(); 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, &node4_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
std::this_thread::sleep_for(1s); std::this_thread::sleep_for(1s);
rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array(); rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array();
rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array(); rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array();
ret = rcl_get_node_names(node1_ptr, node1_options.allocator, &node_names, &node_namespaces); ret = rcl_get_node_names(node1_ptr, node1_options.allocator, &node_names, &node_namespaces);
ASSERT_EQ(RCUTILS_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCUTILS_RET_OK, ret) << rcl_get_error_string().str;
std::stringstream ss; std::stringstream ss;
ss << "[test_rcl_get_node_names]: Found node names:" << std::endl; ss << "[test_rcl_get_node_names]: Found node names:" << std::endl;
@ -113,20 +113,20 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names)
ret = rcl_node_fini(node1_ptr); ret = rcl_node_fini(node1_ptr);
delete node1_ptr; delete node1_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_node_fini(node2_ptr); ret = rcl_node_fini(node2_ptr);
delete node2_ptr; delete node2_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_node_fini(node3_ptr); ret = rcl_node_fini(node3_ptr);
delete node3_ptr; delete node3_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_node_fini(node4_ptr); ret = rcl_node_fini(node4_ptr);
delete node4_ptr; delete node4_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }

View file

@ -58,23 +58,23 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->old_node_ptr = new rcl_node_t; this->old_node_ptr = new rcl_node_t;
*this->old_node_ptr = rcl_get_zero_initialized_node(); *this->old_node_ptr = rcl_get_zero_initialized_node();
const char * old_name = "old_node_name"; const char * old_name = "old_node_name";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); 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(); // after this, the old_node_ptr should be invalid
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_graph_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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->wait_set_ptr = new rcl_wait_set_t; this->wait_set_ptr = new rcl_wait_set_t;
*this->wait_set_ptr = rcl_get_zero_initialized_wait_set(); *this->wait_set_ptr = rcl_get_zero_initialized_wait_set();
@ -86,18 +86,18 @@ public:
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_node_fini(this->old_node_ptr); ret = rcl_node_fini(this->old_node_ptr);
delete this->old_node_ptr; delete this->old_node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(this->wait_set_ptr); ret = rcl_wait_set_fini(this->wait_set_ptr);
delete this->wait_set_ptr; delete this->wait_set_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_node_fini(this->node_ptr); ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -115,31 +115,31 @@ TEST_F(
rcl_node_t zero_node = rcl_get_zero_initialized_node(); rcl_node_t zero_node = rcl_get_zero_initialized_node();
// invalid node // invalid node
ret = rcl_get_topic_names_and_types(nullptr, &allocator, false, &tnat); ret = rcl_get_topic_names_and_types(nullptr, &allocator, false, &tnat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_get_topic_names_and_types(&zero_node, &allocator, false, &tnat); ret = rcl_get_topic_names_and_types(&zero_node, &allocator, false, &tnat);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_get_topic_names_and_types(this->old_node_ptr, &allocator, false, &tnat); ret = rcl_get_topic_names_and_types(this->old_node_ptr, &allocator, false, &tnat);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// invalid allocator // invalid allocator
ret = rcl_get_topic_names_and_types(this->node_ptr, nullptr, false, &tnat); ret = rcl_get_topic_names_and_types(this->node_ptr, nullptr, false, &tnat);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// invalid topic_names_and_types // invalid topic_names_and_types
ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, nullptr); ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// invalid argument to rcl_destroy_topic_names_and_types // invalid argument to rcl_destroy_topic_names_and_types
ret = rcl_names_and_types_fini(nullptr); ret = rcl_names_and_types_fini(nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// valid calls // valid calls
ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, &tnat); ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, &tnat);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_names_and_types_fini(&tnat); ret = rcl_names_and_types_fini(&tnat);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
/* Test the rcl_count_publishers function. /* Test the rcl_count_publishers function.
@ -156,26 +156,26 @@ TEST_F(
size_t count; size_t count;
// invalid node // invalid node
ret = rcl_count_publishers(nullptr, topic_name, &count); ret = rcl_count_publishers(nullptr, topic_name, &count);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_count_publishers(&zero_node, topic_name, &count); ret = rcl_count_publishers(&zero_node, topic_name, &count);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_count_publishers(this->old_node_ptr, topic_name, &count); ret = rcl_count_publishers(this->old_node_ptr, topic_name, &count);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// invalid topic name // invalid topic name
ret = rcl_count_publishers(this->node_ptr, nullptr, &count); ret = rcl_count_publishers(this->node_ptr, nullptr, &count);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// TODO(wjwwood): test valid strings with invalid topic names in them // TODO(wjwwood): test valid strings with invalid topic names in them
// invalid count // invalid count
ret = rcl_count_publishers(this->node_ptr, topic_name, nullptr); ret = rcl_count_publishers(this->node_ptr, topic_name, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// valid call // valid call
ret = rcl_count_publishers(this->node_ptr, topic_name, &count); ret = rcl_count_publishers(this->node_ptr, topic_name, &count);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
} }
@ -193,26 +193,26 @@ TEST_F(
size_t count; size_t count;
// invalid node // invalid node
ret = rcl_count_subscribers(nullptr, topic_name, &count); ret = rcl_count_subscribers(nullptr, topic_name, &count);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_count_subscribers(&zero_node, topic_name, &count); ret = rcl_count_subscribers(&zero_node, topic_name, &count);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_count_subscribers(this->old_node_ptr, topic_name, &count); ret = rcl_count_subscribers(this->old_node_ptr, topic_name, &count);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// invalid topic name // invalid topic name
ret = rcl_count_subscribers(this->node_ptr, nullptr, &count); ret = rcl_count_subscribers(this->node_ptr, nullptr, &count);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// TODO(wjwwood): test valid strings with invalid topic names in them // TODO(wjwwood): test valid strings with invalid topic names in them
// invalid count // invalid count
ret = rcl_count_subscribers(this->node_ptr, topic_name, nullptr); ret = rcl_count_subscribers(this->node_ptr, topic_name, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// valid call // valid call
ret = rcl_count_subscribers(this->node_ptr, topic_name, &count); ret = rcl_count_subscribers(this->node_ptr, topic_name, &count);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
} }
@ -241,16 +241,16 @@ check_graph_state(
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
for (size_t i = 0; i < number_of_tries; ++i) { for (size_t i = 0; i < number_of_tries; ++i) {
ret = rcl_count_publishers(node_ptr, topic_name.c_str(), &publisher_count); ret = rcl_count_publishers(node_ptr, topic_name.c_str(), &publisher_count);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_count_subscribers(node_ptr, topic_name.c_str(), &subscriber_count); ret = rcl_count_subscribers(node_ptr, topic_name.c_str(), &subscriber_count);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
tnat = rcl_get_zero_initialized_names_and_types(); tnat = rcl_get_zero_initialized_names_and_types();
ret = rcl_get_topic_names_and_types(node_ptr, &allocator, false, &tnat); ret = rcl_get_topic_names_and_types(node_ptr, &allocator, false, &tnat);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
is_in_tnat = false; is_in_tnat = false;
for (size_t i = 0; RCL_RET_OK == ret && i < tnat.names.size; ++i) { for (size_t i = 0; RCL_RET_OK == ret && i < tnat.names.size; ++i) {
@ -261,7 +261,7 @@ check_graph_state(
} }
if (RCL_RET_OK == ret) { if (RCL_RET_OK == ret) {
ret = rcl_names_and_types_fini(&tnat); ret = rcl_names_and_types_fini(&tnat);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
} }
@ -286,9 +286,9 @@ check_graph_state(
continue; continue;
} }
ret = rcl_wait_set_clear(wait_set_ptr); ret = rcl_wait_set_clear(wait_set_ptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(wait_set_ptr, graph_guard_condition); ret = rcl_wait_set_add_guard_condition(wait_set_ptr, graph_guard_condition);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
std::chrono::nanoseconds time_to_sleep = std::chrono::milliseconds(200); std::chrono::nanoseconds time_to_sleep = std::chrono::milliseconds(200);
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME,
" state wrong, waiting up to '%s' nanoseconds for graph changes... ", " state wrong, waiting up to '%s' nanoseconds for graph changes... ",
@ -299,7 +299,7 @@ check_graph_state(
continue; continue;
} }
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "change occurred"); RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, "change occurred");
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
EXPECT_EQ(expected_publisher_count, publisher_count); EXPECT_EQ(expected_publisher_count, publisher_count);
EXPECT_EQ(expected_subscriber_count, subscriber_count); EXPECT_EQ(expected_subscriber_count, subscriber_count);
@ -335,7 +335,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options(); rcl_publisher_options_t pub_ops = rcl_publisher_get_default_options();
auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives); auto ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives);
ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops); ret = rcl_publisher_init(&pub, this->node_ptr, ts, topic_name.c_str(), &pub_ops);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Check the graph. // Check the graph.
check_graph_state( check_graph_state(
@ -351,7 +351,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
rcl_subscription_t sub = rcl_get_zero_initialized_subscription(); rcl_subscription_t sub = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options(); rcl_subscription_options_t sub_ops = rcl_subscription_get_default_options();
ret = rcl_subscription_init(&sub, this->node_ptr, ts, topic_name.c_str(), &sub_ops); ret = rcl_subscription_init(&sub, this->node_ptr, ts, topic_name.c_str(), &sub_ops);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Check the graph again. // Check the graph again.
check_graph_state( check_graph_state(
@ -365,7 +365,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
9); // number of retries 9); // number of retries
// Destroy the publisher. // Destroy the publisher.
ret = rcl_publisher_fini(&pub, this->node_ptr); ret = rcl_publisher_fini(&pub, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Check the graph again. // Check the graph again.
check_graph_state( check_graph_state(
@ -379,7 +379,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_query_functio
9); // number of retries 9); // number of retries
// Destroy the subscriber. // Destroy the subscriber.
ret = rcl_subscription_fini(&sub, this->node_ptr); ret = rcl_subscription_fini(&sub, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Check the graph again. // Check the graph again.
check_graph_state( check_graph_state(
@ -412,7 +412,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi
rcl_ret_t ret = rcl_publisher_init( rcl_ret_t ret = rcl_publisher_init(
&pub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives), &pub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives),
"/chatter_test_graph_guard_condition_topics", &pub_ops); "/chatter_test_graph_guard_condition_topics", &pub_ops);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// sleep // sleep
std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::this_thread::sleep_for(std::chrono::milliseconds(100));
// create the subscription // create the subscription
@ -421,17 +421,17 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi
ret = rcl_subscription_init( ret = rcl_subscription_init(
&sub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives), &sub, this->node_ptr, ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Primitives),
"/chatter_test_graph_guard_condition_topics", &sub_ops); "/chatter_test_graph_guard_condition_topics", &sub_ops);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// sleep // sleep
std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::this_thread::sleep_for(std::chrono::milliseconds(100));
// destroy the subscription // destroy the subscription
ret = rcl_subscription_fini(&sub, this->node_ptr); ret = rcl_subscription_fini(&sub, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// sleep // sleep
std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::this_thread::sleep_for(std::chrono::milliseconds(100));
// destroy the publication // destroy the publication
ret = rcl_publisher_fini(&pub, this->node_ptr); ret = rcl_publisher_fini(&pub, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// notify that the thread is done // notify that the thread is done
topic_changes_promise.set_value(true); topic_changes_promise.set_value(true);
}); });
@ -439,15 +439,15 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_graph_guard_conditi
// once for each change in the topics thread. // once for each change in the topics thread.
const rcl_guard_condition_t * graph_guard_condition = const rcl_guard_condition_t * graph_guard_condition =
rcl_node_get_graph_guard_condition(this->node_ptr); rcl_node_get_graph_guard_condition(this->node_ptr);
ASSERT_NE(nullptr, graph_guard_condition) << rcl_get_error_string_safe(); ASSERT_NE(nullptr, graph_guard_condition) << rcl_get_error_string().str;
std::shared_future<bool> future = topic_changes_promise.get_future(); std::shared_future<bool> future = topic_changes_promise.get_future();
size_t graph_changes_count = 0; size_t graph_changes_count = 0;
// while the topic thread is not done, wait and count the graph changes // while the topic thread is not done, wait and count the graph changes
while (future.wait_for(std::chrono::seconds(0)) != std::future_status::ready) { while (future.wait_for(std::chrono::seconds(0)) != std::future_status::ready) {
ret = rcl_wait_set_clear(this->wait_set_ptr); ret = rcl_wait_set_clear(this->wait_set_ptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(this->wait_set_ptr, graph_guard_condition); ret = rcl_wait_set_add_guard_condition(this->wait_set_ptr, graph_guard_condition);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
std::chrono::nanoseconds time_to_sleep = std::chrono::milliseconds(200); std::chrono::nanoseconds time_to_sleep = std::chrono::milliseconds(200);
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME,
"waiting up to '%s' nanoseconds for graph changes", "waiting up to '%s' nanoseconds for graph changes",
@ -473,20 +473,20 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
const char * service_name = "/service_test_rcl_service_server_is_available"; const char * service_name = "/service_test_rcl_service_server_is_available";
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options); ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
// Check, knowing there is no service server (created by us at least). // Check, knowing there is no service server (created by us at least).
bool is_available; bool is_available;
ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available); ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ASSERT_FALSE(is_available); ASSERT_FALSE(is_available);
// Setup function to wait for service state to change using graph guard condition. // Setup function to wait for service state to change using graph guard condition.
const rcl_guard_condition_t * graph_guard_condition = const rcl_guard_condition_t * graph_guard_condition =
rcl_node_get_graph_guard_condition(this->node_ptr); rcl_node_get_graph_guard_condition(this->node_ptr);
ASSERT_NE(nullptr, graph_guard_condition) << rcl_get_error_string_safe(); ASSERT_NE(nullptr, graph_guard_condition) << rcl_get_error_string().str;
auto wait_for_service_state_to_change = [this, &graph_guard_condition, &client]( auto wait_for_service_state_to_change = [this, &graph_guard_condition, &client](
bool expected_state, bool expected_state,
bool & is_available) bool & is_available)
@ -503,9 +503,9 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
time_to_sleep = min_sleep; time_to_sleep = min_sleep;
} }
rcl_ret_t ret = rcl_wait_set_clear(this->wait_set_ptr); rcl_ret_t ret = rcl_wait_set_clear(this->wait_set_ptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(this->wait_set_ptr, graph_guard_condition); ret = rcl_wait_set_add_guard_condition(this->wait_set_ptr, graph_guard_condition);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME, RCUTILS_LOG_INFO_NAMED(ROS_PACKAGE_NAME,
"waiting up to '%s' nanoseconds for graph changes", "waiting up to '%s' nanoseconds for graph changes",
std::to_string(time_to_sleep.count()).c_str()); std::to_string(time_to_sleep.count()).c_str());
@ -526,10 +526,10 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
continue; continue;
} }
} else { } else {
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available); ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
if (is_available == expected_state) { if (is_available == expected_state) {
break; break;
} }
@ -540,10 +540,10 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options); ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
// Wait for and then assert that it is available. // Wait for and then assert that it is available.
wait_for_service_state_to_change(true, is_available); wait_for_service_state_to_change(true, is_available);

View file

@ -42,8 +42,7 @@ public:
do { \ do { \
rcl_lexeme_t actual_lexeme; \ rcl_lexeme_t actual_lexeme; \
size_t length; \ size_t length; \
rcl_allocator_t allocator = rcl_get_default_allocator(); \ rcl_ret_t ret = rcl_lexer_analyze(text, &actual_lexeme, &length); \
rcl_ret_t ret = rcl_lexer_analyze(text, allocator, &actual_lexeme, &length); \
ASSERT_EQ(RCL_RET_OK, ret); \ ASSERT_EQ(RCL_RET_OK, ret); \
EXPECT_EQ(expected_lexeme, actual_lexeme); \ EXPECT_EQ(expected_lexeme, actual_lexeme); \
std::string actual_text(text, length); \ std::string actual_text(text, length); \

View file

@ -44,22 +44,22 @@ public:
{ \ { \
name = rcl_get_zero_initialized_lexer_lookahead2(); \ name = rcl_get_zero_initialized_lexer_lookahead2(); \
rcl_ret_t ret = rcl_lexer_lookahead2_init(&name, text, rcl_get_default_allocator()); \ rcl_ret_t ret = rcl_lexer_lookahead2_init(&name, text, rcl_get_default_allocator()); \
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \
} \ } \
auto __scope_lookahead2_ ## name = osrf_testing_tools_cpp::make_scope_exit( \ auto __scope_lookahead2_ ## name = osrf_testing_tools_cpp::make_scope_exit( \
[&name]() { \ [&name]() { \
rcl_ret_t ret = rcl_lexer_lookahead2_fini(&buffer); \ rcl_ret_t ret = rcl_lexer_lookahead2_fini(&buffer); \
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \
}) })
TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_init_fini_twice) TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_init_fini_twice)
{ {
rcl_lexer_lookahead2_t buffer = rcl_get_zero_initialized_lexer_lookahead2(); rcl_lexer_lookahead2_t buffer = rcl_get_zero_initialized_lexer_lookahead2();
rcl_ret_t ret = rcl_lexer_lookahead2_init(&buffer, "foobar", rcl_get_default_allocator()); rcl_ret_t ret = rcl_lexer_lookahead2_init(&buffer, "foobar", rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_lexer_lookahead2_fini(&buffer); ret = rcl_lexer_lookahead2_fini(&buffer);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_lexer_lookahead2_fini(&buffer); ret = rcl_lexer_lookahead2_fini(&buffer);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
@ -105,7 +105,7 @@ TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_peek2)
rcl_lexeme_t lexeme2 = RCL_LEXEME_NONE; rcl_lexeme_t lexeme2 = RCL_LEXEME_NONE;
ret = rcl_lexer_lookahead2_peek2(&buffer, &lexeme1, &lexeme2); ret = rcl_lexer_lookahead2_peek2(&buffer, &lexeme1, &lexeme2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_LEXEME_TOKEN, lexeme1); EXPECT_EQ(RCL_LEXEME_TOKEN, lexeme1);
EXPECT_EQ(RCL_LEXEME_FORWARD_SLASH, lexeme2); EXPECT_EQ(RCL_LEXEME_FORWARD_SLASH, lexeme2);
@ -113,7 +113,7 @@ TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_peek2)
lexeme1 = RCL_LEXEME_NONE; lexeme1 = RCL_LEXEME_NONE;
lexeme2 = RCL_LEXEME_NONE; lexeme2 = RCL_LEXEME_NONE;
ret = rcl_lexer_lookahead2_peek2(&buffer, &lexeme1, &lexeme2); ret = rcl_lexer_lookahead2_peek2(&buffer, &lexeme1, &lexeme2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_LEXEME_TOKEN, lexeme1); EXPECT_EQ(RCL_LEXEME_TOKEN, lexeme1);
EXPECT_EQ(RCL_LEXEME_FORWARD_SLASH, lexeme2); EXPECT_EQ(RCL_LEXEME_FORWARD_SLASH, lexeme2);
} }
@ -134,7 +134,7 @@ TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_eof)
rcl_lexeme_t lexeme1 = RCL_LEXEME_NONE; rcl_lexeme_t lexeme1 = RCL_LEXEME_NONE;
rcl_lexeme_t lexeme2 = RCL_LEXEME_NONE; rcl_lexeme_t lexeme2 = RCL_LEXEME_NONE;
ret = rcl_lexer_lookahead2_peek2(&buffer, &lexeme1, &lexeme2); ret = rcl_lexer_lookahead2_peek2(&buffer, &lexeme1, &lexeme2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_LEXEME_EOF, lexeme1); EXPECT_EQ(RCL_LEXEME_EOF, lexeme1);
EXPECT_EQ(RCL_LEXEME_EOF, lexeme2); EXPECT_EQ(RCL_LEXEME_EOF, lexeme2);
} }
@ -161,37 +161,37 @@ TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_accept)
// Peek token // Peek token
ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme); ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_LEXEME_TOKEN, lexeme); EXPECT_EQ(RCL_LEXEME_TOKEN, lexeme);
// accept token // accept token
ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length); ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("foobar", std::string(lexeme_text, lexeme_text_length).c_str()); EXPECT_STREQ("foobar", std::string(lexeme_text, lexeme_text_length).c_str());
// peek forward slash // peek forward slash
ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme); ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_LEXEME_FORWARD_SLASH, lexeme); EXPECT_EQ(RCL_LEXEME_FORWARD_SLASH, lexeme);
// accept forward slash // accept forward slash
ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length); ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/", std::string(lexeme_text, lexeme_text_length).c_str()); EXPECT_STREQ("/", std::string(lexeme_text, lexeme_text_length).c_str());
// peek eof // peek eof
ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme); ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_LEXEME_EOF, lexeme); EXPECT_EQ(RCL_LEXEME_EOF, lexeme);
// accept eof // accept eof
ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length); ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("", std::string(lexeme_text, lexeme_text_length).c_str()); EXPECT_STREQ("", std::string(lexeme_text, lexeme_text_length).c_str());
// peek eof again // peek eof again
ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme); ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_LEXEME_EOF, lexeme); EXPECT_EQ(RCL_LEXEME_EOF, lexeme);
} }
@ -204,12 +204,12 @@ TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_expect)
size_t lexeme_text_length; size_t lexeme_text_length;
ret = rcl_lexer_lookahead2_expect(&buffer, RCL_LEXEME_TOKEN, &lexeme_text, &lexeme_text_length); ret = rcl_lexer_lookahead2_expect(&buffer, RCL_LEXEME_TOKEN, &lexeme_text, &lexeme_text_length);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("node_name", std::string(lexeme_text, lexeme_text_length).c_str()); EXPECT_STREQ("node_name", std::string(lexeme_text, lexeme_text_length).c_str());
ret = rcl_lexer_lookahead2_expect( ret = rcl_lexer_lookahead2_expect(
&buffer, RCL_LEXEME_FORWARD_SLASH, &lexeme_text, &lexeme_text_length); &buffer, RCL_LEXEME_FORWARD_SLASH, &lexeme_text, &lexeme_text_length);
EXPECT_EQ(RCL_RET_WRONG_LEXEME, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_WRONG_LEXEME, ret) << rcl_get_error_string().str;
} }
#define EXPECT_LOOKAHEAD(expected_lexeme, expected_text, buffer) \ #define EXPECT_LOOKAHEAD(expected_lexeme, expected_text, buffer) \
@ -219,9 +219,9 @@ TEST_F(CLASSNAME(TestLexerLookaheadFixture, RMW_IMPLEMENTATION), test_expect)
rcl_lexeme_t lexeme; \ rcl_lexeme_t lexeme; \
ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme); \ ret = rcl_lexer_lookahead2_peek(&buffer, &lexeme); \
EXPECT_EQ(expected_lexeme, lexeme); \ EXPECT_EQ(expected_lexeme, lexeme); \
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \
ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length); \ ret = rcl_lexer_lookahead2_accept(&buffer, &lexeme_text, &lexeme_text_length); \
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); \ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; \
EXPECT_STREQ(expected_text, std::string(lexeme_text, lexeme_text_length).c_str()); \ EXPECT_STREQ(expected_text, std::string(lexeme_text, lexeme_text_length).c_str()); \
} while (false) } while (false)

View file

@ -133,16 +133,16 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
}); });
// Test rcl_node_is_valid(). // Test rcl_node_is_valid().
bool is_valid; bool is_valid;
is_valid = rcl_node_is_valid(nullptr, nullptr); is_valid = rcl_node_is_valid(nullptr);
EXPECT_FALSE(is_valid); EXPECT_FALSE(is_valid);
rcl_reset_error(); rcl_reset_error();
is_valid = rcl_node_is_valid(&zero_node, nullptr); is_valid = rcl_node_is_valid(&zero_node);
EXPECT_FALSE(is_valid); EXPECT_FALSE(is_valid);
rcl_reset_error(); rcl_reset_error();
is_valid = rcl_node_is_valid(&invalid_node, nullptr); is_valid = rcl_node_is_valid(&invalid_node);
EXPECT_FALSE(is_valid); EXPECT_FALSE(is_valid);
rcl_reset_error(); rcl_reset_error();
is_valid = rcl_node_is_valid(&node, nullptr); is_valid = rcl_node_is_valid(&node);
EXPECT_TRUE(is_valid); EXPECT_TRUE(is_valid);
rcl_reset_error(); rcl_reset_error();
// Test rcl_node_get_name(). // Test rcl_node_get_name().

View file

@ -39,22 +39,22 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_publisher_node"; const char * name = "test_publisher_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
void TearDown() void TearDown()
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -69,10 +69,10 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
const char * expected_topic_name = "/chatter"; const char * expected_topic_name = "/chatter";
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0); EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0);
test_msgs__msg__Primitives msg; test_msgs__msg__Primitives msg;
@ -80,7 +80,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
msg.int64_value = 42; msg.int64_value = 42;
ret = rcl_publish(&publisher, &msg); ret = rcl_publish(&publisher, &msg);
test_msgs__msg__Primitives__fini(&msg); test_msgs__msg__Primitives__fini(&msg);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
/* Basic nominal test of a publisher with a string. /* Basic nominal test of a publisher with a string.
@ -93,17 +93,17 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_nomin
const char * topic_name = "chatter"; const char * topic_name = "chatter";
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
test_msgs__msg__Primitives msg; test_msgs__msg__Primitives msg;
test_msgs__msg__Primitives__init(&msg); test_msgs__msg__Primitives__init(&msg);
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, "testing")); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, "testing"));
ret = rcl_publish(&publisher, &msg); ret = rcl_publish(&publisher, &msg);
test_msgs__msg__Primitives__fini(&msg); test_msgs__msg__Primitives__fini(&msg);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
/* Test two publishers using different message types with the same basename. /* Test two publishers using different message types with the same basename.
@ -121,10 +121,10 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
const char * expected_topic_name = "/basename"; const char * expected_topic_name = "/basename";
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts_int, topic_name, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts_int, topic_name, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0); EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher), expected_topic_name), 0);
@ -135,10 +135,10 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
expected_topic_name = "/namespace/basename"; expected_topic_name = "/namespace/basename";
ret = rcl_publisher_init( ret = rcl_publisher_init(
&publisher_in_namespace, this->node_ptr, ts_string, topic_name, &publisher_options); &publisher_in_namespace, this->node_ptr, ts_string, topic_name, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_publisher_fini(&publisher_in_namespace, this->node_ptr); rcl_ret_t ret = rcl_publisher_fini(&publisher_in_namespace, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher_in_namespace), expected_topic_name), 0); EXPECT_EQ(strcmp(rcl_publisher_get_topic_name(&publisher_in_namespace), expected_topic_name), 0);
@ -146,14 +146,14 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publishers_diff
test_msgs__msg__Primitives__init(&msg_int); test_msgs__msg__Primitives__init(&msg_int);
msg_int.int64_value = 42; msg_int.int64_value = 42;
ret = rcl_publish(&publisher, &msg_int); ret = rcl_publish(&publisher, &msg_int);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_msgs__msg__Primitives__fini(&msg_int); test_msgs__msg__Primitives__fini(&msg_int);
test_msgs__msg__Primitives msg_string; test_msgs__msg__Primitives msg_string;
test_msgs__msg__Primitives__init(&msg_string); test_msgs__msg__Primitives__init(&msg_string);
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg_string.string_value, "testing")); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg_string.string_value, "testing"));
ret = rcl_publish(&publisher_in_namespace, &msg_string); ret = rcl_publish(&publisher_in_namespace, &msg_string);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
/* Testing the publisher init and fini functions. /* Testing the publisher init and fini functions.
@ -168,56 +168,56 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_
rcl_publisher_options_t default_publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t default_publisher_options = rcl_publisher_get_default_options();
// Check if null publisher is valid // Check if null publisher is valid
EXPECT_FALSE(rcl_publisher_is_valid(nullptr, nullptr)); EXPECT_FALSE(rcl_publisher_is_valid(nullptr));
rcl_reset_error(); rcl_reset_error();
// Check if zero initialized node is valid // Check if zero initialized node is valid
publisher = rcl_get_zero_initialized_publisher(); publisher = rcl_get_zero_initialized_publisher();
EXPECT_FALSE(rcl_publisher_is_valid(&publisher, nullptr)); EXPECT_FALSE(rcl_publisher_is_valid(&publisher));
rcl_reset_error(); rcl_reset_error();
// Check that valid publisher is valid // Check that valid publisher is valid
publisher = rcl_get_zero_initialized_publisher(); publisher = rcl_get_zero_initialized_publisher();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &default_publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, &default_publisher_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_TRUE(rcl_publisher_is_valid(&publisher, nullptr)); EXPECT_TRUE(rcl_publisher_is_valid(&publisher));
rcl_reset_error(); rcl_reset_error();
// Try passing null for publisher in init. // Try passing null for publisher in init.
ret = rcl_publisher_init(nullptr, this->node_ptr, ts, topic_name, &default_publisher_options); ret = rcl_publisher_init(nullptr, this->node_ptr, ts, topic_name, &default_publisher_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for a node pointer in init. // Try passing null for a node pointer in init.
publisher = rcl_get_zero_initialized_publisher(); publisher = rcl_get_zero_initialized_publisher();
ret = rcl_publisher_init(&publisher, nullptr, ts, topic_name, &default_publisher_options); ret = rcl_publisher_init(&publisher, nullptr, ts, topic_name, &default_publisher_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing an invalid (uninitialized) node in init. // Try passing an invalid (uninitialized) node in init.
publisher = rcl_get_zero_initialized_publisher(); publisher = rcl_get_zero_initialized_publisher();
rcl_node_t invalid_node = rcl_get_zero_initialized_node(); rcl_node_t invalid_node = rcl_get_zero_initialized_node();
ret = rcl_publisher_init(&publisher, &invalid_node, ts, topic_name, &default_publisher_options); ret = rcl_publisher_init(&publisher, &invalid_node, ts, topic_name, &default_publisher_options);
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for the type support in init. // Try passing null for the type support in init.
publisher = rcl_get_zero_initialized_publisher(); publisher = rcl_get_zero_initialized_publisher();
ret = rcl_publisher_init( ret = rcl_publisher_init(
&publisher, this->node_ptr, nullptr, topic_name, &default_publisher_options); &publisher, this->node_ptr, nullptr, topic_name, &default_publisher_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for the topic name in init. // Try passing null for the topic name in init.
publisher = rcl_get_zero_initialized_publisher(); publisher = rcl_get_zero_initialized_publisher();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, nullptr, &default_publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, nullptr, &default_publisher_options);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing null for the options in init. // Try passing null for the options in init.
publisher = rcl_get_zero_initialized_publisher(); publisher = rcl_get_zero_initialized_publisher();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, nullptr); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic_name, nullptr);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing options with an invalid allocate in allocator with init. // Try passing options with an invalid allocate in allocator with init.
@ -227,7 +227,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_
publisher_options_with_invalid_allocator.allocator.allocate = nullptr; publisher_options_with_invalid_allocator.allocator.allocate = nullptr;
ret = rcl_publisher_init( ret = rcl_publisher_init(
&publisher, this->node_ptr, ts, topic_name, &publisher_options_with_invalid_allocator); &publisher, this->node_ptr, ts, topic_name, &publisher_options_with_invalid_allocator);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Try passing options with an invalid deallocate in allocator with init. // Try passing options with an invalid deallocate in allocator with init.
@ -236,7 +236,7 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_
publisher_options_with_invalid_allocator.allocator.deallocate = nullptr; publisher_options_with_invalid_allocator.allocator.deallocate = nullptr;
ret = rcl_publisher_init( ret = rcl_publisher_init(
&publisher, this->node_ptr, ts, topic_name, &publisher_options_with_invalid_allocator); &publisher, this->node_ptr, ts, topic_name, &publisher_options_with_invalid_allocator);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// An allocator with an invalid realloc will probably work (so we will not test it). // An allocator with an invalid realloc will probably work (so we will not test it).
@ -250,6 +250,6 @@ TEST_F(CLASSNAME(TestPublisherFixture, RMW_IMPLEMENTATION), test_publisher_init_
publisher_options_with_failing_allocator.allocator.zero_allocate = failing_calloc; publisher_options_with_failing_allocator.allocator.zero_allocate = failing_calloc;
ret = rcl_publisher_init( ret = rcl_publisher_init(
&publisher, this->node_ptr, ts, topic_name, &publisher_options_with_failing_allocator); &publisher, this->node_ptr, ts, topic_name, &publisher_options_with_failing_allocator);
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
} }

View file

@ -19,6 +19,7 @@
#include "./failing_allocator_functions.hpp" #include "./failing_allocator_functions.hpp"
#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp" #include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp"
#include "rcl/error_handling.h" #include "rcl/error_handling.h"
#include "rcutils/format_string.h"
#include "rcutils/snprintf.h" #include "rcutils/snprintf.h"
#ifdef RMW_IMPLEMENTATION #ifdef RMW_IMPLEMENTATION

View file

@ -67,7 +67,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/foo", rcl_publisher_get_topic_name(&publisher)); EXPECT_STREQ("/bar/foo", rcl_publisher_get_topic_name(&publisher));
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node)); EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
} }
@ -78,7 +78,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_ret_t ret = rcl_subscription_init( rcl_ret_t ret = rcl_subscription_init(
&subscription, &node, ts, "/foo/bar", &subscription_options); &subscription, &node, ts, "/foo/bar", &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/foo", rcl_subscription_get_topic_name(&subscription)); EXPECT_STREQ("/bar/foo", rcl_subscription_get_topic_name(&subscription));
EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node)); EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node));
} }
@ -88,7 +88,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/foo", rcl_client_get_service_name(&client)); EXPECT_STREQ("/bar/foo", rcl_client_get_service_name(&client));
EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node)); EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node));
} }
@ -98,7 +98,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/foo", rcl_service_get_service_name(&service)); EXPECT_STREQ("/bar/foo", rcl_service_get_service_name(&service));
EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node)); EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node));
} }
@ -135,7 +135,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/bar", rcl_publisher_get_topic_name(&publisher)); EXPECT_STREQ("/foo/bar", rcl_publisher_get_topic_name(&publisher));
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node)); EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
} }
@ -146,7 +146,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_ret_t ret = rcl_subscription_init( rcl_ret_t ret = rcl_subscription_init(
&subscription, &node, ts, "/foo/bar", &subscription_options); &subscription, &node, ts, "/foo/bar", &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/bar", rcl_subscription_get_topic_name(&subscription)); EXPECT_STREQ("/foo/bar", rcl_subscription_get_topic_name(&subscription));
EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node)); EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node));
} }
@ -156,7 +156,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/bar", rcl_client_get_service_name(&client)); EXPECT_STREQ("/foo/bar", rcl_client_get_service_name(&client));
EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node)); EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node));
} }
@ -166,7 +166,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/bar", rcl_service_get_service_name(&service)); EXPECT_STREQ("/foo/bar", rcl_service_get_service_name(&service));
EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node)); EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node));
} }
@ -204,7 +204,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "/foo/bar", &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/local", rcl_publisher_get_topic_name(&publisher)); EXPECT_STREQ("/bar/local", rcl_publisher_get_topic_name(&publisher));
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node)); EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
} }
@ -215,7 +215,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_ret_t ret = rcl_subscription_init( rcl_ret_t ret = rcl_subscription_init(
&subscription, &node, ts, "/foo/bar", &subscription_options); &subscription, &node, ts, "/foo/bar", &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/local", rcl_subscription_get_topic_name(&subscription)); EXPECT_STREQ("/bar/local", rcl_subscription_get_topic_name(&subscription));
EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node)); EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node));
} }
@ -225,7 +225,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "/foo/bar", &client_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/local", rcl_client_get_service_name(&client)); EXPECT_STREQ("/bar/local", rcl_client_get_service_name(&client));
EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node)); EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node));
} }
@ -235,7 +235,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "/foo/bar", &service_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/bar/local", rcl_service_get_service_name(&service)); EXPECT_STREQ("/bar/local", rcl_service_get_service_name(&service));
EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node)); EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node));
} }
@ -258,7 +258,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "bar", &publisher_options); rcl_ret_t ret = rcl_publisher_init(&publisher, &node, ts, "bar", &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/remap/global", rcl_publisher_get_topic_name(&publisher)); EXPECT_STREQ("/foo/remap/global", rcl_publisher_get_topic_name(&publisher));
EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node)); EXPECT_EQ(RCL_RET_OK, rcl_publisher_fini(&publisher, &node));
} }
@ -269,7 +269,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_ret_t ret = rcl_subscription_init( rcl_ret_t ret = rcl_subscription_init(
&subscription, &node, ts, "bar", &subscription_options); &subscription, &node, ts, "bar", &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/remap/global", rcl_subscription_get_topic_name(&subscription)); EXPECT_STREQ("/foo/remap/global", rcl_subscription_get_topic_name(&subscription));
EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node)); EXPECT_EQ(RCL_RET_OK, rcl_subscription_fini(&subscription, &node));
} }
@ -279,7 +279,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_ret_t ret = rcl_client_init(&client, &node, ts, "bar", &client_options); rcl_ret_t ret = rcl_client_init(&client, &node, ts, "bar", &client_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/remap/global", rcl_client_get_service_name(&client)); EXPECT_STREQ("/foo/remap/global", rcl_client_get_service_name(&client));
EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node)); EXPECT_EQ(RCL_RET_OK, rcl_client_fini(&client, &node));
} }
@ -289,7 +289,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relativ
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_ret_t ret = rcl_service_init(&service, &node, ts, "bar", &service_options); rcl_ret_t ret = rcl_service_init(&service, &node, ts, "bar", &service_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("/foo/remap/global", rcl_service_get_service_name(&service)); EXPECT_STREQ("/foo/remap/global", rcl_service_get_service_name(&service));
EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node)); EXPECT_EQ(RCL_RET_OK, rcl_service_fini(&service, &node));
} }

View file

@ -42,22 +42,22 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_service_node"; const char * name = "test_service_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
void TearDown() void TearDown()
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -70,23 +70,23 @@ wait_for_service_to_be_ready(
{ {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 1, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 0, 0, 1, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_wait_set_fini(&wait_set); rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
size_t iteration = 0; size_t iteration = 0;
do { do {
++iteration; ++iteration;
ret = rcl_wait_set_clear(&wait_set); ret = rcl_wait_set_clear(&wait_set);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_service(&wait_set, service); ret = rcl_wait_set_add_service(&wait_set, service);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms));
if (ret == RCL_RET_TIMEOUT) { if (ret == RCL_RET_TIMEOUT) {
continue; continue;
} }
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
for (size_t i = 0; i < wait_set.size_of_services; ++i) { for (size_t i = 0; i < wait_set.size_of_services; ++i) {
if (wait_set.services[i] && wait_set.services[i] == service) { if (wait_set.services[i] && wait_set.services[i] == service) {
success = true; success = true;
@ -109,38 +109,38 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options); ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// Check if null service is valid // Check if null service is valid
EXPECT_FALSE(rcl_service_is_valid(nullptr, nullptr)); EXPECT_FALSE(rcl_service_is_valid(nullptr));
rcl_reset_error(); rcl_reset_error();
// Check if zero initialized client is valid // Check if zero initialized client is valid
service = rcl_get_zero_initialized_service(); service = rcl_get_zero_initialized_service();
EXPECT_FALSE(rcl_service_is_valid(&service, nullptr)); EXPECT_FALSE(rcl_service_is_valid(&service));
rcl_reset_error(); rcl_reset_error();
// Check that a valid service is valid // Check that a valid service is valid
service = rcl_get_zero_initialized_service(); service = rcl_get_zero_initialized_service();
ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options); ret = rcl_service_init(&service, this->node_ptr, ts, topic, &service_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_TRUE(rcl_service_is_valid(&service, nullptr)); EXPECT_TRUE(rcl_service_is_valid(&service));
rcl_reset_error(); rcl_reset_error();
// Check that the service name matches what we assigned. // Check that the service name matches what we assigned.
EXPECT_EQ(strcmp(rcl_service_get_service_name(&service), expected_topic), 0); EXPECT_EQ(strcmp(rcl_service_get_service_name(&service), expected_topic), 0);
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
rcl_client_t client = rcl_get_zero_initialized_client(); rcl_client_t client = rcl_get_zero_initialized_client();
rcl_client_options_t client_options = rcl_client_get_default_options(); rcl_client_options_t client_options = rcl_client_get_default_options();
ret = rcl_client_init(&client, this->node_ptr, ts, topic, &client_options); ret = rcl_client_init(&client, this->node_ptr, ts, topic, &client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
// TODO(wjwwood): add logic to wait for the connection to be established // TODO(wjwwood): add logic to wait for the connection to be established
@ -157,7 +157,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
ret = rcl_send_request(&client, &client_request, &sequence_number); ret = rcl_send_request(&client, &client_request, &sequence_number);
EXPECT_EQ(sequence_number, 1); EXPECT_EQ(sequence_number, 1);
test_msgs__srv__Primitives_Request__fini(&client_request); test_msgs__srv__Primitives_Request__fini(&client_request);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
bool success; bool success;
wait_for_service_to_be_ready(&service, 10, 100, success); wait_for_service_to_be_ready(&service, 10, 100, success);
@ -178,14 +178,14 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
test_msgs__srv__Primitives_Request__init(&service_request); test_msgs__srv__Primitives_Request__init(&service_request);
rmw_request_id_t header; rmw_request_id_t header;
ret = rcl_take_request(&service, &header, &service_request); ret = rcl_take_request(&service, &header, &service_request);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(1, service_request.uint8_value); EXPECT_EQ(1, service_request.uint8_value);
EXPECT_EQ(2UL, service_request.uint32_value); EXPECT_EQ(2UL, service_request.uint32_value);
// Simulate a response callback by summing the request and send the response.. // Simulate a response callback by summing the request and send the response..
service_response.uint64_value = service_request.uint8_value + service_request.uint32_value; service_response.uint64_value = service_request.uint8_value + service_request.uint32_value;
ret = rcl_send_response(&service, &header, &service_response); ret = rcl_send_response(&service, &header, &service_response);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
wait_for_service_to_be_ready(&service, 10, 100, success); wait_for_service_to_be_ready(&service, 10, 100, success);
@ -195,7 +195,7 @@ TEST_F(CLASSNAME(TestServiceFixture, RMW_IMPLEMENTATION), test_service_nominal)
rmw_request_id_t header; rmw_request_id_t header;
ret = rcl_take_response(&client, &header, &client_response); ret = rcl_take_response(&client, &header, &client_response);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(client_response.uint64_value, 3ULL); EXPECT_EQ(client_response.uint64_value, 3ULL);
EXPECT_EQ(header.sequence_number, 1); EXPECT_EQ(header.sequence_number, 1);
} }

View file

@ -42,22 +42,22 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_subscription_node"; const char * name = "test_subscription_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
void TearDown() void TearDown()
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -70,23 +70,23 @@ wait_for_subscription_to_be_ready(
{ {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 0, 0, 0, 0, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 0, 0, 0, 0, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_wait_set_fini(&wait_set); rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
size_t iteration = 0; size_t iteration = 0;
do { do {
++iteration; ++iteration;
ret = rcl_wait_set_clear(&wait_set); ret = rcl_wait_set_clear(&wait_set);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_subscription(&wait_set, subscription); ret = rcl_wait_set_add_subscription(&wait_set, subscription);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(period_ms));
if (ret == RCL_RET_TIMEOUT) { if (ret == RCL_RET_TIMEOUT) {
continue; continue;
} }
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
for (size_t i = 0; i < wait_set.size_of_subscriptions; ++i) { for (size_t i = 0; i < wait_set.size_of_subscriptions; ++i) {
if (wait_set.subscriptions[i] && wait_set.subscriptions[i] == subscription) { if (wait_set.subscriptions[i] && wait_set.subscriptions[i] == subscription) {
success = true; success = true;
@ -108,35 +108,35 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
const char * expected_topic = "/chatter"; const char * expected_topic = "/chatter";
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
EXPECT_EQ(strcmp(rcl_subscription_get_topic_name(&subscription), expected_topic), 0); EXPECT_EQ(strcmp(rcl_subscription_get_topic_name(&subscription), expected_topic), 0);
// Test is_valid for subscription with nullptr // Test is_valid for subscription with nullptr
EXPECT_FALSE(rcl_subscription_is_valid(nullptr, nullptr)); EXPECT_FALSE(rcl_subscription_is_valid(nullptr));
rcl_reset_error(); rcl_reset_error();
// Test is_valid for zero initialized subscription // Test is_valid for zero initialized subscription
subscription = rcl_get_zero_initialized_subscription(); subscription = rcl_get_zero_initialized_subscription();
EXPECT_FALSE(rcl_subscription_is_valid(&subscription, nullptr)); EXPECT_FALSE(rcl_subscription_is_valid(&subscription));
rcl_reset_error(); rcl_reset_error();
// Check that valid subscriber is valid // Check that valid subscriber is valid
subscription = rcl_get_zero_initialized_subscription(); subscription = rcl_get_zero_initialized_subscription();
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_TRUE(rcl_subscription_is_valid(&subscription, nullptr)); EXPECT_TRUE(rcl_subscription_is_valid(&subscription));
rcl_reset_error(); rcl_reset_error();
// TODO(wjwwood): add logic to wait for the connection to be established // TODO(wjwwood): add logic to wait for the connection to be established
@ -149,7 +149,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
msg.int64_value = 42; msg.int64_value = 42;
ret = rcl_publish(&publisher, &msg); ret = rcl_publish(&publisher, &msg);
test_msgs__msg__Primitives__fini(&msg); test_msgs__msg__Primitives__fini(&msg);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
bool success; bool success;
wait_for_subscription_to_be_ready(&subscription, 10, 100, success); wait_for_subscription_to_be_ready(&subscription, 10, 100, success);
@ -161,7 +161,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
test_msgs__msg__Primitives__fini(&msg); test_msgs__msg__Primitives__fini(&msg);
}); });
ret = rcl_take(&subscription, &msg, nullptr); ret = rcl_take(&subscription, &msg, nullptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ASSERT_EQ(42, msg.int64_value); ASSERT_EQ(42, msg.int64_value);
} }
} }
@ -176,18 +176,18 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
const char * topic = "rcl_test_subscription_nominal_string_chatter"; const char * topic = "rcl_test_subscription_nominal_string_chatter";
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
// TODO(wjwwood): add logic to wait for the connection to be established // TODO(wjwwood): add logic to wait for the connection to be established
// probably using the count_subscriptions busy wait mechanism // probably using the count_subscriptions busy wait mechanism
@ -200,7 +200,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string)); ASSERT_TRUE(rosidl_generator_c__String__assign(&msg.string_value, test_string));
ret = rcl_publish(&publisher, &msg); ret = rcl_publish(&publisher, &msg);
test_msgs__msg__Primitives__fini(&msg); test_msgs__msg__Primitives__fini(&msg);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
bool success; bool success;
wait_for_subscription_to_be_ready(&subscription, 10, 100, success); wait_for_subscription_to_be_ready(&subscription, 10, 100, success);
@ -212,7 +212,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
test_msgs__msg__Primitives__fini(&msg); test_msgs__msg__Primitives__fini(&msg);
}); });
ret = rcl_take(&subscription, &msg, nullptr); ret = rcl_take(&subscription, &msg, nullptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ASSERT_EQ(std::string(test_string), std::string(msg.string_value.data, msg.string_value.size)); ASSERT_EQ(std::string(test_string), std::string(msg.string_value.data, msg.string_value.size));
} }
} }

View file

@ -60,40 +60,40 @@ TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_ros_time_set_ove
rcl_clock_t ros_clock; rcl_clock_t ros_clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_ret_t retval = rcl_ros_clock_init(&ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(&ros_clock, &allocator);
ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&ros_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&ros_clock)) << rcl_get_error_string().str;
}); });
rcl_ret_t ret; rcl_ret_t ret;
// Check for invalid argument error condition (allowed to alloc). // Check for invalid argument error condition (allowed to alloc).
ret = rcl_set_ros_time_override(nullptr, 0); ret = rcl_set_ros_time_override(nullptr, 0);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
bool result; bool result;
ret = rcl_is_enabled_ros_time_override(nullptr, &result); ret = rcl_is_enabled_ros_time_override(nullptr, &result);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_is_enabled_ros_time_override(&ros_clock, nullptr); ret = rcl_is_enabled_ros_time_override(&ros_clock, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
ret = rcl_is_enabled_ros_time_override(nullptr, nullptr); ret = rcl_is_enabled_ros_time_override(nullptr, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
rcl_time_point_value_t query_now; rcl_time_point_value_t query_now;
bool is_enabled; bool is_enabled;
ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled); ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(is_enabled, false); EXPECT_EQ(is_enabled, false);
EXPECT_NO_MEMORY_OPERATIONS({ EXPECT_NO_MEMORY_OPERATIONS({
// Check for normal operation (not allowed to alloc). // Check for normal operation (not allowed to alloc).
ret = rcl_clock_get_now(&ros_clock, &query_now); ret = rcl_clock_get_now(&ros_clock, &query_now);
}); });
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_NE(query_now, 0u); EXPECT_NE(query_now, 0u);
// Compare to std::chrono::system_clock time (within a second). // Compare to std::chrono::system_clock time (within a second).
ret = rcl_clock_get_now(&ros_clock, &query_now); ret = rcl_clock_get_now(&ros_clock, &query_now);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
{ {
std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now(); std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now();
auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch()); auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch());
@ -106,18 +106,18 @@ TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_ros_time_set_ove
rcl_time_point_value_t set_point = 1000000000ull; rcl_time_point_value_t set_point = 1000000000ull;
// Check initialized state // Check initialized state
ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled); ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(is_enabled, false); EXPECT_EQ(is_enabled, false);
// set the time point // set the time point
ret = rcl_set_ros_time_override(&ros_clock, set_point); ret = rcl_set_ros_time_override(&ros_clock, set_point);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
// check still disabled // check still disabled
ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled); ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(is_enabled, false); EXPECT_EQ(is_enabled, false);
// get real // get real
ret = rcl_clock_get_now(&ros_clock, &query_now); ret = rcl_clock_get_now(&ros_clock, &query_now);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
{ {
std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now(); std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now();
auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch()); auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch());
@ -128,25 +128,25 @@ TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_ros_time_set_ove
} }
// enable // enable
ret = rcl_enable_ros_time_override(&ros_clock); ret = rcl_enable_ros_time_override(&ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
// check enabled // check enabled
ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled); ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(is_enabled, true); EXPECT_EQ(is_enabled, true);
// get sim // get sim
ret = rcl_clock_get_now(&ros_clock, &query_now); ret = rcl_clock_get_now(&ros_clock, &query_now);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(query_now, set_point); EXPECT_EQ(query_now, set_point);
// disable // disable
ret = rcl_disable_ros_time_override(&ros_clock); ret = rcl_disable_ros_time_override(&ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
// check disabled // check disabled
ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled); ret = rcl_is_enabled_ros_time_override(&ros_clock, &is_enabled);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(is_enabled, false); EXPECT_EQ(is_enabled, false);
// get real // get real
ret = rcl_clock_get_now(&ros_clock, &query_now); ret = rcl_clock_get_now(&ros_clock, &query_now);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
{ {
std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now(); std::chrono::system_clock::time_point now_sc = std::chrono::system_clock::now();
auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch()); auto now_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(now_sc.time_since_epoch());
@ -162,39 +162,39 @@ TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_rcl_init_for_clock_a
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
// Check for invalid argument error condition (allowed to alloc). // Check for invalid argument error condition (allowed to alloc).
ret = rcl_ros_clock_init(nullptr, &allocator); ret = rcl_ros_clock_init(nullptr, &allocator);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Check for invalid argument error condition (allowed to alloc). // Check for invalid argument error condition (allowed to alloc).
rcl_clock_t uninitialized_clock; rcl_clock_t uninitialized_clock;
ret = rcl_ros_clock_init(&uninitialized_clock, nullptr); ret = rcl_ros_clock_init(&uninitialized_clock, nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT) << rcl_get_error_string().str;
rcl_reset_error(); rcl_reset_error();
// Check for normal operation (not allowed to alloc). // Check for normal operation (not allowed to alloc).
rcl_clock_t source; rcl_clock_t source;
ret = rcl_ros_clock_init(&source, &allocator); ret = rcl_ros_clock_init(&source, &allocator);
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&source)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&source)) << rcl_get_error_string().str;
}); });
rcl_clock_t ros_clock; rcl_clock_t ros_clock;
rcl_ret_t retval = rcl_ros_clock_init(&ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(&ros_clock, &allocator);
ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&ros_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&ros_clock)) << rcl_get_error_string().str;
}); });
} }
TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_ros_clock_initially_zero) { TEST_F(CLASSNAME(TestTimeFixture, RMW_IMPLEMENTATION), test_ros_clock_initially_zero) {
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_clock_t ros_clock; rcl_clock_t ros_clock;
ASSERT_EQ(RCL_RET_OK, rcl_ros_clock_init(&ros_clock, &allocator)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_ros_clock_init(&ros_clock, &allocator)) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&ros_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&ros_clock)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&ros_clock)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&ros_clock)) << rcl_get_error_string().str;
rcl_time_point_value_t query_now = 5; rcl_time_point_value_t query_now = 5;
ASSERT_EQ(RCL_RET_OK, rcl_clock_get_now(&ros_clock, &query_now)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_clock_get_now(&ros_clock, &query_now)) << rcl_get_error_string().str;
EXPECT_EQ(0, query_now); EXPECT_EQ(0, query_now);
} }
@ -206,9 +206,9 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), clock_validation) {
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_ros_clock_init(&uninitialized, &allocator); ret = rcl_ros_clock_init(&uninitialized, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&uninitialized)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&uninitialized)) << rcl_get_error_string().str;
}); });
} }
@ -216,9 +216,9 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), default_clock_instanciation) {
rcl_clock_t ros_clock; rcl_clock_t ros_clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_ret_t retval = rcl_ros_clock_init(&ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(&ros_clock, &allocator);
ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&ros_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(&ros_clock)) << rcl_get_error_string().str;
}); });
ASSERT_TRUE(rcl_clock_valid(&ros_clock)); ASSERT_TRUE(rcl_clock_valid(&ros_clock));
@ -229,9 +229,9 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), default_clock_instanciation) {
}); });
retval = rcl_steady_clock_init(steady_clock, &allocator); retval = rcl_steady_clock_init(steady_clock, &allocator);
EXPECT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_steady_clock_fini(steady_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_steady_clock_fini(steady_clock)) << rcl_get_error_string().str;
}); });
ASSERT_TRUE(rcl_clock_valid(steady_clock)); ASSERT_TRUE(rcl_clock_valid(steady_clock));
@ -241,9 +241,9 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), default_clock_instanciation) {
allocator.deallocate(system_clock, allocator.state); allocator.deallocate(system_clock, allocator.state);
}); });
retval = rcl_system_clock_init(system_clock, &allocator); retval = rcl_system_clock_init(system_clock, &allocator);
EXPECT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_system_clock_fini(system_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_system_clock_fini(system_clock)) << rcl_get_error_string().str;
}); });
ASSERT_TRUE(rcl_clock_valid(system_clock)); ASSERT_TRUE(rcl_clock_valid(system_clock));
} }
@ -254,36 +254,36 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), specific_clock_instantiation) {
rcl_clock_t uninitialized_clock; rcl_clock_t uninitialized_clock;
rcl_ret_t ret = rcl_clock_init( rcl_ret_t ret = rcl_clock_init(
RCL_CLOCK_UNINITIALIZED, &uninitialized_clock, &allocator); RCL_CLOCK_UNINITIALIZED, &uninitialized_clock, &allocator);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(uninitialized_clock.type, RCL_CLOCK_UNINITIALIZED) << EXPECT_EQ(uninitialized_clock.type, RCL_CLOCK_UNINITIALIZED) <<
"Expected time source of type RCL_CLOCK_UNINITIALIZED"; "Expected time source of type RCL_CLOCK_UNINITIALIZED";
} }
{ {
rcl_clock_t ros_clock; rcl_clock_t ros_clock;
rcl_ret_t ret = rcl_clock_init(RCL_ROS_TIME, &ros_clock, &allocator); rcl_ret_t ret = rcl_clock_init(RCL_ROS_TIME, &ros_clock, &allocator);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(ros_clock.type, RCL_ROS_TIME) << EXPECT_EQ(ros_clock.type, RCL_ROS_TIME) <<
"Expected time source of type RCL_ROS_TIME"; "Expected time source of type RCL_ROS_TIME";
ret = rcl_clock_fini(&ros_clock); ret = rcl_clock_fini(&ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
} }
{ {
rcl_clock_t system_clock; rcl_clock_t system_clock;
rcl_ret_t ret = rcl_clock_init(RCL_SYSTEM_TIME, &system_clock, &allocator); rcl_ret_t ret = rcl_clock_init(RCL_SYSTEM_TIME, &system_clock, &allocator);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(system_clock.type, RCL_SYSTEM_TIME) << EXPECT_EQ(system_clock.type, RCL_SYSTEM_TIME) <<
"Expected time source of type RCL_SYSTEM_TIME"; "Expected time source of type RCL_SYSTEM_TIME";
ret = rcl_clock_fini(&system_clock); ret = rcl_clock_fini(&system_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
} }
{ {
rcl_clock_t steady_clock; rcl_clock_t steady_clock;
rcl_ret_t ret = rcl_clock_init(RCL_STEADY_TIME, &steady_clock, &allocator); rcl_ret_t ret = rcl_clock_init(RCL_STEADY_TIME, &steady_clock, &allocator);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(steady_clock.type, RCL_STEADY_TIME) << EXPECT_EQ(steady_clock.type, RCL_STEADY_TIME) <<
"Expected time source of type RCL_STEADY_TIME"; "Expected time source of type RCL_STEADY_TIME";
ret = rcl_clock_fini(&steady_clock); ret = rcl_clock_fini(&steady_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
} }
} }
@ -295,9 +295,9 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_difference) {
allocator.deallocate(ros_clock, allocator.state); allocator.deallocate(ros_clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator);
ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(ros_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(ros_clock)) << rcl_get_error_string().str;
}); });
EXPECT_TRUE(ros_clock != nullptr); EXPECT_TRUE(ros_clock != nullptr);
EXPECT_TRUE(ros_clock->data != nullptr); EXPECT_TRUE(ros_clock->data != nullptr);
@ -313,12 +313,12 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_difference) {
rcl_duration_t d; rcl_duration_t d;
ret = rcl_difference_times(&a, &b, &d); ret = rcl_difference_times(&a, &b, &d);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(d.nanoseconds, 1000); EXPECT_EQ(d.nanoseconds, 1000);
ret = rcl_difference_times(&b, &a, &d); ret = rcl_difference_times(&b, &a, &d);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(d.nanoseconds, -1000); EXPECT_EQ(d.nanoseconds, -1000);
} }
@ -330,9 +330,9 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_difference_signed) {
allocator.deallocate(ros_clock, allocator.state); allocator.deallocate(ros_clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator);
ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(ros_clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_ros_clock_fini(ros_clock)) << rcl_get_error_string().str;
}); });
rcl_time_point_t a, b; rcl_time_point_t a, b;
@ -345,7 +345,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_difference_signed) {
rcl_duration_t d; rcl_duration_t d;
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_difference_times(&a, &b, &d); ret = rcl_difference_times(&a, &b, &d);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(d.nanoseconds, RCL_S_TO_NS(10LL)); EXPECT_EQ(d.nanoseconds, RCL_S_TO_NS(10LL));
} }
@ -353,7 +353,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_difference_signed) {
rcl_duration_t d; rcl_duration_t d;
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_difference_times(&b, &a, &d); ret = rcl_difference_times(&b, &a, &d);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(d.nanoseconds, RCL_S_TO_NS(-10LL)); EXPECT_EQ(d.nanoseconds, RCL_S_TO_NS(-10LL));
} }
@ -365,7 +365,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_difference_signed) {
rcl_duration_t d; rcl_duration_t d;
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_difference_times(&a, &b, &d); ret = rcl_difference_times(&a, &b, &d);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(d.nanoseconds, 2147483647LL); EXPECT_EQ(d.nanoseconds, 2147483647LL);
} }
@ -373,7 +373,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_difference_signed) {
rcl_duration_t d; rcl_duration_t d;
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_difference_times(&b, &a, &d); ret = rcl_difference_times(&b, &a, &d);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
// The erroneous value was -2147483648 (https://github.com/ros2/rcl/issues/204) // The erroneous value was -2147483648 (https://github.com/ros2/rcl/issues/204)
EXPECT_EQ(d.nanoseconds, -2147483647LL); EXPECT_EQ(d.nanoseconds, -2147483647LL);
} }
@ -411,7 +411,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_clock_change_callbacks) {
allocator.deallocate(ros_clock, allocator.state); allocator.deallocate(ros_clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator);
ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(ros_clock)); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(ros_clock));
}); });
@ -426,18 +426,18 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_clock_change_callbacks) {
threshold.min_backward.nanoseconds = 0; threshold.min_backward.nanoseconds = 0;
ASSERT_EQ(RCL_RET_OK, ASSERT_EQ(RCL_RET_OK,
rcl_clock_add_jump_callback(ros_clock, threshold, clock_callback, &time_jump)) << rcl_clock_add_jump_callback(ros_clock, threshold, clock_callback, &time_jump)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
reset_callback_triggers(); reset_callback_triggers();
// Query time, no changes expected. // Query time, no changes expected.
ret = rcl_clock_get_now(ros_clock, &query_now); ret = rcl_clock_get_now(ros_clock, &query_now);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
// Clock change callback called when ROS time is enabled // Clock change callback called when ROS time is enabled
ret = rcl_enable_ros_time_override(ros_clock); ret = rcl_enable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_TRUE(pre_callback_called); EXPECT_TRUE(pre_callback_called);
EXPECT_TRUE(post_callback_called); EXPECT_TRUE(post_callback_called);
EXPECT_EQ(RCL_ROS_TIME_ACTIVATED, time_jump.clock_change); EXPECT_EQ(RCL_ROS_TIME_ACTIVATED, time_jump.clock_change);
@ -445,14 +445,14 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_clock_change_callbacks) {
// Clock change callback not called because ROS time is already enabled. // Clock change callback not called because ROS time is already enabled.
ret = rcl_enable_ros_time_override(ros_clock); ret = rcl_enable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
reset_callback_triggers(); reset_callback_triggers();
// Clock change callback called when ROS time is disabled // Clock change callback called when ROS time is disabled
ret = rcl_disable_ros_time_override(ros_clock); ret = rcl_disable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_TRUE(pre_callback_called); EXPECT_TRUE(pre_callback_called);
EXPECT_TRUE(post_callback_called); EXPECT_TRUE(post_callback_called);
EXPECT_EQ(RCL_ROS_TIME_DEACTIVATED, time_jump.clock_change); EXPECT_EQ(RCL_ROS_TIME_DEACTIVATED, time_jump.clock_change);
@ -460,7 +460,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_clock_change_callbacks) {
// Clock change callback not called because ROS time is already disabled. // Clock change callback not called because ROS time is already disabled.
ret = rcl_disable_ros_time_override(ros_clock); ret = rcl_disable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
reset_callback_triggers(); reset_callback_triggers();
@ -474,7 +474,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_forward_jump_callbacks) {
allocator.deallocate(ros_clock, allocator.state); allocator.deallocate(ros_clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator);
ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(ros_clock)); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(ros_clock));
}); });
@ -490,24 +490,24 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_forward_jump_callbacks) {
threshold.min_backward.nanoseconds = 0; threshold.min_backward.nanoseconds = 0;
ASSERT_EQ(RCL_RET_OK, ASSERT_EQ(RCL_RET_OK,
rcl_clock_add_jump_callback(ros_clock, threshold, clock_callback, &time_jump)) << rcl_clock_add_jump_callback(ros_clock, threshold, clock_callback, &time_jump)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
reset_callback_triggers(); reset_callback_triggers();
// Set the time before it's enabled. Should be no callbacks // Set the time before it's enabled. Should be no callbacks
ret = rcl_set_ros_time_override(ros_clock, set_point1); ret = rcl_set_ros_time_override(ros_clock, set_point1);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
// enable no callbacks // enable no callbacks
ret = rcl_enable_ros_time_override(ros_clock); ret = rcl_enable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
// Set the time now that it's enabled, now get callbacks // Set the time now that it's enabled, now get callbacks
ret = rcl_set_ros_time_override(ros_clock, set_point2); ret = rcl_set_ros_time_override(ros_clock, set_point2);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_TRUE(pre_callback_called); EXPECT_TRUE(pre_callback_called);
EXPECT_TRUE(post_callback_called); EXPECT_TRUE(post_callback_called);
EXPECT_EQ(set_point2 - set_point1, time_jump.delta.nanoseconds); EXPECT_EQ(set_point2 - set_point1, time_jump.delta.nanoseconds);
@ -516,13 +516,13 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_forward_jump_callbacks) {
// Setting same value as previous time, not a jump // Setting same value as previous time, not a jump
ret = rcl_set_ros_time_override(ros_clock, set_point2); ret = rcl_set_ros_time_override(ros_clock, set_point2);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
// disable no callbacks // disable no callbacks
ret = rcl_disable_ros_time_override(ros_clock); ret = rcl_disable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
} }
@ -535,7 +535,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_backward_jump_callbacks)
allocator.deallocate(ros_clock, allocator.state); allocator.deallocate(ros_clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(ros_clock, &allocator);
ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string_safe(); ASSERT_EQ(retval, RCL_RET_OK) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(ros_clock)); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(ros_clock));
}); });
@ -550,24 +550,24 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_backward_jump_callbacks)
threshold.min_backward.nanoseconds = -1; threshold.min_backward.nanoseconds = -1;
ASSERT_EQ(RCL_RET_OK, ASSERT_EQ(RCL_RET_OK,
rcl_clock_add_jump_callback(ros_clock, threshold, clock_callback, &time_jump)) << rcl_clock_add_jump_callback(ros_clock, threshold, clock_callback, &time_jump)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
reset_callback_triggers(); reset_callback_triggers();
// Set the time before it's enabled. Should be no callbacks // Set the time before it's enabled. Should be no callbacks
ret = rcl_set_ros_time_override(ros_clock, set_point2); ret = rcl_set_ros_time_override(ros_clock, set_point2);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
// enable no callbacks // enable no callbacks
ret = rcl_enable_ros_time_override(ros_clock); ret = rcl_enable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
// Set the time now that it's enabled, now get callbacks // Set the time now that it's enabled, now get callbacks
ret = rcl_set_ros_time_override(ros_clock, set_point1); ret = rcl_set_ros_time_override(ros_clock, set_point1);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_TRUE(pre_callback_called); EXPECT_TRUE(pre_callback_called);
EXPECT_TRUE(post_callback_called); EXPECT_TRUE(post_callback_called);
EXPECT_EQ(set_point1 - set_point2, time_jump.delta.nanoseconds); EXPECT_EQ(set_point1 - set_point2, time_jump.delta.nanoseconds);
@ -576,13 +576,13 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_time_backward_jump_callbacks)
// Setting same value as previous time, not a jump // Setting same value as previous time, not a jump
ret = rcl_set_ros_time_override(ros_clock, set_point1); ret = rcl_set_ros_time_override(ros_clock, set_point1);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
// disable no callbacks // disable no callbacks
ret = rcl_disable_ros_time_override(ros_clock); ret = rcl_disable_ros_time_override(ros_clock);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string_safe(); EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_FALSE(pre_callback_called); EXPECT_FALSE(pre_callback_called);
EXPECT_FALSE(post_callback_called); EXPECT_FALSE(post_callback_called);
} }
@ -595,7 +595,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_clock_add_jump_callback) {
allocator.deallocate(clock, allocator.state); allocator.deallocate(clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(clock, &allocator);
ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(clock)); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(clock));
}); });
@ -611,12 +611,12 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_clock_add_jump_callback) {
rcl_reset_error(); rcl_reset_error();
EXPECT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, NULL)) << EXPECT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, NULL)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
EXPECT_EQ(RCL_RET_ERROR, rcl_clock_add_jump_callback(clock, threshold, cb, NULL)); EXPECT_EQ(RCL_RET_ERROR, rcl_clock_add_jump_callback(clock, threshold, cb, NULL));
rcl_reset_error(); rcl_reset_error();
EXPECT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data)) << EXPECT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
EXPECT_EQ(RCL_RET_ERROR, rcl_clock_add_jump_callback(clock, threshold, cb, user_data)); EXPECT_EQ(RCL_RET_ERROR, rcl_clock_add_jump_callback(clock, threshold, cb, user_data));
rcl_reset_error(); rcl_reset_error();
@ -631,7 +631,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_clock_remove_jump_callback) {
allocator.deallocate(clock, allocator.state); allocator.deallocate(clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(clock, &allocator);
ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(clock)); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(clock));
}); });
@ -652,13 +652,13 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), rcl_clock_remove_jump_callback) {
rcl_reset_error(); rcl_reset_error();
ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data1)) << ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data1)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data2)) << ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data2)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data3)) << ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data3)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data4)) << ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data4)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
EXPECT_EQ(4u, clock->num_jump_callbacks); EXPECT_EQ(4u, clock->num_jump_callbacks);
EXPECT_EQ(RCL_RET_OK, rcl_clock_remove_jump_callback(clock, cb, user_data3)); EXPECT_EQ(RCL_RET_OK, rcl_clock_remove_jump_callback(clock, cb, user_data3));
@ -679,7 +679,7 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), add_remove_add_jump_callback) {
allocator.deallocate(clock, allocator.state); allocator.deallocate(clock, allocator.state);
}); });
rcl_ret_t retval = rcl_ros_clock_init(clock, &allocator); rcl_ret_t retval = rcl_ros_clock_init(clock, &allocator);
ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, retval) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(clock)); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(clock));
}); });
@ -692,11 +692,11 @@ TEST(CLASSNAME(rcl_time, RMW_IMPLEMENTATION), add_remove_add_jump_callback) {
void * user_data = reinterpret_cast<void *>(0xCAFE); void * user_data = reinterpret_cast<void *>(0xCAFE);
ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data)) << ASSERT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
EXPECT_EQ(1u, clock->num_jump_callbacks); EXPECT_EQ(1u, clock->num_jump_callbacks);
EXPECT_EQ(RCL_RET_OK, rcl_clock_remove_jump_callback(clock, cb, user_data)); EXPECT_EQ(RCL_RET_OK, rcl_clock_remove_jump_callback(clock, cb, user_data));
EXPECT_EQ(0u, clock->num_jump_callbacks); EXPECT_EQ(0u, clock->num_jump_callbacks);
EXPECT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data)) << EXPECT_EQ(RCL_RET_OK, rcl_clock_add_jump_callback(clock, threshold, cb, user_data)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
EXPECT_EQ(1u, clock->num_jump_callbacks); EXPECT_EQ(1u, clock->num_jump_callbacks);
} }

View file

@ -31,22 +31,22 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_publisher_node"; const char * name = "test_publisher_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
void TearDown() void TearDown()
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -56,35 +56,35 @@ TEST_F(TestTimerFixture, test_two_timers) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_timer_t timer = rcl_get_zero_initialized_timer(); rcl_timer_t timer = rcl_get_zero_initialized_timer();
rcl_timer_t timer2 = 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, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); 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, RCL_MS_TO_NS(20), nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
ret = rcl_wait_set_init(&wait_set, 0, 0, 2, 0, 0, rcl_get_default_allocator()); ret = rcl_wait_set_init(&wait_set, 0, 0, 2, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &timer); ret = rcl_wait_set_add_timer(&wait_set, &timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &timer2); ret = rcl_wait_set_add_timer(&wait_set, &timer2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_timer_fini(&timer); rcl_ret_t ret = rcl_timer_fini(&timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_timer_fini(&timer2); ret = rcl_timer_fini(&timer2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(10)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(10));
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
uint8_t nonnull_timers = 0; uint8_t nonnull_timers = 0;
for (uint8_t i = 0; i < wait_set.size_of_timers; i++) { for (uint8_t i = 0; i < wait_set.size_of_timers; i++) {
if (wait_set.timers[i] != NULL) { if (wait_set.timers[i] != NULL) {
@ -93,15 +93,15 @@ TEST_F(TestTimerFixture, test_two_timers) {
} }
bool is_ready = false; bool is_ready = false;
ret = rcl_timer_is_ready(&timer, &is_ready); ret = rcl_timer_is_ready(&timer, &is_ready);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_TRUE(is_ready); EXPECT_TRUE(is_ready);
ret = rcl_timer_is_ready(&timer2, &is_ready); ret = rcl_timer_is_ready(&timer2, &is_ready);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_FALSE(is_ready); EXPECT_FALSE(is_ready);
ASSERT_EQ(1, nonnull_timers); ASSERT_EQ(1, nonnull_timers);
ret = rcl_clock_fini(&clock); ret = rcl_clock_fini(&clock);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) { TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) {
@ -110,35 +110,35 @@ TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_timer_t timer = rcl_get_zero_initialized_timer(); rcl_timer_t timer = rcl_get_zero_initialized_timer();
rcl_timer_t timer2 = 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, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); 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, RCL_MS_TO_NS(10), nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
ret = rcl_wait_set_init(&wait_set, 0, 0, 2, 0, 0, rcl_get_default_allocator()); ret = rcl_wait_set_init(&wait_set, 0, 0, 2, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &timer); ret = rcl_wait_set_add_timer(&wait_set, &timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &timer2); ret = rcl_wait_set_add_timer(&wait_set, &timer2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_timer_fini(&timer); rcl_ret_t ret = rcl_timer_fini(&timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_timer_fini(&timer2); ret = rcl_timer_fini(&timer2);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(20)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(20));
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
uint8_t nonnull_timers = 0; uint8_t nonnull_timers = 0;
for (uint8_t i = 0; i < wait_set.size_of_timers; i++) { for (uint8_t i = 0; i < wait_set.size_of_timers; i++) {
if (wait_set.timers[i] != NULL) { if (wait_set.timers[i] != NULL) {
@ -147,15 +147,15 @@ TEST_F(TestTimerFixture, test_two_timers_ready_before_timeout) {
} }
bool is_ready = false; bool is_ready = false;
ret = rcl_timer_is_ready(&timer, &is_ready); ret = rcl_timer_is_ready(&timer, &is_ready);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_TRUE(is_ready); EXPECT_TRUE(is_ready);
ret = rcl_timer_is_ready(&timer2, &is_ready); ret = rcl_timer_is_ready(&timer2, &is_ready);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_FALSE(is_ready); EXPECT_FALSE(is_ready);
ASSERT_EQ(1, nonnull_timers); ASSERT_EQ(1, nonnull_timers);
ret = rcl_clock_fini(&clock); ret = rcl_clock_fini(&clock);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
TEST_F(TestTimerFixture, test_timer_not_ready) { TEST_F(TestTimerFixture, test_timer_not_ready) {
@ -164,28 +164,28 @@ TEST_F(TestTimerFixture, test_timer_not_ready) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_timer_t timer = rcl_get_zero_initialized_timer(); 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, RCL_MS_TO_NS(5), nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator()); ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &timer); ret = rcl_wait_set_add_timer(&wait_set, &timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_timer_fini(&timer); rcl_ret_t ret = rcl_timer_fini(&timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1));
EXPECT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string().str;
uint8_t nonnull_timers = 0; uint8_t nonnull_timers = 0;
for (uint8_t i = 0; i < wait_set.size_of_timers; i++) { for (uint8_t i = 0; i < wait_set.size_of_timers; i++) {
if (wait_set.timers[i] != NULL) { if (wait_set.timers[i] != NULL) {
@ -194,12 +194,12 @@ TEST_F(TestTimerFixture, test_timer_not_ready) {
} }
bool is_ready = false; bool is_ready = false;
ret = rcl_timer_is_ready(&timer, &is_ready); ret = rcl_timer_is_ready(&timer, &is_ready);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_FALSE(is_ready); EXPECT_FALSE(is_ready);
ASSERT_EQ(0, nonnull_timers); ASSERT_EQ(0, nonnull_timers);
ret = rcl_clock_fini(&clock); ret = rcl_clock_fini(&clock);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
TEST_F(TestTimerFixture, test_canceled_timer) { TEST_F(TestTimerFixture, test_canceled_timer) {
@ -208,31 +208,31 @@ TEST_F(TestTimerFixture, test_canceled_timer) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_timer_t timer = rcl_get_zero_initialized_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, 500, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_timer_cancel(&timer); ret = rcl_timer_cancel(&timer);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator()); ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &timer); ret = rcl_wait_set_add_timer(&wait_set, &timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_timer_fini(&timer); rcl_ret_t ret = rcl_timer_fini(&timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1)); ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1));
EXPECT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string().str;
uint8_t nonnull_timers = 0; uint8_t nonnull_timers = 0;
for (uint8_t i = 0; i < wait_set.size_of_timers; i++) { for (uint8_t i = 0; i < wait_set.size_of_timers; i++) {
if (wait_set.timers[i] != NULL) { if (wait_set.timers[i] != NULL) {
@ -241,12 +241,12 @@ TEST_F(TestTimerFixture, test_canceled_timer) {
} }
bool is_ready = false; bool is_ready = false;
ret = rcl_timer_is_ready(&timer, &is_ready); ret = rcl_timer_is_ready(&timer, &is_ready);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_FALSE(is_ready); EXPECT_FALSE(is_ready);
ASSERT_EQ(0, nonnull_timers); ASSERT_EQ(0, nonnull_timers);
ret = rcl_clock_fini(&clock); ret = rcl_clock_fini(&clock);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
TEST_F(TestTimerFixture, test_rostime_time_until_next_call) { TEST_F(TestTimerFixture, test_rostime_time_until_next_call) {
@ -257,33 +257,33 @@ TEST_F(TestTimerFixture, test_rostime_time_until_next_call) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string_safe(); 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(); 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, sec_5, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, 1)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, 1)) << rcl_get_error_string().str;
ret = rcl_timer_get_time_until_next_call(&timer, &time_until); ret = rcl_timer_get_time_until_next_call(&timer, &time_until);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(sec_5 - 1, time_until); EXPECT_EQ(sec_5 - 1, time_until);
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_5)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_5)) << rcl_get_error_string().str;
ret = rcl_timer_get_time_until_next_call(&timer, &time_until); ret = rcl_timer_get_time_until_next_call(&timer, &time_until);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(0, time_until); EXPECT_EQ(0, time_until);
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_5 + 1)) << ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_5 + 1)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
ret = rcl_timer_get_time_until_next_call(&timer, &time_until); ret = rcl_timer_get_time_until_next_call(&timer, &time_until);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(-1, time_until); EXPECT_EQ(-1, time_until);
} }
@ -294,30 +294,30 @@ TEST_F(TestTimerFixture, test_system_time_to_ros_time) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
}); });
rcl_timer_t timer = rcl_get_zero_initialized_timer(); 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, sec_5, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str;
}); });
int64_t time_until_pre = 0; int64_t time_until_pre = 0;
ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until_pre)) << ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until_pre)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
ASSERT_LT(0, time_until_pre); ASSERT_LT(0, time_until_pre);
ASSERT_GT(sec_5, time_until_pre); ASSERT_GT(sec_5, time_until_pre);
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, 1)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, 1)) << rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string().str;
int64_t time_until = 0; int64_t time_until = 0;
ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) << ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
// Because of time credit the time until next call should be less than before // Because of time credit the time until next call should be less than before
EXPECT_GT(time_until_pre, time_until); EXPECT_GT(time_until_pre, time_until);
EXPECT_LT(0, time_until); EXPECT_LT(0, time_until);
@ -331,34 +331,34 @@ TEST_F(TestTimerFixture, test_ros_time_to_system_time) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, 1)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, 1)) << rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string_safe(); 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(); 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, sec_5, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1)) << rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string().str;
int64_t time_until_pre = 0; int64_t time_until_pre = 0;
ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until_pre)) << ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until_pre)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
ASSERT_EQ(sec_5 - (sec_1 - 1), time_until_pre); ASSERT_EQ(sec_5 - (sec_1 - 1), time_until_pre);
ASSERT_EQ(RCL_RET_OK, rcl_disable_ros_time_override(&clock)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_disable_ros_time_override(&clock)) << rcl_get_error_string().str;
int64_t time_until = 0; int64_t time_until = 0;
ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) << ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
// Because of time credit the time until next call should be less than before // Because of time credit the time until next call should be less than before
EXPECT_GT(time_until_pre, time_until); EXPECT_GT(time_until_pre, time_until);
EXPECT_LT(0, time_until); EXPECT_LT(0, time_until);
@ -374,35 +374,35 @@ TEST_F(TestTimerFixture, test_ros_time_backwards_jump) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_ROS_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_2)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_2)) << rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string_safe(); 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(); 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, sec_5, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_3)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_3)) << rcl_get_error_string().str;
{ {
// Moved forward a little bit, timer should be closer to being ready // Moved forward a little bit, timer should be closer to being ready
int64_t time_until = 0; int64_t time_until = 0;
ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) << ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
EXPECT_EQ(sec_5 - (sec_3 - sec_2), time_until); EXPECT_EQ(sec_5 - (sec_3 - sec_2), time_until);
} }
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1)) << rcl_get_error_string().str;
{ {
// Jumped back before timer was created, so last_call_time should be 1 period // Jumped back before timer was created, so last_call_time should be 1 period
int64_t time_until = 0; int64_t time_until = 0;
ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) << ASSERT_EQ(RCL_RET_OK, rcl_timer_get_time_until_next_call(&timer, &time_until)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
EXPECT_EQ(sec_5, time_until); EXPECT_EQ(sec_5, time_until);
} }
} }
@ -416,18 +416,18 @@ TEST_F(TestTimerFixture, test_ros_time_wakes_wait) {
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ASSERT_EQ(RCL_RET_OK, rcl_clock_init(RCL_ROS_TIME, &clock, &allocator)) << ASSERT_EQ(RCL_RET_OK, rcl_clock_init(RCL_ROS_TIME, &clock, &allocator)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_clock_fini(&clock)) << rcl_get_error_string().str;
}); });
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1)) << rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_enable_ros_time_override(&clock)) << rcl_get_error_string_safe(); 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(); 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, sec_1, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, rcl_timer_fini(&timer)) << rcl_get_error_string().str;
}); });
bool timer_was_ready = false; bool timer_was_ready = false;
@ -435,20 +435,20 @@ TEST_F(TestTimerFixture, test_ros_time_wakes_wait) {
std::thread wait_thr([&](void) { std::thread wait_thr([&](void) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator()); ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ASSERT_EQ(RCL_RET_OK, rcl_wait_set_add_timer(&wait_set, &timer)) << ASSERT_EQ(RCL_RET_OK, rcl_wait_set_add_timer(&wait_set, &timer)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
// *INDENT-OFF* (Uncrustify wants strange un-indentation here) // *INDENT-OFF* (Uncrustify wants strange un-indentation here)
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set)) << EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
}); });
// *INDENT-ON* // *INDENT-ON*
ret = rcl_wait(&wait_set, sec_5); ret = rcl_wait(&wait_set, sec_5);
// set some flag indicating wait was exited // set some flag indicating wait was exited
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
if (wait_set.timers[0] != NULL) { if (wait_set.timers[0] != NULL) {
timer_was_ready = true; timer_was_ready = true;
} }
@ -456,12 +456,12 @@ TEST_F(TestTimerFixture, test_ros_time_wakes_wait) {
// Timer not exceeded, should not wake // Timer not exceeded, should not wake
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1_5)) << ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_1_5)) <<
rcl_get_error_string_safe(); rcl_get_error_string().str;
std::this_thread::sleep_for(std::chrono::milliseconds(100)); std::this_thread::sleep_for(std::chrono::milliseconds(100));
EXPECT_FALSE(timer_was_ready); EXPECT_FALSE(timer_was_ready);
// Timer exceeded, should wake // Timer exceeded, should wake
ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_5)) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(&clock, sec_5)) << rcl_get_error_string().str;
auto start = std::chrono::steady_clock::now(); auto start = std::chrono::steady_clock::now();
wait_thr.join(); wait_thr.join();
auto finish = std::chrono::steady_clock::now(); auto finish = std::chrono::steady_clock::now();

View file

@ -29,7 +29,7 @@ TEST(test_validate_topic_name, normal) {
{ {
int validation_result; int validation_result;
ret = rcl_validate_topic_name("topic", &validation_result, nullptr); ret = rcl_validate_topic_name("topic", &validation_result, nullptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_TOPIC_NAME_VALID, validation_result); EXPECT_EQ(RCL_TOPIC_NAME_VALID, validation_result);
EXPECT_EQ(nullptr, rcl_topic_name_validation_result_string(validation_result)); EXPECT_EQ(nullptr, rcl_topic_name_validation_result_string(validation_result));
} }
@ -39,7 +39,7 @@ TEST(test_validate_topic_name, normal) {
int validation_result; int validation_result;
size_t invalid_index = 42; size_t invalid_index = 42;
ret = rcl_validate_topic_name("topic", &validation_result, &invalid_index); ret = rcl_validate_topic_name("topic", &validation_result, &invalid_index);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_TOPIC_NAME_VALID, validation_result); EXPECT_EQ(RCL_TOPIC_NAME_VALID, validation_result);
EXPECT_EQ(42u, invalid_index); // ensure invalid_index is not assigned on success EXPECT_EQ(42u, invalid_index); // ensure invalid_index is not assigned on success
EXPECT_EQ(nullptr, rcl_topic_name_validation_result_string(validation_result)); EXPECT_EQ(nullptr, rcl_topic_name_validation_result_string(validation_result));
@ -50,7 +50,7 @@ TEST(test_validate_topic_name, normal) {
int validation_result; int validation_result;
size_t invalid_index = 42; size_t invalid_index = 42;
ret = rcl_validate_topic_name("", &validation_result, &invalid_index); ret = rcl_validate_topic_name("", &validation_result, &invalid_index);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_TOPIC_NAME_INVALID_IS_EMPTY_STRING, validation_result); EXPECT_EQ(RCL_TOPIC_NAME_INVALID_IS_EMPTY_STRING, validation_result);
EXPECT_EQ(0u, invalid_index); EXPECT_EQ(0u, invalid_index);
EXPECT_NE(nullptr, rcl_topic_name_validation_result_string(validation_result)); EXPECT_NE(nullptr, rcl_topic_name_validation_result_string(validation_result));
@ -112,7 +112,7 @@ TEST(test_validate_topic_name, various_valid_topics) {
int validation_result; int validation_result;
size_t invalid_index = 42; size_t invalid_index = 42;
rcl_ret_t ret = rcl_validate_topic_name(topic.c_str(), &validation_result, &invalid_index); rcl_ret_t ret = rcl_validate_topic_name(topic.c_str(), &validation_result, &invalid_index);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_TOPIC_NAME_VALID, validation_result) << EXPECT_EQ(RCL_TOPIC_NAME_VALID, validation_result) <<
"'" << topic << "' should have passed: " << "'" << topic << "' should have passed: " <<
rcl_topic_name_validation_result_string(validation_result) << "\n" << rcl_topic_name_validation_result_string(validation_result) << "\n" <<
@ -162,7 +162,7 @@ TEST(test_validate_topic_name, various_invalid_topics) {
int validation_result; int validation_result;
size_t invalid_index = 0; size_t invalid_index = 0;
rcl_ret_t ret = rcl_validate_topic_name(topic.c_str(), &validation_result, &invalid_index); rcl_ret_t ret = rcl_validate_topic_name(topic.c_str(), &validation_result, &invalid_index);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(expected_validation_result, validation_result) << EXPECT_EQ(expected_validation_result, validation_result) <<
"'" << topic << "' should have failed with '" << "'" << topic << "' should have failed with '" <<
expected_validation_result << "' but got '" << validation_result << "'.\n" << expected_validation_result << "' but got '" << validation_result << "'.\n" <<

View file

@ -45,14 +45,14 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
void TearDown() void TearDown()
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -60,10 +60,10 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), test_resize_to_zero) {
// Initialize a wait set with a subscription and then resize it to zero. // Initialize a wait set with a subscription and then resize it to zero.
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 1, 1, 1, 1, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 1, 1, 1, 1, 1, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_resize(&wait_set, 0u, 0u, 0u, 0u, 0u); ret = rcl_wait_set_resize(&wait_set, 0u, 0u, 0u, 0u, 0u);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(wait_set.size_of_subscriptions, 0ull); EXPECT_EQ(wait_set.size_of_subscriptions, 0ull);
EXPECT_EQ(wait_set.size_of_guard_conditions, 0ull); EXPECT_EQ(wait_set.size_of_guard_conditions, 0ull);
@ -72,59 +72,59 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), test_resize_to_zero) {
EXPECT_EQ(wait_set.size_of_timers, 0ull); EXPECT_EQ(wait_set.size_of_timers, 0ull);
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
// Test rcl_wait with a positive finite timeout value (1ms) // Test rcl_wait with a positive finite timeout value (1ms)
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), finite_timeout) { TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), finite_timeout) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 0, 1, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int64_t timeout = RCL_MS_TO_NS(10); // nanoseconds int64_t timeout = RCL_MS_TO_NS(10); // nanoseconds
std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now();
ret = rcl_wait(&wait_set, timeout); ret = rcl_wait(&wait_set, timeout);
std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now();
ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string().str;
// Check time // Check time
int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count(); int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count();
EXPECT_LE(diff, timeout + TOLERANCE); EXPECT_LE(diff, timeout + TOLERANCE);
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
// Check that a timer overrides a negative timeout value (blocking forever) // Check that a timer overrides a negative timeout value (blocking forever)
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) { TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// Add a dummy guard condition to avoid an error // Add a dummy guard condition to avoid an error
rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); 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, rcl_guard_condition_get_default_options());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_timer_t timer = rcl_get_zero_initialized_timer(); 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, RCL_MS_TO_NS(10), nullptr, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &timer); ret = rcl_wait_set_add_timer(&wait_set, &timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_timer_fini(&timer); ret = rcl_timer_fini(&timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
int64_t timeout = -1; int64_t timeout = -1;
@ -132,7 +132,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) {
ret = rcl_wait(&wait_set, timeout); ret = rcl_wait(&wait_set, timeout);
std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now();
// We expect a timeout here (timer value reached) // We expect a timeout here (timer value reached)
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// Check time // Check time
int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count(); int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count();
EXPECT_LE(diff, RCL_MS_TO_NS(10) + TOLERANCE); EXPECT_LE(diff, RCL_MS_TO_NS(10) + TOLERANCE);
@ -142,20 +142,20 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), negative_timeout) {
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) { TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// Add a dummy guard condition to avoid an error // Add a dummy guard condition to avoid an error
rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); 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, rcl_guard_condition_get_default_options());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
// Time spent during wait should be negligible. // Time spent during wait should be negligible.
@ -164,7 +164,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) {
ret = rcl_wait(&wait_set, timeout); ret = rcl_wait(&wait_set, timeout);
std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now();
// We expect a timeout here (timer value reached) // We expect a timeout here (timer value reached)
ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string().str;
int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count(); int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count();
EXPECT_LE(diff, TOLERANCE); EXPECT_LE(diff, TOLERANCE);
} }
@ -173,21 +173,21 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout) {
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered_guard_condition) { TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered_guard_condition) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 0, 0, 0, rcl_get_default_allocator()); 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_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); 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, rcl_guard_condition_get_default_options());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_trigger_guard_condition(&guard_cond); ret = rcl_trigger_guard_condition(&guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
// Time spent during wait should be negligible. // Time spent during wait should be negligible.
@ -196,7 +196,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered
ret = rcl_wait(&wait_set, timeout); ret = rcl_wait(&wait_set, timeout);
std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now();
// We don't expect a timeout here (since the guard condition had already been triggered) // We don't expect a timeout here (since the guard condition had already been triggered)
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count(); int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count();
EXPECT_LE(diff, TOLERANCE); EXPECT_LE(diff, TOLERANCE);
} }
@ -205,36 +205,36 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), zero_timeout_triggered
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) { TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 1, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// Add a dummy guard condition to avoid an error // Add a dummy guard condition to avoid an error
rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); 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, rcl_guard_condition_get_default_options());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_clock_t clock; rcl_clock_t clock;
rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_allocator_t allocator = rcl_get_default_allocator();
ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator); ret = rcl_clock_init(RCL_STEADY_TIME, &clock, &allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_timer_t canceled_timer = rcl_get_zero_initialized_timer(); rcl_timer_t canceled_timer = rcl_get_zero_initialized_timer();
ret = rcl_timer_init( ret = rcl_timer_init(
&canceled_timer, &clock, RCL_MS_TO_NS(1), nullptr, rcl_get_default_allocator()); &canceled_timer, &clock, RCL_MS_TO_NS(1), nullptr, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_timer_cancel(&canceled_timer); ret = rcl_timer_cancel(&canceled_timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_timer(&wait_set, &canceled_timer); ret = rcl_wait_set_add_timer(&wait_set, &canceled_timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond); rcl_ret_t ret = rcl_guard_condition_fini(&guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&wait_set); ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_timer_fini(&canceled_timer); ret = rcl_timer_fini(&canceled_timer);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
int64_t timeout = RCL_MS_TO_NS(10); int64_t timeout = RCL_MS_TO_NS(10);
@ -242,24 +242,24 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), canceled_timer) {
ret = rcl_wait(&wait_set, timeout); ret = rcl_wait(&wait_set, timeout);
std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now();
// We expect a timeout here (timer value reached) // We expect a timeout here (timer value reached)
ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string().str;
// Check time // Check time
int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count(); int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count();
EXPECT_LE(diff, RCL_MS_TO_NS(10) + TOLERANCE); EXPECT_LE(diff, RCL_MS_TO_NS(10) + TOLERANCE);
ret = rcl_clock_fini(&clock); ret = rcl_clock_fini(&clock);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
// Test rcl_wait_set_t with excess capacity works. // Test rcl_wait_set_t with excess capacity works.
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), excess_capacity) { TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), excess_capacity) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 42, 42, 42, 42, 42, rcl_get_default_allocator()); rcl_ret_t ret = rcl_wait_set_init(&wait_set, 42, 42, 42, 42, 42, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int64_t timeout = 1; int64_t timeout = 1;
ret = rcl_wait(&wait_set, timeout); ret = rcl_wait(&wait_set, timeout);
ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_TIMEOUT, ret) << rcl_get_error_string().str;
} }
// Check rcl_wait can be called in many threads, each with unique wait sets and resources. // Check rcl_wait can be called in many threads, each with unique wait sets and resources.
@ -292,9 +292,9 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade
wake_try_count++; wake_try_count++;
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_wait_set_clear(&test_set.wait_set); ret = rcl_wait_set_clear(&test_set.wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(&test_set.wait_set, &test_set.guard_condition); ret = rcl_wait_set_add_guard_condition(&test_set.wait_set, &test_set.guard_condition);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait(&test_set.wait_set, wait_period); ret = rcl_wait(&test_set.wait_set, wait_period);
if (ret != RCL_RET_TIMEOUT) { if (ret != RCL_RET_TIMEOUT) {
ASSERT_EQ(ret, RCL_RET_OK); ASSERT_EQ(ret, RCL_RET_OK);
@ -334,22 +334,22 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade
test_set.guard_condition = rcl_get_zero_initialized_guard_condition(); test_set.guard_condition = rcl_get_zero_initialized_guard_condition();
ret = rcl_guard_condition_init( ret = rcl_guard_condition_init(
&test_set.guard_condition, rcl_guard_condition_get_default_options()); &test_set.guard_condition, rcl_guard_condition_get_default_options());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
// setup the wait set // setup the wait set
test_set.wait_set = rcl_get_zero_initialized_wait_set(); test_set.wait_set = rcl_get_zero_initialized_wait_set();
ret = rcl_wait_set_init(&test_set.wait_set, 0, 1, 0, 0, 0, rcl_get_default_allocator()); ret = rcl_wait_set_init(&test_set.wait_set, 0, 1, 0, 0, 0, rcl_get_default_allocator());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(&test_set.wait_set, &test_set.guard_condition); ret = rcl_wait_set_add_guard_condition(&test_set.wait_set, &test_set.guard_condition);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_set.thread_id = 0; test_set.thread_id = 0;
} }
// Setup safe tear-down. // Setup safe tear-down.
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
for (auto & test_set : test_sets) { for (auto & test_set : test_sets) {
rcl_ret_t ret = rcl_guard_condition_fini(&test_set.guard_condition); rcl_ret_t ret = rcl_guard_condition_fini(&test_set.guard_condition);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_fini(&test_set.wait_set); ret = rcl_wait_set_fini(&test_set.wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}); });
// Now kick off all the threads. // Now kick off all the threads.
@ -376,7 +376,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade
loop_count++; loop_count++;
for (auto & test_set : test_sets) { for (auto & test_set : test_sets) {
ret = rcl_trigger_guard_condition(&test_set.guard_condition); ret = rcl_trigger_guard_condition(&test_set.guard_condition);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
std::this_thread::sleep_for(trigger_period); std::this_thread::sleep_for(trigger_period);
} }
@ -395,18 +395,18 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), multi_wait_set_threade
TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) { TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) {
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set(); rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
rcl_ret_t ret = rcl_wait_set_init(&wait_set, 0, 1, 0, 0, 0, rcl_get_default_allocator()); 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_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_guard_condition_t guard_cond = rcl_get_zero_initialized_guard_condition(); 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, rcl_guard_condition_get_default_options());
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond); ret = rcl_wait_set_add_guard_condition(&wait_set, &guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_wait_set_fini(&wait_set); rcl_ret_t ret = rcl_wait_set_fini(&wait_set);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_guard_condition_fini(&guard_cond); ret = rcl_guard_condition_fini(&guard_cond);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
std::promise<rcl_ret_t> p; std::promise<rcl_ret_t> p;
@ -429,7 +429,7 @@ TEST_F(CLASSNAME(WaitSetTestFixture, RMW_IMPLEMENTATION), guard_condition) {
std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point before_sc = std::chrono::steady_clock::now();
ret = rcl_wait(&wait_set, timeout); ret = rcl_wait(&wait_set, timeout);
std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now(); std::chrono::steady_clock::time_point after_sc = std::chrono::steady_clock::now();
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count(); int64_t diff = std::chrono::duration_cast<std::chrono::nanoseconds>(after_sc - before_sc).count();
trigger_thread.join(); trigger_thread.join();
EXPECT_EQ(RCL_RET_OK, f.get()); EXPECT_EQ(RCL_RET_OK, f.get());

View file

@ -38,22 +38,22 @@ public:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "rcl_test_namespace_node"; const char * name = "rcl_test_namespace_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
void TearDown() void TearDown()
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -70,20 +70,20 @@ TEST_F(TestNamespaceFixture, test_client_server) {
rcl_service_t service = rcl_get_zero_initialized_service(); rcl_service_t service = rcl_get_zero_initialized_service();
rcl_service_options_t service_options = rcl_service_get_default_options(); rcl_service_options_t service_options = rcl_service_get_default_options();
ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options); ret = rcl_service_init(&service, this->node_ptr, ts, service_name, &service_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr); rcl_ret_t ret = rcl_service_fini(&service, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
rcl_client_t unmatched_client = rcl_get_zero_initialized_client(); rcl_client_t unmatched_client = rcl_get_zero_initialized_client();
rcl_client_options_t unmatched_client_options = rcl_client_get_default_options(); rcl_client_options_t unmatched_client_options = rcl_client_get_default_options();
ret = rcl_client_init( ret = rcl_client_init(
&unmatched_client, this->node_ptr, ts, unmatched_client_name, &unmatched_client_options); &unmatched_client, this->node_ptr, ts, unmatched_client_name, &unmatched_client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_client_fini(&unmatched_client, this->node_ptr); rcl_ret_t ret = rcl_client_fini(&unmatched_client, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
bool is_available = false; bool is_available = false;
@ -101,10 +101,10 @@ TEST_F(TestNamespaceFixture, test_client_server) {
rcl_client_options_t matched_client_options = rcl_client_get_default_options(); rcl_client_options_t matched_client_options = rcl_client_get_default_options();
ret = rcl_client_init( ret = rcl_client_init(
&matched_client, this->node_ptr, ts, matched_client_name, &matched_client_options); &matched_client, this->node_ptr, ts, matched_client_name, &matched_client_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_ret_t ret = rcl_client_fini(&matched_client, this->node_ptr); rcl_ret_t ret = rcl_client_fini(&matched_client, this->node_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
}); });
is_available = false; is_available = false;

View file

@ -25,7 +25,6 @@ extern "C"
#include "rcl_action/visibility_control.h" #include "rcl_action/visibility_control.h"
#include "rcl/wait.h" #include "rcl/wait.h"
/// Add a rcl_action_client_t to a wait set. /// Add a rcl_action_client_t to a wait set.
/** /**
* This function will add the underlying service clients and subscriber to the wait set. * This function will add the underlying service clients and subscriber to the wait set.

View file

@ -19,7 +19,6 @@ extern "C"
#include "rcl_action/goal_state_machine.h" #include "rcl_action/goal_state_machine.h"
typedef rcl_action_goal_state_t typedef rcl_action_goal_state_t
(* rcl_action_goal_event_handler)(rcl_action_goal_state_t, rcl_action_goal_event_t); (* rcl_action_goal_event_handler)(rcl_action_goal_state_t, rcl_action_goal_event_t);

View file

@ -29,15 +29,15 @@ rcl_action_get_goal_service_name(
char ** goal_service_name) char ** goal_service_name)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(goal_service_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(goal_service_name, RCL_RET_INVALID_ARGUMENT);
if (NULL != *goal_service_name) { if (NULL != *goal_service_name) {
RCL_SET_ERROR_MSG("writing action goal service name may leak memory", allocator); RCL_SET_ERROR_MSG("writing action goal service name may leak memory");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
*goal_service_name = rcutils_format_string(allocator, "%s/_action/send_goal", action_name); *goal_service_name = rcutils_format_string(allocator, "%s/_action/send_goal", action_name);
if (NULL == *goal_service_name) { if (NULL == *goal_service_name) {
RCL_SET_ERROR_MSG("failed to allocate memory for action goal service name", allocator); RCL_SET_ERROR_MSG("failed to allocate memory for action goal service name");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -50,15 +50,15 @@ rcl_action_get_cancel_service_name(
char ** cancel_service_name) char ** cancel_service_name)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(cancel_service_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(cancel_service_name, RCL_RET_INVALID_ARGUMENT);
if (NULL != *cancel_service_name) { if (NULL != *cancel_service_name) {
RCL_SET_ERROR_MSG("writing action cancel service name may leak memory", allocator); RCL_SET_ERROR_MSG("writing action cancel service name may leak memory");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
*cancel_service_name = rcutils_format_string(allocator, "%s/_action/cancel_goal", action_name); *cancel_service_name = rcutils_format_string(allocator, "%s/_action/cancel_goal", action_name);
if (NULL == *cancel_service_name) { if (NULL == *cancel_service_name) {
RCL_SET_ERROR_MSG("failed to allocate memory for action cancel service name", allocator); RCL_SET_ERROR_MSG("failed to allocate memory for action cancel service name");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -71,16 +71,16 @@ rcl_action_get_result_service_name(
char ** result_service_name) char ** result_service_name)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(result_service_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(result_service_name, RCL_RET_INVALID_ARGUMENT);
if (NULL != *result_service_name) { if (NULL != *result_service_name) {
RCL_SET_ERROR_MSG("writing action result service name may leak memory", allocator); RCL_SET_ERROR_MSG("writing action result service name may leak memory");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
*result_service_name = rcutils_format_string(allocator, "%s/_action/get_result", action_name); *result_service_name = rcutils_format_string(allocator, "%s/_action/get_result", action_name);
if (NULL == *result_service_name) { if (NULL == *result_service_name) {
RCL_SET_ERROR_MSG("failed to allocate memory for action result service name", allocator); RCL_SET_ERROR_MSG("failed to allocate memory for action result service name");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -93,15 +93,15 @@ rcl_action_get_feedback_topic_name(
char ** feedback_topic_name) char ** feedback_topic_name)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(feedback_topic_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(feedback_topic_name, RCL_RET_INVALID_ARGUMENT);
if (NULL != *feedback_topic_name) { if (NULL != *feedback_topic_name) {
RCL_SET_ERROR_MSG("writing action feedback topic name may leak memory", allocator); RCL_SET_ERROR_MSG("writing action feedback topic name may leak memory");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
*feedback_topic_name = rcutils_format_string(allocator, "%s/_action/feedback", action_name); *feedback_topic_name = rcutils_format_string(allocator, "%s/_action/feedback", action_name);
if (NULL == *feedback_topic_name) { if (NULL == *feedback_topic_name) {
RCL_SET_ERROR_MSG("failed to allocate memory for action feedback topic name", allocator); RCL_SET_ERROR_MSG("failed to allocate memory for action feedback topic name");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -114,15 +114,15 @@ rcl_action_get_status_topic_name(
char ** status_topic_name) char ** status_topic_name)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(action_name, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(status_topic_name, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(status_topic_name, RCL_RET_INVALID_ARGUMENT);
if (NULL != *status_topic_name) { if (NULL != *status_topic_name) {
RCL_SET_ERROR_MSG("writing action status topic name may leak memory", allocator); RCL_SET_ERROR_MSG("writing action status topic name may leak memory");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
*status_topic_name = rcutils_format_string(allocator, "%s/_action/status", action_name); *status_topic_name = rcutils_format_string(allocator, "%s/_action/status", action_name);
if (NULL == *status_topic_name) { if (NULL == *status_topic_name) {
RCL_SET_ERROR_MSG("failed to allocate memory for action status topic name", allocator); RCL_SET_ERROR_MSG("failed to allocate memory for action status topic name");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
return RCL_RET_OK; return RCL_RET_OK;

View file

@ -20,7 +20,6 @@ extern "C"
#include "rcl/error_handling.h" #include "rcl/error_handling.h"
rcl_action_goal_info_t rcl_action_goal_info_t
rcl_action_get_zero_initialized_goal_info(void) rcl_action_get_zero_initialized_goal_info(void)
{ {
@ -56,10 +55,10 @@ rcl_action_goal_status_array_init(
const rcl_allocator_t allocator) const rcl_allocator_t allocator)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(status_array, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(status_array, RCL_RET_INVALID_ARGUMENT);
// Ensure status array is zero initialized // Ensure status array is zero initialized
if (status_array->status_list.size > 0) { if (status_array->status_list.size > 0) {
RCL_SET_ERROR_MSG("status_array already inititalized", allocator); RCL_SET_ERROR_MSG("status_array already inititalized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Allocate space for status array // Allocate space for status array
@ -78,7 +77,7 @@ rcl_action_goal_status_array_fini(
const rcl_allocator_t allocator) const rcl_allocator_t allocator)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(status_array, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(status_array, RCL_RET_INVALID_ARGUMENT);
if (!status_array->status_list.data) { if (!status_array->status_list.data) {
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
@ -93,10 +92,10 @@ rcl_action_cancel_response_init(
const rcl_allocator_t allocator) const rcl_allocator_t allocator)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT);
// Ensure cancel response is zero initialized // Ensure cancel response is zero initialized
if (cancel_response->goals_canceling.size > 0) { if (cancel_response->goals_canceling.size > 0) {
RCL_SET_ERROR_MSG("cancel_response already inititalized", allocator); RCL_SET_ERROR_MSG("cancel_response already inititalized");
return RCL_RET_ALREADY_INIT; return RCL_RET_ALREADY_INIT;
} }
// Allocate space for cancel response // Allocate space for cancel response
@ -115,7 +114,7 @@ rcl_action_cancel_response_fini(
const rcl_allocator_t allocator) const rcl_allocator_t allocator)
{ {
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT);
if (!cancel_response->goals_canceling.data) { if (!cancel_response->goals_canceling.data) {
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }

View file

@ -15,7 +15,6 @@
#include "rcl_action/types.h" #include "rcl_action/types.h"
TEST(TestActionTypes, test_get_zero_inititalized_goal_info) TEST(TestActionTypes, test_get_zero_inititalized_goal_info)
{ {
rcl_action_goal_info_t goal_info = rcl_action_get_zero_initialized_goal_info(); rcl_action_goal_info_t goal_info = rcl_action_get_zero_initialized_goal_info();

View file

@ -67,21 +67,16 @@ rcl_lifecycle_com_interface_init(
const rosidl_service_type_support_t * ts_srv_get_state, const rosidl_service_type_support_t * ts_srv_get_state,
const rosidl_service_type_support_t * ts_srv_get_available_states, const rosidl_service_type_support_t * ts_srv_get_available_states,
const rosidl_service_type_support_t * ts_srv_get_available_transitions, const rosidl_service_type_support_t * ts_srv_get_available_transitions,
const rosidl_service_type_support_t * ts_srv_get_transition_graph, const rosidl_service_type_support_t * ts_srv_get_transition_graph)
const rcl_allocator_t * allocator)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT, rcl_get_default_allocator()) RCL_CHECK_ARGUMENT_FOR_NULL(com_interface, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(com_interface, RCL_RET_INVALID_ARGUMENT, *allocator) RCL_CHECK_ARGUMENT_FOR_NULL(node_handle, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(node_handle, RCL_RET_INVALID_ARGUMENT, *allocator) RCL_CHECK_ARGUMENT_FOR_NULL(ts_pub_notify, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(ts_pub_notify, RCL_RET_INVALID_ARGUMENT, *allocator) RCL_CHECK_ARGUMENT_FOR_NULL(ts_srv_change_state, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(ts_srv_change_state, RCL_RET_INVALID_ARGUMENT, *allocator) RCL_CHECK_ARGUMENT_FOR_NULL(ts_srv_get_state, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(ts_srv_get_state, RCL_RET_INVALID_ARGUMENT, *allocator) RCL_CHECK_ARGUMENT_FOR_NULL(ts_srv_get_available_states, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL( RCL_CHECK_ARGUMENT_FOR_NULL(ts_srv_get_available_transitions, RCL_RET_INVALID_ARGUMENT);
ts_srv_get_available_states, RCL_RET_INVALID_ARGUMENT, *allocator) RCL_CHECK_ARGUMENT_FOR_NULL(ts_srv_get_transition_graph, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(
ts_srv_get_available_transitions, RCL_RET_INVALID_ARGUMENT, *allocator)
RCL_CHECK_ARGUMENT_FOR_NULL(
ts_srv_get_transition_graph, RCL_RET_INVALID_ARGUMENT, *allocator)
// initialize publisher // initialize publisher
{ {

View file

@ -37,8 +37,7 @@ rcl_lifecycle_com_interface_init(
const rosidl_service_type_support_t * ts_srv_get_state, const rosidl_service_type_support_t * ts_srv_get_state,
const rosidl_service_type_support_t * ts_srv_get_available_states, const rosidl_service_type_support_t * ts_srv_get_available_states,
const rosidl_service_type_support_t * ts_srv_get_available_transitions, const rosidl_service_type_support_t * ts_srv_get_available_transitions,
const rosidl_service_type_support_t * ts_srv_get_transition_graph, const rosidl_service_type_support_t * ts_srv_get_transition_graph);
const rcl_allocator_t * allocator);
rcl_ret_t rcl_ret_t
RCL_WARN_UNUSED RCL_WARN_UNUSED

View file

@ -692,8 +692,7 @@ rcl_lifecycle_init_default_state_machine(
fail: fail:
if (rcl_lifecycle_transition_map_fini(&state_machine->transition_map, allocator) != RCL_RET_OK) { if (rcl_lifecycle_transition_map_fini(&state_machine->transition_map, allocator) != RCL_RET_OK) {
RCL_SET_ERROR_MSG("could not free lifecycle transition map. Leaking memory!\n", RCL_SET_ERROR_MSG("could not free lifecycle transition map. Leaking memory!\n");
rcl_get_default_allocator());
} }
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }

View file

@ -51,19 +51,18 @@ rcl_lifecycle_state_init(
const rcl_allocator_t * allocator) const rcl_allocator_t * allocator)
{ {
if (!allocator) { if (!allocator) {
RCL_SET_ERROR_MSG("can't initialize state, no allocator given\n", RCL_SET_ERROR_MSG("can't initialize state, no allocator given\n");
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (!state) { if (!state) {
RCL_SET_ERROR_MSG("state pointer is null\n", *allocator); RCL_SET_ERROR_MSG("state pointer is null\n");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
state->id = id; state->id = id;
state->label = rcutils_strndup(label, strlen(label), *allocator); state->label = rcutils_strndup(label, strlen(label), *allocator);
if (!state->label) { if (!state->label) {
RCL_SET_ERROR_MSG("failed to duplicate label for rcl_lifecycle_state_t\n", *allocator); RCL_SET_ERROR_MSG("failed to duplicate label for rcl_lifecycle_state_t\n");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -76,8 +75,7 @@ rcl_lifecycle_state_fini(
const rcl_allocator_t * allocator) const rcl_allocator_t * allocator)
{ {
if (!allocator) { if (!allocator) {
RCL_SET_ERROR_MSG("can't free state, no allocator given\n", RCL_SET_ERROR_MSG("can't free state, no allocator given\n");
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
// it is already NULL // it is already NULL
@ -114,13 +112,12 @@ rcl_lifecycle_transition_init(
const rcl_allocator_t * allocator) const rcl_allocator_t * allocator)
{ {
if (!allocator) { if (!allocator) {
RCL_SET_ERROR_MSG("can't initialize transition, no allocator given\n", RCL_SET_ERROR_MSG("can't initialize transition, no allocator given\n");
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (!transition) { if (!transition) {
RCL_SET_ERROR_MSG("transition pointer is null\n", *allocator); RCL_SET_ERROR_MSG("transition pointer is null\n");
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -130,7 +127,7 @@ rcl_lifecycle_transition_init(
transition->id = id; transition->id = id;
transition->label = rcutils_strndup(label, strlen(label), *allocator); transition->label = rcutils_strndup(label, strlen(label), *allocator);
if (!transition->label) { if (!transition->label) {
RCL_SET_ERROR_MSG("failed to duplicate label for rcl_lifecycle_transition_t\n", *allocator); RCL_SET_ERROR_MSG("failed to duplicate label for rcl_lifecycle_transition_t\n");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -143,8 +140,7 @@ rcl_lifecycle_transition_fini(
const rcl_allocator_t * allocator) const rcl_allocator_t * allocator)
{ {
if (!allocator) { if (!allocator) {
RCL_SET_ERROR_MSG("can't initialize transition, no allocator given\n", RCL_SET_ERROR_MSG("can't initialize transition, no allocator given\n");
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
// it is already NULL // it is already NULL
@ -197,8 +193,7 @@ rcl_lifecycle_state_machine_init(
const rcl_allocator_t * allocator) const rcl_allocator_t * allocator)
{ {
if (!allocator) { if (!allocator) {
RCL_SET_ERROR_MSG("can't initialize state machine, no allocator given\n", RCL_SET_ERROR_MSG("can't initialize state machine, no allocator given\n");
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -206,8 +201,7 @@ rcl_lifecycle_state_machine_init(
&state_machine->com_interface, node_handle, &state_machine->com_interface, node_handle,
ts_pub_notify, ts_pub_notify,
ts_srv_change_state, ts_srv_get_state, ts_srv_change_state, ts_srv_get_state,
ts_srv_get_available_states, ts_srv_get_available_transitions, ts_srv_get_transition_graph, ts_srv_get_available_states, ts_srv_get_available_transitions, ts_srv_get_transition_graph);
allocator);
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -235,24 +229,21 @@ rcl_lifecycle_state_machine_fini(
const rcl_allocator_t * allocator) const rcl_allocator_t * allocator)
{ {
if (!allocator) { if (!allocator) {
RCL_SET_ERROR_MSG("can't free state machine, no allocator given\n", RCL_SET_ERROR_MSG("can't free state machine, no allocator given\n");
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
rcl_ret_t fcn_ret = RCL_RET_OK; rcl_ret_t fcn_ret = RCL_RET_OK;
if (rcl_lifecycle_com_interface_fini(&state_machine->com_interface, node_handle) != RCL_RET_OK) { if (rcl_lifecycle_com_interface_fini(&state_machine->com_interface, node_handle) != RCL_RET_OK) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("could not free lifecycle com interface. Leaking memory!\n");
"could not free lifecycle com interface. Leaking memory!\n", rcl_get_default_allocator());
fcn_ret = RCL_RET_ERROR; fcn_ret = RCL_RET_ERROR;
} }
if (rcl_lifecycle_transition_map_fini( if (rcl_lifecycle_transition_map_fini(
&state_machine->transition_map, allocator) != RCL_RET_OK) &state_machine->transition_map, allocator) != RCL_RET_OK)
{ {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("could not free lifecycle transition map. Leaking memory!\n");
"could not free lifecycle transition map. Leaking memory!\n", rcl_get_default_allocator());
fcn_ret = RCL_RET_ERROR; fcn_ret = RCL_RET_ERROR;
} }
@ -263,15 +254,15 @@ rcl_ret_t
rcl_lifecycle_state_machine_is_initialized(const rcl_lifecycle_state_machine_t * state_machine) rcl_lifecycle_state_machine_is_initialized(const rcl_lifecycle_state_machine_t * state_machine)
{ {
if (!state_machine->com_interface.srv_get_state.impl) { if (!state_machine->com_interface.srv_get_state.impl) {
RCL_SET_ERROR_MSG("get_state service is null", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("get_state service is null");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (!state_machine->com_interface.srv_change_state.impl) { if (!state_machine->com_interface.srv_change_state.impl) {
RCL_SET_ERROR_MSG("change_state service is null", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("change_state service is null");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (rcl_lifecycle_transition_map_is_initialized(&state_machine->transition_map) != RCL_RET_OK) { if (rcl_lifecycle_transition_map_is_initialized(&state_machine->transition_map) != RCL_RET_OK) {
RCL_SET_ERROR_MSG("transition map is null", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("transition map is null");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
return RCL_RET_OK; return RCL_RET_OK;
@ -282,8 +273,7 @@ rcl_lifecycle_get_transition_by_id(
const rcl_lifecycle_state_t * state, const rcl_lifecycle_state_t * state,
uint8_t id) uint8_t id)
{ {
RCL_CHECK_FOR_NULL_WITH_MSG(state, RCL_CHECK_FOR_NULL_WITH_MSG(state, "state pointer is null", return NULL);
"state pointer is null", return NULL, rcl_get_default_allocator());
for (unsigned int i = 0; i < state->valid_transition_size; ++i) { for (unsigned int i = 0; i < state->valid_transition_size; ++i) {
if (state->valid_transitions[i].id == id) { if (state->valid_transitions[i].id == id) {
@ -304,8 +294,7 @@ rcl_lifecycle_get_transition_by_label(
const rcl_lifecycle_state_t * state, const rcl_lifecycle_state_t * state,
const char * label) const char * label)
{ {
RCL_CHECK_FOR_NULL_WITH_MSG(state, RCL_CHECK_FOR_NULL_WITH_MSG(state, "state pointer is null", return NULL);
"state pointer is null", return NULL, rcl_get_default_allocator());
for (unsigned int i = 0; i < state->valid_transition_size; ++i) { for (unsigned int i = 0; i < state->valid_transition_size; ++i) {
if (strcmp(state->valid_transitions[i].label, label) == 0) { if (strcmp(state->valid_transitions[i].label, label) == 0) {
@ -329,7 +318,7 @@ _trigger_transition(
{ {
// If we have a faulty transition pointer // If we have a faulty transition pointer
if (!transition) { if (!transition) {
RCL_SET_ERROR_MSG("Transition is not registered.", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("Transition is not registered.");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -344,7 +333,7 @@ _trigger_transition(
rcl_ret_t ret = rcl_lifecycle_com_interface_publish_notification( rcl_ret_t ret = rcl_lifecycle_com_interface_publish_notification(
&state_machine->com_interface, transition->start, state_machine->current_state); &state_machine->com_interface, transition->start, state_machine->current_state);
if (ret != RCL_RET_OK) { if (ret != RCL_RET_OK) {
RCL_SET_ERROR_MSG("Could not publish transition", rcl_get_default_allocator()); RCL_SET_ERROR_MSG("Could not publish transition");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
} }

View file

@ -72,8 +72,7 @@ rcl_lifecycle_register_state(
const rcutils_allocator_t * allocator) const rcutils_allocator_t * allocator)
{ {
if (rcl_lifecycle_get_state(transition_map, state.id) != NULL) { if (rcl_lifecycle_get_state(transition_map, state.id) != NULL) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(rcutils_get_default_allocator(), RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("state %u is already registered\n", state.id);
"state %u is already registered\n", state.id);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -87,8 +86,7 @@ rcl_lifecycle_register_state(
transition_map->states_size * sizeof(rcl_lifecycle_state_t), transition_map->states_size * sizeof(rcl_lifecycle_state_t),
allocator->state); allocator->state);
if (!new_states) { if (!new_states) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("failed to reallocate memory for new states");
"failed to reallocate memory for new states", rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
transition_map->states = new_states; transition_map->states = new_states;
@ -108,8 +106,7 @@ rcl_lifecycle_register_transition(
rcl_lifecycle_state_t * state = rcl_lifecycle_get_state(transition_map, transition.start->id); rcl_lifecycle_state_t * state = rcl_lifecycle_get_state(transition_map, transition.start->id);
if (!state) { if (!state) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(rcl_get_default_allocator(), RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("state %u is not registered\n", transition.start->id);
"state %u is not registered\n", transition.start->id);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -120,9 +117,7 @@ rcl_lifecycle_register_transition(
transition_map->transitions_size * sizeof(rcl_lifecycle_transition_t), transition_map->transitions_size * sizeof(rcl_lifecycle_transition_t),
allocator->state); allocator->state);
if (!new_transitions) { if (!new_transitions) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("failed to reallocate memory for new transitions");
"failed to reallocate memory for new transitions",
rcl_get_default_allocator());
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
transition_map->transitions = new_transitions; transition_map->transitions = new_transitions;
@ -138,9 +133,7 @@ rcl_lifecycle_register_transition(
state->valid_transition_size * sizeof(rcl_lifecycle_transition_t), state->valid_transition_size * sizeof(rcl_lifecycle_transition_t),
allocator->state); allocator->state);
if (!new_valid_transitions) { if (!new_valid_transitions) {
RCL_SET_ERROR_MSG( RCL_SET_ERROR_MSG("failed to reallocate memory for new transitions on state");
"failed to reallocate memory for new transitions on state",
rcl_get_default_allocator());
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
state->valid_transitions = new_valid_transitions; state->valid_transitions = new_valid_transitions;

View file

@ -40,13 +40,13 @@ protected:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_state_machine_node"; const char * name = "test_state_machine_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); 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); const rcl_node_options_t * node_ops = rcl_node_get_options(this->node_ptr);
this->allocator = &node_ops->allocator; this->allocator = &node_ops->allocator;
} }
@ -55,9 +55,9 @@ protected:
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -91,17 +91,17 @@ TEST_F(TestDefaultStateMachine, zero_init) {
EXPECT_EQ(transition_map->transitions, nullptr); EXPECT_EQ(transition_map->transitions, nullptr);
auto ret = rcl_lifecycle_state_machine_fini(&state_machine, this->node_ptr, this->allocator); auto ret = rcl_lifecycle_state_machine_fini(&state_machine, this->node_ptr, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
TEST_F(TestDefaultStateMachine, default_init) { TEST_F(TestDefaultStateMachine, default_init) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
auto ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); auto ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_lifecycle_state_machine_fini(&state_machine, this->node_ptr, this->allocator); ret = rcl_lifecycle_state_machine_fini(&state_machine, this->node_ptr, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
TEST_F(TestDefaultStateMachine, default_sequence) { TEST_F(TestDefaultStateMachine, default_sequence) {
@ -109,7 +109,7 @@ TEST_F(TestDefaultStateMachine, default_sequence) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_trigger_transition( test_trigger_transition(
&state_machine, &state_machine,
@ -180,7 +180,7 @@ TEST_F(TestDefaultStateMachine, wrong_default_sequence) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
std::vector<uint8_t> transition_ids = std::vector<uint8_t> transition_ids =
{ {
@ -394,7 +394,7 @@ TEST_F(TestDefaultStateMachine, default_in_a_loop) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
for (auto i = 0; i < 5; ++i) { for (auto i = 0; i < 5; ++i) {
test_trigger_transition( test_trigger_transition(
@ -467,7 +467,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_failure) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_trigger_transition( test_trigger_transition(
&state_machine, &state_machine,
@ -583,7 +583,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_resolved) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_trigger_transition( test_trigger_transition(
&state_machine, &state_machine,
@ -732,7 +732,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_unresolved) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_state_machine_t state_machine =
rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_trigger_transition( test_trigger_transition(
&state_machine, &state_machine,
@ -760,7 +760,7 @@ TEST_F(TestDefaultStateMachine, default_sequence_error_unresolved) {
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_state_machine_t state_machine =
rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_trigger_transition( test_trigger_transition(
&state_machine, &state_machine,

View file

@ -37,13 +37,13 @@ protected:
{ {
rcl_ret_t ret; rcl_ret_t ret;
ret = rcl_init(0, nullptr, rcl_get_default_allocator()); ret = rcl_init(0, nullptr, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
this->node_ptr = new rcl_node_t; this->node_ptr = new rcl_node_t;
*this->node_ptr = rcl_get_zero_initialized_node(); *this->node_ptr = rcl_get_zero_initialized_node();
const char * name = "test_multiple_instances_node"; const char * name = "test_multiple_instances_node";
rcl_node_options_t node_options = rcl_node_get_default_options(); 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, "", &node_options);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); 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); const rcl_node_options_t * node_ops = rcl_node_get_options(this->node_ptr);
this->allocator = &node_ops->allocator; this->allocator = &node_ops->allocator;
} }
@ -52,9 +52,9 @@ protected:
{ {
rcl_ret_t ret = rcl_node_fini(this->node_ptr); rcl_ret_t ret = rcl_node_fini(this->node_ptr);
delete this->node_ptr; delete this->node_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_shutdown(); ret = rcl_shutdown();
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }
}; };
@ -80,24 +80,24 @@ TEST_F(TestMultipleInstances, default_sequence_error_unresolved) {
rcl_lifecycle_state_machine_t state_machine1 = rcl_lifecycle_state_machine_t state_machine1 =
rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine1, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine1, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_lifecycle_state_machine_t state_machine2 = rcl_lifecycle_state_machine_t state_machine2 =
rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine2, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine2, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
rcl_lifecycle_state_machine_t state_machine3 = rcl_lifecycle_state_machine_t state_machine3 =
rcl_lifecycle_get_zero_initialized_state_machine(); rcl_lifecycle_get_zero_initialized_state_machine();
ret = rcl_lifecycle_init_default_state_machine(&state_machine3, this->allocator); ret = rcl_lifecycle_init_default_state_machine(&state_machine3, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
test_trigger_transition( test_trigger_transition(
&state_machine1, &state_machine1,
lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE, lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE,
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED, lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING); lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ( EXPECT_EQ(
lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING, state_machine1.current_state->id); lifecycle_msgs__msg__State__TRANSITION_STATE_CONFIGURING, state_machine1.current_state->id);
@ -107,9 +107,9 @@ TEST_F(TestMultipleInstances, default_sequence_error_unresolved) {
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED, state_machine3.current_state->id); lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED, state_machine3.current_state->id);
ret = rcl_lifecycle_state_machine_fini(&state_machine1, this->node_ptr, this->allocator); ret = rcl_lifecycle_state_machine_fini(&state_machine1, this->node_ptr, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_lifecycle_state_machine_fini(&state_machine2, this->node_ptr, this->allocator); ret = rcl_lifecycle_state_machine_fini(&state_machine2, this->node_ptr, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
ret = rcl_lifecycle_state_machine_fini(&state_machine3, this->node_ptr, this->allocator); ret = rcl_lifecycle_state_machine_fini(&state_machine3, this->node_ptr, this->allocator);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
} }

View file

@ -57,7 +57,7 @@ TEST_F(TestTransitionMap, initialized) {
EXPECT_EQ(RCL_RET_OK, rcl_lifecycle_transition_map_is_initialized(&transition_map)); EXPECT_EQ(RCL_RET_OK, rcl_lifecycle_transition_map_is_initialized(&transition_map));
ret = rcl_lifecycle_register_state(&transition_map, state0, &allocator); ret = rcl_lifecycle_register_state(&transition_map, state0, &allocator);
EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string_safe(); EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str;
rcl_lifecycle_state_t state1 = {"my_state_1", 1, NULL, 0}; rcl_lifecycle_state_t state1 = {"my_state_1", 1, NULL, 0};
ret = rcl_lifecycle_register_state(&transition_map, state1, &allocator); ret = rcl_lifecycle_register_state(&transition_map, state1, &allocator);

View file

@ -197,8 +197,7 @@ static rcl_ret_t add_name_to_ns(
tot_len = ns_len + sep_len + name_len + 1U; tot_len = ns_len + sep_len + name_len + 1U;
if (tot_len > MAX_STRING_SIZE) { if (tot_len > MAX_STRING_SIZE) {
RCL_SET_ERROR_MSG("New namespace string is exceeding max string size", RCL_SET_ERROR_MSG("New namespace string is exceeding max string size");
allocator);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
cur_ns = allocator.reallocate(cur_ns, tot_len, allocator.state); cur_ns = allocator.reallocate(cur_ns, tot_len, allocator.state);
@ -266,7 +265,7 @@ static rcl_ret_t rem_name_from_ns(
next_str = strstr(cur_ns, sep_str); next_str = strstr(cur_ns, sep_str);
while (NULL != next_str) { while (NULL != next_str) {
if (next_str > end_ptr) { if (next_str > end_ptr) {
RCL_SET_ERROR_MSG("Internal error. Crossing arrau boundary", allocator); RCL_SET_ERROR_MSG("Internal error. Crossing arrau boundary");
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
last_idx = next_str; last_idx = next_str;
@ -719,7 +718,7 @@ static void * get_value(
char * endptr = NULL; char * endptr = NULL;
if ((NULL == value) || (NULL == val_type)) { if ((NULL == value) || (NULL == val_type)) {
RCL_SET_ERROR_MSG("Invalid arguments", allocator); RCL_SET_ERROR_MSG("Invalid arguments");
return NULL; return NULL;
} }
@ -839,12 +838,12 @@ static rcl_ret_t parse_value(
rcl_variant_t * param_value; rcl_variant_t * param_value;
if (val_size > MAX_STRING_SIZE) { if (val_size > MAX_STRING_SIZE) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Scalar value at line %d" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" is bigger than %d bytes", line_num, MAX_STRING_SIZE); "Scalar value at line %d is bigger than %d bytes", line_num, MAX_STRING_SIZE);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} else { } else {
if (0U == val_size) { if (0U == val_size) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "No value at line %d", line_num); RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("No value at line %d", line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
} }
@ -854,7 +853,7 @@ static rcl_ret_t parse_value(
} }
if (NULL == params_st->params[node_idx].parameter_values) { if (NULL == params_st->params[node_idx].parameter_values) {
RCL_SET_ERROR_MSG("Internal error: Invalid mem", allocator); RCL_SET_ERROR_MSG("Internal error: Invalid mem");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
@ -863,15 +862,14 @@ static rcl_ret_t parse_value(
// param_value->string_value = rcutils_strdup(value, allocator); // param_value->string_value = rcutils_strdup(value, allocator);
ret_val = get_value(value, &val_type, allocator); ret_val = get_value(value, &val_type, allocator);
if (NULL == ret_val) { if (NULL == ret_val) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Error parsing value %s at" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Error parsing value %s at line %d", value, line_num);
" line %d", value, line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
switch (val_type) { switch (val_type) {
case DATA_TYPE_UNKNOWN: case DATA_TYPE_UNKNOWN:
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Unknown data type of" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" value %s at line %d\n", value, line_num); "Unknown data type of value %s at line %d\n", value, line_num);
res = RCL_RET_ERROR; res = RCL_RET_ERROR;
break; break;
case DATA_TYPE_BOOL: case DATA_TYPE_BOOL:
@ -888,8 +886,9 @@ static rcl_ret_t parse_value(
} }
} else { } else {
if (*seq_data_type != val_type) { if (*seq_data_type != val_type) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Sequence should be of same" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" type. Value type 'bool' do not belong at line_num %d", line_num); "Sequence should be of same type. Value type 'bool' do not belong at line_num %d",
line_num);
allocator.deallocate(ret_val, allocator.state); allocator.deallocate(ret_val, allocator.state);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -917,8 +916,9 @@ static rcl_ret_t parse_value(
} }
} else { } else {
if (*seq_data_type != val_type) { if (*seq_data_type != val_type) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Sequence should be of same" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" type. Value type 'integer' do not belong at line_num %d", line_num); "Sequence should be of same type. Value type 'integer' do not belong at line_num %d",
line_num);
allocator.deallocate(ret_val, allocator.state); allocator.deallocate(ret_val, allocator.state);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -946,8 +946,9 @@ static rcl_ret_t parse_value(
} }
} else { } else {
if (*seq_data_type != val_type) { if (*seq_data_type != val_type) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Sequence should be of same" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" type. Value type 'double' do not belong at line_num %d", line_num); "Sequence should be of same type. Value type 'double' do not belong at line_num %d",
line_num);
allocator.deallocate(ret_val, allocator.state); allocator.deallocate(ret_val, allocator.state);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -978,8 +979,9 @@ static rcl_ret_t parse_value(
} }
} else { } else {
if (*seq_data_type != val_type) { if (*seq_data_type != val_type) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Sequence should be of same" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" type. Value type 'string' do not belong at line_num %d", line_num); "Sequence should be of same type. Value type 'string' do not belong at line_num %d",
line_num);
allocator.deallocate(ret_val, allocator.state); allocator.deallocate(ret_val, allocator.state);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -994,8 +996,8 @@ static rcl_ret_t parse_value(
} }
break; break;
default: default:
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Unknown data type of value" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" %s at line %d", value, line_num); "Unknown data type of value %s at line %d", value, line_num);
res = RCL_RET_ERROR; res = RCL_RET_ERROR;
break; break;
} }
@ -1026,12 +1028,13 @@ static rcl_ret_t parse_key(
allocator = params_st->allocator; allocator = params_st->allocator;
if (val_size > MAX_STRING_SIZE) { if (val_size > MAX_STRING_SIZE) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Scalar value at line %d" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" is bigger than %d bytes", line_num, MAX_STRING_SIZE); "Scalar value at line %d is bigger than %d bytes",
line_num, MAX_STRING_SIZE);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} else { } else {
if (0U == val_size) { if (0U == val_size) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "No key at line %d", line_num); RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("No key at line %d", line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
} }
@ -1046,8 +1049,7 @@ static rcl_ret_t parse_key(
switch (*map_level) { switch (*map_level) {
case MAP_UNINIT_LVL: case MAP_UNINIT_LVL:
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Unintialized map level" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Unintialized map level at line %d", line_num);
" at line %d", line_num);
res = RCL_RET_ERROR; res = RCL_RET_ERROR;
break; break;
case MAP_NODE_NAME_LVL: case MAP_NODE_NAME_LVL:
@ -1056,14 +1058,14 @@ static rcl_ret_t parse_key(
if (0 != strncmp(PARAMS_KEY, value, strlen(PARAMS_KEY))) { if (0 != strncmp(PARAMS_KEY, value, strlen(PARAMS_KEY))) {
res = add_name_to_ns(ns_tracker, value, NS_TYPE_NODE, allocator); res = add_name_to_ns(ns_tracker, value, NS_TYPE_NODE, allocator);
if (RCL_RET_OK != res) { if (RCL_RET_OK != res) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Internal error" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" adding node namespace at line %d", line_num); "Internal error adding node namespace at line %d", line_num);
return res; return res;
} }
} else { } else {
if (0U == ns_tracker->num_node_ns) { if (0U == ns_tracker->num_node_ns) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "There are no node names" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" before %s at line %d", PARAMS_KEY, line_num); "There are no node names before %s at line %d", PARAMS_KEY, line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
/// The previous key(last name in namespace) was the node name. Remove it /// The previous key(last name in namespace) was the node name. Remove it
@ -1076,14 +1078,14 @@ static rcl_ret_t parse_key(
res = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); res = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator);
if (RCL_RET_OK != res) { if (RCL_RET_OK != res) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Internal error" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" adding node namespace at line %d", line_num); "Internal error adding node namespace at line %d", line_num);
return res; return res;
} }
res = node_params_init(&(params_st->params[num_nodes]), allocator); res = node_params_init(&(params_st->params[num_nodes]), allocator);
if (RCL_RET_OK != res) { if (RCL_RET_OK != res) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Error creating node" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" parameter at line %d", line_num); "Error creating node parameter at line %d", line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
params_st->num_nodes++; params_st->num_nodes++;
@ -1104,15 +1106,15 @@ static rcl_ret_t parse_key(
parameter_idx = params_st->params[node_idx].num_params; parameter_idx = params_st->params[node_idx].num_params;
parameter_ns = params_st->params[node_idx].parameter_names[parameter_idx]; parameter_ns = params_st->params[node_idx].parameter_names[parameter_idx];
if (NULL == parameter_ns) { if (NULL == parameter_ns) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Internal error" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" creating param namespace at line %d", line_num); "Internal error creating param namespace at line %d", line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
res = replace_ns(ns_tracker, parameter_ns, (ns_tracker->num_parameter_ns + 1U), res = replace_ns(ns_tracker, parameter_ns, (ns_tracker->num_parameter_ns + 1U),
NS_TYPE_PARAM, allocator); NS_TYPE_PARAM, allocator);
if (RCL_RET_OK != res) { if (RCL_RET_OK != res) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Internal error replacing" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" namespace at line %d", line_num); "Internal error replacing namespace at line %d", line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
*is_new_map = false; *is_new_map = false;
@ -1131,8 +1133,8 @@ static rcl_ret_t parse_key(
const size_t tot_len = (params_ns_len + param_name_len + 2U); const size_t tot_len = (params_ns_len + param_name_len + 2U);
if (tot_len > MAX_STRING_SIZE) { if (tot_len > MAX_STRING_SIZE) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "The name length" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" exceeds the MAX size %d at line %d", MAX_STRING_SIZE, line_num); "The name length exceeds the MAX size %d at line %d", MAX_STRING_SIZE, line_num);
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -1151,8 +1153,7 @@ static rcl_ret_t parse_key(
} }
break; break;
default: default:
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Unknown map level at" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Unknown map level at line %d", line_num);
" line %d", line_num);
res = RCL_RET_ERROR; res = RCL_RET_ERROR;
break; break;
} }
@ -1190,8 +1191,7 @@ static rcl_ret_t parse_events(
} }
res = yaml_parser_parse(parser, &event); res = yaml_parser_parse(parser, &event);
if (0 == res) { if (0 == res) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Error parsing a" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Error parsing a event near line %d", line_num);
" event near line %d", line_num);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} else { } else {
res = RCL_RET_OK; res = RCL_RET_OK;
@ -1216,8 +1216,8 @@ static rcl_ret_t parse_events(
} else { } else {
/// It is a value /// It is a value
if (map_level < (uint32_t)(MAP_PARAMS_LVL)) { if (map_level < (uint32_t)(MAP_PARAMS_LVL)) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Cannot have a value" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" before %s at line %d", PARAMS_KEY, line_num); "Cannot have a value before %s at line %d", PARAMS_KEY, line_num);
yaml_event_delete(&event); yaml_event_delete(&event);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -1235,14 +1235,13 @@ static rcl_ret_t parse_events(
break; break;
case YAML_SEQUENCE_START_EVENT: case YAML_SEQUENCE_START_EVENT:
if (true == is_key) { if (true == is_key) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Sequences cannot be key" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Sequences cannot be key at line %d", line_num);
" at line %d", line_num);
yaml_event_delete(&event); yaml_event_delete(&event);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
if (map_level < (uint32_t)(MAP_PARAMS_LVL)) { if (map_level < (uint32_t)(MAP_PARAMS_LVL)) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Sequences can only be" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" values and not keys in params. Error at line %d\n", line_num); "Sequences can only be values and not keys in params. Error at line %d\n", line_num);
yaml_event_delete(&event); yaml_event_delete(&event);
return RCL_RET_ERROR; return RCL_RET_ERROR;
} }
@ -1273,8 +1272,8 @@ static rcl_ret_t parse_events(
/// Remove param namesapce /// Remove param namesapce
res = rem_name_from_ns(ns_tracker, NS_TYPE_PARAM, allocator); res = rem_name_from_ns(ns_tracker, NS_TYPE_PARAM, allocator);
if (RCL_RET_OK != res) { if (RCL_RET_OK != res) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Internal error" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" removing parameter namespace at line %d", line_num); "Internal error removing parameter namespace at line %d", line_num);
yaml_event_delete(&event); yaml_event_delete(&event);
return res; return res;
} }
@ -1288,8 +1287,8 @@ static rcl_ret_t parse_events(
/// Remove node namespace /// Remove node namespace
res = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); res = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator);
if (RCL_RET_OK != res) { if (RCL_RET_OK != res) {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Internal error" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" removing node namespace at line %d", line_num); "Internal error removing node namespace at line %d", line_num);
yaml_event_delete(&event); yaml_event_delete(&event);
return res; return res;
} }
@ -1299,8 +1298,8 @@ static rcl_ret_t parse_events(
yaml_event_delete(&event); yaml_event_delete(&event);
break; break;
case YAML_ALIAS_EVENT: case YAML_ALIAS_EVENT:
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Will not support aliasing" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" at line %d\n", line_num); "Will not support aliasing at line %d\n", line_num);
res = RCL_RET_ERROR; res = RCL_RET_ERROR;
yaml_event_delete(&event); yaml_event_delete(&event);
break; break;
@ -1314,14 +1313,13 @@ static rcl_ret_t parse_events(
yaml_event_delete(&event); yaml_event_delete(&event);
break; break;
case YAML_NO_EVENT: case YAML_NO_EVENT:
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Received an empty event at" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
" line %d", line_num); "Received an empty event at line %d", line_num);
res = RCL_RET_ERROR; res = RCL_RET_ERROR;
yaml_event_delete(&event); yaml_event_delete(&event);
break; break;
default: default:
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(allocator, "Unknown YAML event at line" RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("Unknown YAML event at line %d", line_num);
" %d", line_num);
res = RCL_RET_ERROR; res = RCL_RET_ERROR;
yaml_event_delete(&event); yaml_event_delete(&event);
break; break;
@ -1354,20 +1352,20 @@ bool rcl_parse_yaml_file(
allocator = params_st->allocator; allocator = params_st->allocator;
if (NULL == file_path) { if (NULL == file_path) {
RCL_SET_ERROR_MSG("YAML file path is NULL", allocator); RCL_SET_ERROR_MSG("YAML file path is NULL");
return false; return false;
} }
res = yaml_parser_initialize(&parser); res = yaml_parser_initialize(&parser);
if (0 == res) { if (0 == res) {
RCL_SET_ERROR_MSG("Could not initialize the parser", allocator); RCL_SET_ERROR_MSG("Could not initialize the parser");
return false; return false;
} }
yaml_file = fopen(file_path, "r"); yaml_file = fopen(file_path, "r");
if (NULL == yaml_file) { if (NULL == yaml_file) {
yaml_parser_delete(&parser); yaml_parser_delete(&parser);
RCL_SET_ERROR_MSG("Error opening YAML file", allocator); RCL_SET_ERROR_MSG("Error opening YAML file");
return false; return false;
} }

View file

@ -35,7 +35,7 @@ TEST(test_file_parser, correct_syntax) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_TRUE(res); EXPECT_TRUE(res);
rcl_yaml_node_struct_print(params_hdl); rcl_yaml_node_struct_print(params_hdl);
rcl_yaml_node_struct_fini(params_hdl); rcl_yaml_node_struct_fini(params_hdl);
@ -54,7 +54,7 @@ TEST(test_file_parser, multi_ns_correct_syntax) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_TRUE(res); EXPECT_TRUE(res);
rcl_yaml_node_struct_print(params_hdl); rcl_yaml_node_struct_print(params_hdl);
rcl_yaml_node_struct_fini(params_hdl); rcl_yaml_node_struct_fini(params_hdl);
@ -73,7 +73,7 @@ TEST(test_file_parser, root_ns) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_TRUE(res); EXPECT_TRUE(res);
rcl_yaml_node_struct_print(params_hdl); rcl_yaml_node_struct_print(params_hdl);
@ -98,7 +98,7 @@ TEST(test_file_parser, seq_map1) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res); EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state); allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state); allocator.deallocate(path, allocator.state);
@ -115,7 +115,7 @@ TEST(test_file_parser, seq_map2) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res); EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state); allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state); allocator.deallocate(path, allocator.state);
@ -132,7 +132,7 @@ TEST(test_file_parser, params_with_no_node) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res); EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state); allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state); allocator.deallocate(path, allocator.state);
@ -149,7 +149,7 @@ TEST(test_file_parser, no_alias_support) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res); EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state); allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state); allocator.deallocate(path, allocator.state);
@ -166,7 +166,7 @@ TEST(test_file_parser, max_string_sz) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res); EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state); allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state); allocator.deallocate(path, allocator.state);
@ -183,7 +183,7 @@ TEST(test_file_parser, no_value1) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res); EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state); allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state); allocator.deallocate(path, allocator.state);
@ -200,7 +200,7 @@ TEST(test_file_parser, indented_ns) {
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
EXPECT_FALSE(NULL == params_hdl); EXPECT_FALSE(NULL == params_hdl);
bool res = rcl_parse_yaml_file(path, params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string_safe()); fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res); EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state); allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state); allocator.deallocate(path, allocator.state);