MoveIt Pro API
Core Behaviors for MoveIt Pro
Loading...
Searching...
No Matches
moveit_studio::behavior::LoggerROS Class Reference

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>

Inheritance diagram for moveit_studio::behavior::LoggerROS:
Collaboration diagram for moveit_studio::behavior::LoggerROS:

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.
 
- Public Member Functions inherited from moveit_studio::behavior::LoggerBase
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.
 

Detailed Description

A ROS-specialized implementation of LoggerBase that publishes the error message on a topic and logs it through an rclcpp Logger.

Constructor & Destructor Documentation

◆ LoggerROS()

moveit_studio::behavior::LoggerROS::LoggerROS ( const std::shared_ptr< rclcpp::Node > &  node)
explicit

Constructor for LoggerROS.

Parameters
noderclcpp Node used when creating the log publisher.

Member Function Documentation

◆ 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_levelmoveit_studio_agent_msgs::msg::ERROR/WARN/INFO
detailsContains the information message

Reimplemented from moveit_studio::behavior::LoggerBase.


The documentation for this class was generated from the following files: