Template Class PublisherState

Inheritance Relationships

Base Type

  • public yasmin::State

Class Documentation

template<typename MsgT>
class PublisherState : public yasmin::State

Template class to publish ROS 2 messages.

This class provides functionality to publish to a ROS 2 topic of type MsgT and create a custom messages.

Template Parameters:

MsgT – The message type of the topic to publish to.

Public Functions

inline PublisherState(std::string topic_name, CreateMessageHandler create_message_handler, rclcpp::QoS qos = 10, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)

Construct a new PublisherState with ROS 2 node and specific QoS.

Parameters:
  • topic_name – The name of the topic to monitor.

  • create_message_handler – A callback handler to create messages.

  • qos – Quality of Service settings for the topic.

inline PublisherState(const rclcpp::Node::SharedPtr &node, std::string topic_name, CreateMessageHandler create_message_handler, rclcpp::QoS qos = 10, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr)

Construct a new PublisherState with ROS 2 node and specific QoS.

Parameters:
  • node – The ROS 2 node.

  • topic_name – The name of the topic to monitor.

  • create_message_handler – A callback handler to create messages.

  • qos – Quality of Service settings for the topic.

inline std::string execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard) override

Execute the publishing operation.

Parameters:

blackboard – A shared pointer to the blackboard for data storage.

Returns:

A string outcome indicating the result of the monitoring operation.