From 10225c6482a820bb31a1766f2c2e90f385bca99a Mon Sep 17 00:00:00 2001 From: Tyler Weaver Date: Thu, 26 Oct 2023 12:37:38 -0600 Subject: [PATCH] No longer create nodes for child loggers on Humble --- moveit_core/utils/src/logger.cpp | 34 +++++++++++--------------------- 1 file changed, 12 insertions(+), 22 deletions(-) diff --git a/moveit_core/utils/src/logger.cpp b/moveit_core/utils/src/logger.cpp index 3a99dce0e1..2fd7813532 100644 --- a/moveit_core/utils/src/logger.cpp +++ b/moveit_core/utils/src/logger.cpp @@ -69,29 +69,19 @@ const rclcpp::Logger& get_logger() rclcpp::Logger make_child_logger(const std::string& name) { - // On versions of ROS older than Iron we need to create a node for each child logger - // Remove once Humble is EOL - // References: - // Use parent logger (rcl PR) - https://github.com/ros2/rcl/pull/921 - // Request for backport (rclpy issue) - https://github.com/ros2/rclpy/issues/1131 - // MoveIt PR that added this - https://github.com/ros-planning/moveit2/pull/2445 + // On versions of ROS older than Iron child loggers do not log to rosout unless there + // is a node of the same name. See: https://github.com/ros2/rcl/pull/921 + // We attempted to solve this problem by creating nodes for each child logger + // as suggested here: https://github.com/ros2/rclpy/issues/1131 + // The side-affects of creating many nodes caused problems with many duplicate + // ros nodes and creating many services per-node that slow DDS discovery. + // + // To deal with the problem of loss of namespacing on Humble see this comment: + // https://github.com/ros-planning/moveit2/issues/2376#issuecomment-1781586851 + // TL;DR is to use the source location information in /rosout + // #if !RCLCPP_VERSION_GTE(21, 0, 3) - static std::unordered_map> child_nodes; - if (child_nodes.find(name) == child_nodes.end()) - { - std::string ns = get_logger().get_name(); - try - { - child_nodes[name] = std::make_shared(name, ns); - } - catch (...) - { - // rclcpp::init was not called so rcl context is null, return non-node logger - auto logger = rclcpp::get_logger(ns.append(".").append(name)); - RCLCPP_WARN(logger, "rclcpp::init was not called, messages from this logger may be missing from /rosout"); - return logger; - } - } + return get_global_logger_ref(); #endif return get_global_logger_ref().get_child(name);