Don't call rcl_logging_configure/rcl_logging_fini in rcl_init/rcl_shutdown (#579)

Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
This commit is contained in:
Ivan Santiago Paunovic 2020-04-23 17:33:32 -03:00 committed by GitHub
parent 3d1337d0fc
commit 8a0ec5fe95
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
5 changed files with 50 additions and 19 deletions

View file

@ -144,7 +144,7 @@ rcl_init_options_fini(rcl_init_options_t * init_options);
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] init_options object from which the rmw init options should be retrieved * \param[in] init_options object from which the rmw init options should be retrieved
* \return pointer to the the rmw init options, or * \return pointer to the the rcl init options, or
* \return `NULL` if there was an error * \return `NULL` if there was an error
*/ */
RCL_PUBLIC RCL_PUBLIC
@ -152,6 +152,31 @@ RCL_WARN_UNUSED
rmw_init_options_t * rmw_init_options_t *
rcl_init_options_get_rmw_init_options(rcl_init_options_t * init_options); rcl_init_options_get_rmw_init_options(rcl_init_options_t * init_options);
/// Return the allocator stored in the init_options.
/**
* This function can fail and return `NULL` if:
* - init_options is NULL
* - init_options is invalid, e.g. init_options->impl is NULL
*
* If NULL is returned an error message will have been set.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | Yes
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] init_options object from which the allocator should be retrieved
* \return pointer to the rcl allocator, or
* \return `NULL` if there was an error
*/
RCL_PUBLIC
RCL_WARN_UNUSED
const rcl_allocator_t *
rcl_init_options_get_allocator(const rcl_init_options_t * init_options);
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif

View file

@ -131,16 +131,6 @@ rcl_init(
goto fail; goto fail;
} }
ret = rcl_logging_configure(&context->global_arguments, &allocator);
if (RCL_RET_OK != ret) {
fail_ret = ret;
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME,
"Failed to configure logging: %s",
rcutils_get_error_string().str);
goto fail;
}
// Set the instance id. // Set the instance id.
uint64_t next_instance_id = rcutils_atomic_fetch_add_uint64_t(&__rcl_next_unique_id, 1); uint64_t next_instance_id = rcutils_atomic_fetch_add_uint64_t(&__rcl_next_unique_id, 1);
if (0 == next_instance_id) { if (0 == next_instance_id) {
@ -260,13 +250,6 @@ rcl_shutdown(rcl_context_t * context)
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
} }
rcl_ret_t rcl_ret = rcl_logging_fini();
RCUTILS_LOG_ERROR_EXPRESSION_NAMED(
RCL_RET_OK != rcl_ret, ROS_PACKAGE_NAME,
"Failed to fini logging, rcl_ret_t: %i, rcl_error_str: %s", rcl_ret,
rcl_get_error_string().str);
rcl_reset_error();
return RCL_RET_OK; return RCL_RET_OK;
} }

View file

@ -139,6 +139,14 @@ rcl_init_options_get_rmw_init_options(rcl_init_options_t * init_options)
return &(init_options->impl->rmw_init_options); return &(init_options->impl->rmw_init_options);
} }
const rcl_allocator_t *
rcl_init_options_get_allocator(const rcl_init_options_t * init_options)
{
RCL_CHECK_ARGUMENT_FOR_NULL(init_options, NULL);
RCL_CHECK_ARGUMENT_FOR_NULL(init_options->impl, NULL);
return &(init_options->impl->allocator);
}
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif

View file

@ -30,6 +30,7 @@
#include "rcl/error_handling.h" #include "rcl/error_handling.h"
#include "rcl/graph.h" #include "rcl/graph.h"
#include "rcl/logging.h"
#include "rcl/rcl.h" #include "rcl/rcl.h"
#include "rcutils/logging_macros.h" #include "rcutils/logging_macros.h"
@ -66,6 +67,7 @@ public:
void SetUp() void SetUp()
{ {
rcl_ret_t ret; rcl_ret_t ret;
rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
@ -77,6 +79,10 @@ public:
*this->old_context_ptr = rcl_get_zero_initialized_context(); *this->old_context_ptr = rcl_get_zero_initialized_context();
ret = rcl_init(0, nullptr, &init_options, this->old_context_ptr); ret = rcl_init(0, nullptr, &init_options, this->old_context_ptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(
RCL_RET_OK,
rcl_logging_configure(&this->old_context_ptr->global_arguments, &allocator)
) << 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";
@ -127,6 +133,7 @@ public:
ret = rcl_context_fini(this->old_context_ptr); ret = rcl_context_fini(this->old_context_ptr);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
delete this->old_context_ptr; delete this->old_context_ptr;
EXPECT_EQ(RCL_RET_OK, rcl_logging_fini()) << rcl_get_error_string().str;
} }
}; };

View file

@ -19,6 +19,7 @@
#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "osrf_testing_tools_cpp/scope_exit.hpp"
#include "rcl/error_handling.h" #include "rcl/error_handling.h"
#include "rcl/logging.h"
#include "rcl/rcl.h" #include "rcl/rcl.h"
#include "rcl/subscription.h" #include "rcl/subscription.h"
#include "rcl_interfaces/msg/log.h" #include "rcl_interfaces/msg/log.h"
@ -70,8 +71,9 @@ public:
{ {
auto param = GetParam(); auto param = GetParam();
rcl_ret_t ret; rcl_ret_t ret;
rcl_allocator_t allocator = rcl_get_default_allocator();
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); ret = rcl_init_options_init(&init_options, allocator);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{ {
@ -83,6 +85,11 @@ public:
ret = rcl_init(param.argc, param.argv, &init_options, this->context_ptr); ret = rcl_init(param.argc, param.argv, &init_options, this->context_ptr);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(
RCL_RET_OK,
rcl_logging_configure(&this->context_ptr->global_arguments, &allocator)
) << rcl_get_error_string().str;
// create node // create node
rcl_node_options_t node_options = rcl_node_get_default_options(); rcl_node_options_t node_options = rcl_node_get_default_options();
if (!param.enable_node_option_rosout) { if (!param.enable_node_option_rosout) {
@ -120,6 +127,7 @@ public:
ret = rcl_context_fini(this->context_ptr); ret = rcl_context_fini(this->context_ptr);
delete this->context_ptr; delete this->context_ptr;
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(RCL_RET_OK, rcl_logging_fini()) << rcl_get_error_string().str;
} }
protected: protected: