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>
|
| | 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.
|
| |
| void | publishMessage (const int32_t log_level, const std::string &source_name, const std::string &details) |
| | Function to publish a message.
|
| |
| virtual void | publishMessage (const int32_t log_level, const std::string &details) |
| | Function to publish a message. The default implementation logs to spdlog. LoggerROS is a good example of a subclass that overrides this, in which it publishes the message to a ROS topic and also calls this superclass function to also log to console.
|
| |
| 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.
|
| |
| void | publishMessage (const int32_t log_level, const std::string &source_name, const std::string &details) |
| | Function to publish a message.
|
| |
| 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.
◆ LoggerROS()
| moveit_studio::behavior::LoggerROS::LoggerROS |
( |
const std::shared_ptr< rclcpp::Node > & |
node | ) |
|
|
explicit |
Constructor for LoggerROS.
- Parameters
-
| node | rclcpp Node used when creating the log publisher. |
◆ publishMessage() [1/3]
| void moveit_studio::behavior::LoggerBase::publishMessage |
( |
const int32_t |
log_level, |
|
|
const std::string & |
details |
|
) |
| |
|
virtual |
Function to publish a message. The default implementation logs to spdlog. LoggerROS is a good example of a subclass that overrides this, in which it publishes the message to a ROS topic and also calls this superclass function to also log to console.
- Parameters
-
| log_level | moveit_studio_agent_msgs::msg::ERROR/WARN/INFO |
| details | Contains the information message |
Reimplemented from moveit_studio::behavior::LoggerBase.
◆ publishMessage() [2/3]
| void moveit_studio::behavior::LoggerROS::publishMessage |
( |
const int32_t |
log_level, |
|
|
const std::string & |
details |
|
) |
| |
|
overridevirtual |
Helper function which handles publishing custom message according to the log level specified by user.
- Parameters
-
| log_level | moveit_studio_agent_msgs::msg::ERROR/WARN/INFO |
| details | Contains the information message |
Reimplemented from moveit_studio::behavior::LoggerBase.
◆ publishMessage() [3/3]
| void moveit_studio::behavior::LoggerBase::publishMessage |
( |
const int32_t |
log_level, |
|
|
const std::string & |
source_name, |
|
|
const std::string & |
details |
|
) |
| |
Function to publish a message.
- Parameters
-
| log_level | moveit_studio_agent_msgs::msg::ERROR/WARN/INFO |
| source_name | Name used to identify the source of the log. |
| details | Contains the information message |
The documentation for this class was generated from the following files: