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. More...
|
|
void | publishFailureMessage (const std::string &error_source_name, const std::string &details="") override |
| Log error on console and publish the error to be displayed on the UI. More...
|
|
void | publishWarnMessage (const std::string &source_name, const std::string &details="") override |
| Log warning on console and publish the warning to be displayed on the UI. More...
|
|
void | publishInfoMessage (const std::string &source_name, const std::string &details="") override |
| Log info on console and publish the info to be displayed on the UI. More...
|
|
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. More...
|
|
virtual | ~LoggerBase ()=default |
|
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. |
◆ publishFailureMessage()
void moveit_studio::behavior::LoggerROS::publishFailureMessage |
( |
const std::string & |
error_source_name, |
|
|
const std::string & |
details = "" |
|
) |
| |
|
overridevirtual |
Log error on console and publish the error to be displayed on the UI.
- Parameters
-
error_source_name | Name used to identify the source of the failure, generally a behavior tree node identifier. |
details | A detailed message describing the failure. |
Implements moveit_studio::behavior::LoggerBase.
◆ publishInfoMessage()
void moveit_studio::behavior::LoggerROS::publishInfoMessage |
( |
const std::string & |
source_name, |
|
|
const std::string & |
details = "" |
|
) |
| |
|
overridevirtual |
Log info on console and publish the info to be displayed on the UI.
- Parameters
-
error_source_name | Name used to identify the source of the info, generally a behavior tree node identifier. |
details | Contains the information message |
Implements moveit_studio::behavior::LoggerBase.
◆ publishMessage()
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 |
Implements moveit_studio::behavior::LoggerBase.
◆ publishWarnMessage()
void moveit_studio::behavior::LoggerROS::publishWarnMessage |
( |
const std::string & |
source_name, |
|
|
const std::string & |
details = "" |
|
) |
| |
|
overridevirtual |
Log warning on console and publish the warning to be displayed on the UI.
- Parameters
-
error_source_name | Name used to identify the source of the warning, generally a behavior tree node identifier. |
details | Contains a brief message describing the warning |
Implements moveit_studio::behavior::LoggerBase.
The documentation for this class was generated from the following files: