37 #include <rclcpp/rclcpp.hpp>
40 #include <rsl/random.hpp>
41 #include <fmt/format.h>
51 static rclcpp::Logger logger = [&] {
55 auto name = fmt::format(
"moveit_{}", rsl::rng()());
58 static auto* moveit_node =
new rclcpp::Node(
name);
59 return moveit_node->get_logger();
61 catch (
const std::exception& ex)
64 auto logger = rclcpp::get_logger(
name);
65 RCLCPP_WARN_STREAM(logger,
"exception thrown while creating node for logging: " << ex.what());
66 RCLCPP_WARN(logger,
"if rclcpp::init was not called, messages from this logger may be missing from /rosout");
75 static auto node = std::make_shared<rclcpp::Node>(
"moveit",
name);
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
rclcpp::Logger & getGlobalRootLogger()