![]() |
MoveIt Pro API
Core Behaviors for MoveIt Pro
|
A ROS-specialized implementation of LoggerBase that publishes the error message on a topic and logs it through an rclcpp Logger. More...
#include <logger.hpp>
Public Member Functions | |
LoggerROS (const std::shared_ptr< rclcpp::Node > &node) | |
Constructor for LoggerROS. | |
void | publishMessage (const int32_t log_level, const std::string &details) override |
Helper function which handles publishing custom message according to the log level specified by user. | |
![]() | |
virtual | ~LoggerBase ()=default |
virtual void | publishFailureMessage (const std::string &error_source_name, const std::string &details="") |
Helper function that wraps publishMessage with a preset ERROR log level. | |
virtual void | publishWarnMessage (const std::string &source_name, const std::string &details="") |
Helper function that wraps publishMessage with a preset WARN log level. | |
virtual void | publishInfoMessage (const std::string &source_name, const std::string &details="") |
Helper function that wraps publishMessage with a preset INFO log level. | |
virtual std::string | consumeErrorLogBuffer () |
Helper function to get the error log buffer. | |
A ROS-specialized implementation of LoggerBase that publishes the error message on a topic and logs it through an rclcpp Logger.
|
explicit |
Constructor for LoggerROS.
node | rclcpp Node used when creating the log publisher. |
|
overridevirtual |
Helper function which handles publishing custom message according to the log level specified by user.
log_level | moveit_studio_agent_msgs::msg::ERROR/WARN/INFO |
details | Contains the information message |
Reimplemented from moveit_studio::behavior::LoggerBase.