diff --git a/rclcpp/src/rclcpp/context.cpp b/rclcpp/src/rclcpp/context.cpp index bbc1d29d0f..a9b40b733e 100644 --- a/rclcpp/src/rclcpp/context.cpp +++ b/rclcpp/src/rclcpp/context.cpp @@ -212,28 +212,27 @@ Context::init( } rcl_context_.reset(context, __delete_context); - if (init_options.auto_initialize_logging()) { - logging_mutex_ = get_global_logging_mutex(); - std::lock_guard guard(*logging_mutex_); - size_t & count = get_logging_reference_count(); - if (0u == count) { - ret = rcl_logging_configure_with_output_handler( - &rcl_context_->global_arguments, - rcl_init_options_get_allocator(init_options.get_rcl_init_options()), - rclcpp_logging_output_handler); - if (RCL_RET_OK != ret) { - rcl_context_.reset(); - rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging"); + try { + if (init_options.auto_initialize_logging()) { + logging_mutex_ = get_global_logging_mutex(); + std::lock_guard guard(*logging_mutex_); + size_t & count = get_logging_reference_count(); + if (0u == count) { + ret = rcl_logging_configure_with_output_handler( + &rcl_context_->global_arguments, + rcl_init_options_get_allocator(init_options.get_rcl_init_options()), + rclcpp_logging_output_handler); + if (RCL_RET_OK != ret) { + rclcpp::exceptions::throw_from_rcl_error(ret, "failed to configure logging"); + } + } else { + RCLCPP_WARN( + rclcpp::get_logger("rclcpp"), + "logging was initialized more than once"); } - } else { - RCLCPP_WARN( - rclcpp::get_logger("rclcpp"), - "logging was initialized more than once"); + ++count; } - ++count; - } - try { std::vector unparsed_ros_arguments = detail::get_unparsed_ros_arguments( argc, argv, &(rcl_context_->global_arguments), rcl_get_default_allocator()); if (!unparsed_ros_arguments.empty()) { diff --git a/rclcpp/test/rclcpp/test_utilities.cpp b/rclcpp/test/rclcpp/test_utilities.cpp index 98874845e3..b64b0a31c6 100644 --- a/rclcpp/test/rclcpp/test_utilities.cpp +++ b/rclcpp/test/rclcpp/test_utilities.cpp @@ -178,11 +178,11 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcl_guard_condition_options_t, <) TEST(TestUtilities, test_context_init_shutdown_fails) { { - auto context = std::make_shared(); auto context_fail_init = std::make_shared(); auto mock = mocking_utils::patch_and_return( "lib:rclcpp", rcl_init, RCL_RET_ERROR); EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError); + EXPECT_FALSE(context_fail_init->is_valid()); } { @@ -190,6 +190,7 @@ TEST(TestUtilities, test_context_init_shutdown_fails) { auto mock = mocking_utils::patch_and_return( "lib:rclcpp", rcl_logging_configure_with_output_handler, RCL_RET_ERROR); EXPECT_THROW(context_fail_init->init(0, nullptr), rclcpp::exceptions::RCLError); + EXPECT_FALSE(context_fail_init->is_valid()); } {