A state that monitors odometry data and transitions based on a specified count.
More...
|
| PrintOdometryState (int times) |
| Constructor for the PrintOdometryState class.
|
|
std::string | monitor_handler (std::shared_ptr< yasmin::blackboard::Blackboard > blackboard, std::shared_ptr< nav_msgs::msg::Odometry > msg) |
| Handler for processing odometry data.
|
|
| MonitorState (std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue) |
| Construct a new MonitorState with specific QoS and message queue settings.
|
|
| MonitorState (std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler) |
| Construct a new MonitorState with default QoS and message queue.
|
|
| MonitorState (std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue, int timeout) |
| Construct a new MonitorState with specific QoS, message queue, and timeout.
|
|
| MonitorState (const rclcpp::Node::SharedPtr &node, std::string topic_name, std::set< std::string > outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos, int msg_queue, int timeout) |
| Construct a new MonitorState with ROS 2 node, specific QoS, message queue, and timeout.
|
|
std::string | execute (std::shared_ptr< yasmin::blackboard::Blackboard > blackboard) override |
| Execute the monitoring operation and process the first received message.
|
|
| State (std::set< std::string > outcomes) |
| Constructs a State with a set of possible outcomes.
|
|
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.
|
|
bool | is_canceled () const |
| Checks if the state has been canceled.
|
|
bool | is_running () const |
| Checks if the state is currently running.
|
|
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.
|
|
A state that monitors odometry data and transitions based on a specified count.
This class inherits from yasmin_ros::MonitorState and listens to the "odom" topic for nav_msgs::msg::Odometry messages. The state transitions once a specified number of messages has been received and processed.
std::string PrintOdometryState::monitor_handler |
( |
std::shared_ptr< yasmin::blackboard::Blackboard > | blackboard, |
|
|
std::shared_ptr< nav_msgs::msg::Odometry > | msg ) |
|
inline |
Handler for processing odometry data.
This function logs the x, y, and z positions from the odometry message. After processing, it decreases the times
counter. When the counter reaches zero, the state transitions to "outcome2"; otherwise, it remains in "outcome1".
- Parameters
-
blackboard | Shared pointer to the blackboard (unused in this implementation). |
msg | Shared pointer to the received odometry message. |
- Returns
- A string representing the outcome: "outcome1" to stay in the state, or "outcome2" to transition out of the state.