Skip to content

Commit

Permalink
No longer create nodes for child loggers on Humble
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw committed Oct 26, 2023
1 parent b264c47 commit 10225c6
Showing 1 changed file with 12 additions and 22 deletions.
34 changes: 12 additions & 22 deletions moveit_core/utils/src/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string, std::shared_ptr<rclcpp::Node>> child_nodes;
if (child_nodes.find(name) == child_nodes.end())
{
std::string ns = get_logger().get_name();
try
{
child_nodes[name] = std::make_shared<rclcpp::Node>(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);
Expand Down

0 comments on commit 10225c6

Please sign in to comment.