A state that monitors odometry data and transitions based on a specified count.
More...
|
| | PrintOdometryState () |
| | Constructor for the PrintOdometryState class.
|
| |
| std::string | monitor_handler (yasmin::Blackboard::SharedPtr blackboard, nav_msgs::msg::Odometry::SharedPtr msg) |
| | Handler for processing odometry data.
|
| |
| | MonitorState (const std::string &topic_name, const yasmin::Outcomes &outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos=10, int msg_queue=10, int timeout=-1, int maximum_retry=3) |
| | Shared pointer type for MonitorState.
|
| |
| | MonitorState (const std::string &topic_name, const yasmin::Outcomes &outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos=10, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr, int msg_queue=10, int timeout=-1, int maximum_retry=3) |
| | Construct a new MonitorState with specific QoS, message queue, and timeout.
|
| |
| | MonitorState (const rclcpp::Node::SharedPtr &node, const std::string &topic_name, const yasmin::Outcomes &outcomes, MonitorHandler monitor_handler, rclcpp::QoS qos=10, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr, int msg_queue=10, int timeout=-1, int maximum_retry=3) |
| | Construct a new MonitorState with ROS 2 node, specific QoS, message queue, and timeout.
|
| |
| std::string | execute (yasmin::Blackboard::SharedPtr blackboard) override |
| | Execute the monitoring operation and process the first received message.
|
| |
| void | cancel_state () override |
| | Cancel the current monitor state.
|
| |
| | State (const Outcomes &outcomes) |
| | Shared pointer type for State.
|
| |
| virtual | ~State ()=default |
| | Virtual destructor for proper polymorphic destruction.
|
| |
| bool | is_idle () const noexcept |
| | Checks if the state is idle.
|
| |
| bool | is_running () const noexcept |
| | Checks if the state is currently running.
|
| |
| bool | is_canceled () const noexcept |
| | Checks if the state has been canceled.
|
| |
| bool | is_completed () const noexcept |
| | Checks if the state has completed execution.
|
| |
| std::string | operator() (Blackboard::SharedPtr blackboard) |
| | Executes the state and returns the outcome.
|
| |
| Outcomes const & | get_outcomes () const noexcept |
| | Gets the set of possible outcomes for this state.
|
| |
| virtual std::string | to_string () const |
| | 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.
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.