16#ifndef YASMIN_ROS__PUBLISHER_STATE_HPP
17#define YASMIN_ROS__PUBLISHER_STATE_HPP
23#include "rclcpp/rclcpp.hpp"
46 std::function<MsgT(std::shared_ptr<yasmin::blackboard::Blackboard>)>;
59 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr)
75 rclcpp::CallbackGroup::SharedPtr callback_group =
nullptr)
79 if (node ==
nullptr) {
90 throw std::invalid_argument(
"create_message_handler is needed");
101 execute(std::shared_ptr<yasmin::blackboard::Blackboard> blackboard)
override {
105 this->
pub->publish(msg);
114 std::shared_ptr<rclcpp::Publisher<MsgT>>
Represents a state in a state machine.
Definition state.hpp:53
State(const std::set< std::string > &outcomes)
Constructs a State with a set of possible outcomes.
Definition state.cpp:27
std::shared_ptr< rclcpp::Publisher< MsgT > > pub
Definition publisher_state.hpp:115
std::string topic_name
Definition publisher_state.hpp:117
PublisherState(const 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.
Definition publisher_state.hpp:56
CreateMessageHandler create_message_handler
Definition publisher_state.hpp:119
rclcpp::Node::SharedPtr node_
Shared pointer to the ROS 2 node.
Definition publisher_state.hpp:111
std::function< MsgT(std::shared_ptr< yasmin::blackboard::Blackboard >)> CreateMessageHandler
Function type for creating messages for topic.
Definition publisher_state.hpp:45
std::string execute(std::shared_ptr< yasmin::blackboard::Blackboard > blackboard) override
Execute the publishing operation.
Definition publisher_state.hpp:101
PublisherState(const rclcpp::Node::SharedPtr &node, const 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.
Definition publisher_state.hpp:71
static rclcpp::Publisher< MsgT >::SharedPtr get_or_create_publisher(rclcpp::Node::SharedPtr node, const std::string &topic_name, const rclcpp::QoS &qos_profile=rclcpp::QoS(10), rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
Get an existing publisher from the cache or create a new one.
Definition ros_clients_cache.hpp:174
static std::shared_ptr< YasminNode > get_instance()
Provides access to the singleton instance of YasminNode.
Definition yasmin_node.hpp:73
#define YASMIN_LOG_DEBUG(text,...)
Definition logs.hpp:174
constexpr char SUCCEED[]
Constant representing a successful action outcome.
Definition basic_outcomes.hpp:39
Definition action_state.hpp:37