yasmin_demos.monitor_demo module
- class yasmin_demos.monitor_demo.PrintOdometryState(*args: Any, **kwargs: Any)
Bases:
MonitorState
MonitorState subclass to handle Odometry messages.
This state monitors Odometry messages from the specified ROS topic, logging them and transitioning based on the number of messages received.
- Attributes:
- times (int): The number of messages to monitor before transitioning
to the next outcome.
- Parameters:
- times (int): The initial count of how many Odometry messages to
process before changing state.
- Methods:
- monitor_handler(blackboard: Blackboard, msg: Odometry) -> str:
Handles incoming Odometry messages, logging the message and returning the appropriate outcome based on the remaining count.
- monitor_handler(blackboard: yasmin.Blackboard, msg: nav_msgs.msg.Odometry) str
Handles incoming Odometry messages.
This method is called whenever a new Odometry message is received. It logs the message, decrements the count of messages to process, and determines the next state outcome.
- Parameters:
blackboard (Blackboard): The shared data storage for states. msg (Odometry): The incoming Odometry message.
- Returns:
- str: The next state outcome, either “outcome1” to continue
monitoring or “outcome2” to transition to the next state.
- Exceptions:
None
- yasmin_demos.monitor_demo.main()
Main function to initialize and run the ROS 2 state machine.
This function initializes ROS 2, sets up logging, creates a finite state machine (FSM), adds states to the FSM, and executes the FSM. It handles cleanup and shutdown of ROS 2 gracefully.
- Exceptions:
- KeyboardInterrupt: Caught to allow graceful cancellation of the
state machine during execution.