diff --git a/rclcpp/src/rclcpp/logger.cpp b/rclcpp/src/rclcpp/logger.cpp index 874858b180..2e83c07013 100644 --- a/rclcpp/src/rclcpp/logger.cpp +++ b/rclcpp/src/rclcpp/logger.cpp @@ -17,6 +17,7 @@ #include #include "rcl_logging_interface/rcl_logging_interface.h" +#include "rcl/error_handling.h" #include "rcl/logging_rosout.h" #include "rclcpp/exceptions.hpp" @@ -80,10 +81,12 @@ Logger::get_child(const std::string & suffix) { std::lock_guard guard(*logging_mutex); rcl_ret = rcl_logging_rosout_add_sublogger((*name_).c_str(), suffix.c_str()); - if (RCL_RET_OK != rcl_ret) { + if (RCL_RET_NOT_FOUND == rcl_ret) { + rcl_reset_error(); + } else if (RCL_RET_OK != rcl_ret) { exceptions::throw_from_rcl_error( rcl_ret, "failed to call rcl_logging_rosout_add_sublogger", - rcutils_get_error_state(), rcutils_reset_error); + rcl_get_error_state(), rcl_reset_error); } } @@ -98,9 +101,7 @@ Logger::get_child(const std::string & suffix) logger_sublogger_pairname_ptr->second.c_str()); delete logger_sublogger_pairname_ptr; if (RCL_RET_OK != rcl_ret) { - exceptions::throw_from_rcl_error( - rcl_ret, "failed to call rcl_logging_rosout_remove_sublogger", - rcutils_get_error_state(), rcutils_reset_error); + rcl_reset_error(); } }); } diff --git a/rclcpp/test/rclcpp/test_rosout_subscription.cpp b/rclcpp/test/rclcpp/test_rosout_subscription.cpp index c5f00bb26d..08786a3fcb 100644 --- a/rclcpp/test/rclcpp/test_rosout_subscription.cpp +++ b/rclcpp/test/rclcpp/test_rosout_subscription.cpp @@ -178,3 +178,13 @@ TEST_F(TestRosoutSubscription, test_rosoutsubscription_getchild_hierarchy) { EXPECT_TRUE(future.get()); received_msg_promise = {}; } + +TEST_F(TestRosoutSubscription, test_rosoutsubscription_node_rosout_disabled) { + rclcpp::NodeOptions options = rclcpp::NodeOptions().enable_rosout(false); + auto node = std::make_shared("my_node", options); + auto log_func = [&node] { + auto logger = node->get_logger().get_child("child"); + RCLCPP_INFO(logger, "test"); + }; + ASSERT_NO_THROW(log_func()); +}