Skip to content

Commit

Permalink
Test for exception thrown durring making a node
Browse files Browse the repository at this point in the history
  • Loading branch information
tylerjw committed Oct 25, 2023
1 parent 70eb1ab commit 8e215d8
Showing 1 changed file with 26 additions and 3 deletions.
29 changes: 26 additions & 3 deletions moveit_core/utils/src/logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,21 @@ namespace moveit

rclcpp::Logger& get_global_logger_ref()
{
static std::shared_ptr<rclcpp::Node> moveit_node = std::make_shared<rclcpp::Node>("moveit");
static rclcpp::Logger logger = moveit_node->get_logger();
static std::shared_ptr<rclcpp::Node> moveit_node;
static rclcpp::Logger logger = [&] {
try
{
moveit_node = std::make_shared<rclcpp::Node>("moveit");
}
catch (...)
{
// rclcpp::init was not called so rcl context is null, return non-node logger
auto logger = rclcpp::get_logger("moveit");
RCLCPP_WARN(logger, "rclcpp::init was not called, messages from this logger may be missing from /rosout");
return logger;
}
return moveit_node->get_logger();
}();
return logger;
}

Expand All @@ -68,7 +81,17 @@ rclcpp::Logger make_child_logger(const std::string& name)
if (child_nodes.find(name) == child_nodes.end())
{
std::string ns = get_logger().get_name();
child_nodes[name] = std::make_shared<rclcpp::Node>(name, ns);
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;
}
}
#endif

Expand Down

0 comments on commit 8e215d8

Please sign in to comment.