Python YASMIN (Yet Another State MachINe)
|
Public Member Functions | |
None | __init__ (self, Type action_type, str action_name, Callable create_goal_handler, Set[str] outcomes=None, Callable result_handler=None, Callable feedback_handler=None, Node node=None, float timeout=None) |
None | cancel_state (self) |
str | execute (self, Blackboard blackboard) |
Public Member Functions inherited from yasmin.state.State | |
str | __call__ (self, Blackboard blackboard=None) |
str | __str__ (self) |
bool | is_canceled (self) |
bool | is_running (self) |
Set[str] | get_outcomes (self) |
Protected Member Functions | |
None | _goal_response_callback (self, Future future) |
None | _get_result_callback (self, Future future) |
Protected Attributes | |
Event | _action_done_event = Event() |
Event used to wait for action completion. | |
Any | _action_result = None |
The result returned by the action server. | |
GoalStatus | _action_status = None |
The status of the action execution. | |
ClientGoalHandle | _goal_handle = None |
Handle for the goal sent to the action server. | |
RLock | _goal_handle_lock = RLock() |
Lock to manage access to the goal handle. | |
Callable[[Blackboard], Any] | _create_goal_handler = create_goal_handler |
Function that creates the goal to send. | |
Callable[[Blackboard, Any], str] | _result_handler = result_handler |
Function to handle the result from the action server. | |
Callable[[Blackboard, Any], None] | _feedback_handler = feedback_handler |
Function to handle feedback from the action server. | |
float | _timeout = timeout |
Timeout duration for waiting for the action server. | |
Node | _node = node |
The ROS 2 node instance used to communicate with the action server. | |
str | _action_name = action_name |
The name of the action to be performed. | |
ActionClient | _action_client |
The action client used to send goals. | |
_goal_response_callback | |
_get_result_callback | |
Protected Attributes inherited from yasmin.state.State | |
Set | _outcomes = set() |
A set of valid outcomes for this state. | |
bool | _running = False |
A flag indicating whether the state is currently running. | |
bool | _canceled = False |
A flag indicating whether the state has been canceled. | |
Represents a state that interacts with a ROS 2 action server. This class encapsulates the functionality needed to manage the sending and receiving of goals to and from an action server. Attributes: _node (Node): The ROS 2 node instance used to communicate with the action server. _action_name (str): The name of the action to be performed. _action_client (ActionClient): The action client used to send goals. _action_done_event (Event): Event used to wait for action completion. _action_result (Any): The result returned by the action server. _action_status (GoalStatus): The status of the action execution. _goal_handle (ClientGoalHandle): Handle for the goal sent to the action server. _goal_handle_lock (RLock): Lock to manage access to the goal handle. _create_goal_handler (Callable[[Blackboard], Any]): Function that creates the goal to send. _result_handler (Callable[[Blackboard, Any], str]): Function to handle the result from the action server. _feedback_handler (Callable[[Blackboard, Any], None]): Function to handle feedback from the action server. _timeout (float): Timeout duration for waiting for the action server.
None yasmin_ros.action_state.ActionState.__init__ | ( | self, | |
Type | action_type, | ||
str | action_name, | ||
Callable | create_goal_handler, | ||
Set[str] | outcomes = None, | ||
Callable | result_handler = None, | ||
Callable | feedback_handler = None, | ||
Node | node = None, | ||
float | timeout = None ) |
Initializes the ActionState instance. This constructor sets up the action client and prepares to handle goals. Parameters: action_type (Type): The type of the action to be executed. action_name (str): The name of the action to be executed. create_goal_handler (Callable[[Blackboard], Any])): A function that generates the goal. outcomes (Set[str], optional): Additional outcomes that this state can return. result_handler (Callable[[Blackboard, Any], str], optional): A function to process the result of the action. feedback_handler (Callable[[Blackboard, Any], None], optional): A function to process feedback from the action. node (Node, optional): The ROS 2 node to use. If None, uses the default YasminNode. timeout (float, optional): Timeout duration for waiting for the action server. Raises: ValueError: If create_goal_handler is None.
Reimplemented from yasmin.state.State.
Reimplemented in yasmin_demos.action_client_demo.FibonacciState, and yasmin_demos.nav_demo.Nav2State.
|
protected |
Callback to handle the result of the executed action. This method sets the action result and status, and signals that the action is done. Parameters: future: The future object representing the result of the action execution.
|
protected |
Callback to handle the response from sending a goal. This method retrieves the goal handle and sets up the result callback. Parameters: future: The future object representing the result of the goal sending operation.
None yasmin_ros.action_state.ActionState.cancel_state | ( | self | ) |
Cancels the current action state. This method cancels the goal sent to the action server, if it exists.
Reimplemented from yasmin.state.State.
str yasmin_ros.action_state.ActionState.execute | ( | self, | |
Blackboard | blackboard ) |
Executes the action state by sending a goal to the action server. This method waits for the action server to be available, sends the goal, and waits for the action to complete, handling feedback and results. Parameters: blackboard (Blackboard): The blackboard instance used for state management. Returns: str: The outcome of the action execution (e.g., SUCCEED, ABORT, CANCEL, TIMEOUT). Raises: Exception: Raises an exception if any error occurs during action execution.
Reimplemented from yasmin.state.State.
|
protected |
The action client used to send goals.
|
protected |
Event used to wait for action completion.
|
protected |
The name of the action to be performed.
|
protected |
The result returned by the action server.
|
protected |
The status of the action execution.
|
protected |
Function that creates the goal to send.
|
protected |
Function to handle feedback from the action server.
|
protected |
|
protected |
Handle for the goal sent to the action server.
|
protected |
Lock to manage access to the goal handle.
|
protected |
|
protected |
The ROS 2 node instance used to communicate with the action server.
|
protected |
Function to handle the result from the action server.
|
protected |
Timeout duration for waiting for the action server.