C++ YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
PublishIntState Class Reference

A state that publishes ints. More...

Inheritance diagram for PublishIntState:
Collaboration diagram for PublishIntState:

Public Member Functions

 PublishIntState ()
 Constructor for the PublishIntState class.
 
std_msgs::msg::Int32 create_int_msg (std::shared_ptr< yasmin::blackboard::Blackboard > blackboard)
 Create a new Int message.
 
- Public Member Functions inherited from yasmin_ros::PublisherState< std_msgs::msg::Int32 >
 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.
 
 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.
 
std::string execute (std::shared_ptr< yasmin::blackboard::Blackboard > blackboard) override
 Execute the publishing operation.
 
- Public Member Functions inherited from yasmin::State
 State (const std::set< std::string > &outcomes)
 Constructs a State with a set of possible outcomes.
 
StateStatus get_status () const
 Gets the current status of the state.
 
bool is_idle () const
 Checks if the state is idle.
 
bool is_running () const
 Checks if the state is currently running.
 
bool is_canceled () const
 Checks if the state has been canceled.
 
bool is_completed () const
 Checks if the state has completed execution.
 
std::string operator() (std::shared_ptr< blackboard::Blackboard > blackboard)
 Executes the state and returns the outcome.
 
virtual void cancel_state ()
 Cancels the current state execution.
 
std::set< std::string > const & get_outcomes ()
 Gets the set of possible outcomes for this state.
 
virtual std::string to_string ()
 Converts the state to a string representation.
 

Additional Inherited Members

- Protected Attributes inherited from yasmin_ros::PublisherState< std_msgs::msg::Int32 >
rclcpp::Node::SharedPtr node_
 Shared pointer to the ROS 2 node.
 
- Protected Attributes inherited from yasmin::State
std::set< std::string > outcomes
 The possible outcomes of this state.
 

Detailed Description

A state that publishes ints.

This class inherits from yasmin_ros::PublisherState and publish ints to the "count" topic.

Constructor & Destructor Documentation

◆ PublishIntState()

PublishIntState::PublishIntState ( )
inline

Constructor for the PublishIntState class.

Member Function Documentation

◆ create_int_msg()

std_msgs::msg::Int32 PublishIntState::create_int_msg ( std::shared_ptr< yasmin::blackboard::Blackboard > blackboard)
inline

Create a new Int message.

Parameters
blackboardShared pointer to the blackboard (unused in this implementation).
Returns
A new Int message.

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