Python YASMIN (Yet Another State MachINe)
Loading...
Searching...
No Matches
yasmin_ros.action_state.ActionState Class Reference
Inheritance diagram for yasmin_ros.action_state.ActionState:
Collaboration diagram for yasmin_ros.action_state.ActionState:

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, CallbackGroup callback_group=None, Node node=None, float wait_timeout=None, float response_timeout=None, int maximum_retry=3)
 
None cancel_state (self)
 
str execute (self, Blackboard blackboard)
 

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
 Shared pointer to the action result.
 
GoalStatus _action_status = None
 Status of the action execution.
 
ClientGoalHandle _goal_handle = None
 Handle for the current goal.
 
RLock _goal_handle_lock = RLock()
 Lock to manage access to the goal handle.
 
Callable[[Blackboard], Any] _create_goal_handler = create_goal_handler
 Handler function for creating goals.
 
Callable[[Blackboard, Any], str] _result_handler = result_handler
 Handler function for processing results.
 
Callable[[Blackboard, Any], None] _feedback_handler = feedback_handler
 Handler function for processing feedback.
 
float _wait_timeout = wait_timeout
 Maximum time to wait for the action server.
 
float _response_timeout = response_timeout
 Timeout for the action response.
 
int _maximum_retry = maximum_retry
 Maximum number of retries.
 
Node _node = node
 Shared pointer to the ROS 2 node.
 
str _action_name = action_name
 Name of the action to communicate with.
 
Type _action_type = action_type
 Action type for caching.
 
ActionClient _action_client
 Shared pointer to the action client (reused from cache if available).
 
 _goal_response_callback
 
 _get_result_callback = self._goal_handle.get_result_async()
 

Detailed Description

A state class for handling ROS 2 action client operations.

This class encapsulates the behavior of a ROS 2 action client within a YASMIN
state. It allows the creation and management of goals, feedback, and results
associated with an action server.

Attributes:
    _node (Node): Shared pointer to the ROS 2 node.
    _action_name (str): Name of the action to communicate with.
    _action_client (ActionClient): Shared pointer to the action client.
    _action_done_event (Event): Event used to wait for action completion.
    _action_result (Any): Shared pointer to the action result.
    _action_status (GoalStatus): Status of the action execution.
    _goal_handle (ClientGoalHandle): Handle for the current goal.
    _goal_handle_lock (RLock): Lock to manage access to the goal handle.
    _create_goal_handler (Callable[[Blackboard], Any]): Handler function for creating goals.
    _result_handler (Callable[[Blackboard, Any], str]): Handler function for processing results.
    _feedback_handler (Callable[[Blackboard, Any], None]): Handler function for processing feedback.
    _wait_timeout (float): Maximum time to wait for the action server.
    _response_timeout (float): Timeout for the action response.
    _maximum_retry (int): Maximum number of retries.

Constructor & Destructor Documentation

◆ __init__()

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,
CallbackGroup callback_group = None,
Node node = None,
float wait_timeout = None,
float response_timeout = None,
int maximum_retry = 3 )
Construct an ActionState with a specific action name and goal handler.

This constructor initializes the action state with a specified action name,
goal handler, and optional timeout.

Args:
    action_type (Type): The type of the action to be executed.
    action_name (str): The name of the action to communicate with.
    create_goal_handler (Callable[[Blackboard], Any]): A function that creates a goal for the action.
    outcomes (Set[str], optional): A set of possible outcomes for this action state.
    result_handler (Callable[[Blackboard, Any], str], optional): A function to handle the result of the action.
    feedback_handler (Callable[[Blackboard, Any], None], optional): A function to handle feedback from the action.
    callback_group (CallbackGroup, optional): The callback group for the action client.
    node (Node, optional): The ROS 2 node to use. If None, uses the default YasminNode.
    wait_timeout (float, optional): The maximum time to wait for the action server. Default is None (wait indefinitely).
    response_timeout (float, optional): The maximum time to wait for the action response. Default is None (wait indefinitely).
    maximum_retry (int, optional): Maximum retries of the action if it returns timeout. Default is 3.

Raises:
    ValueError: If create_goal_handler is None.

Member Function Documentation

◆ _get_result_callback()

None yasmin_ros.action_state.ActionState._get_result_callback ( self,
Future future )
protected
Callback for handling the result of the executed action.

This method sets the action result and status, and signals that the action is done.

Args:
    future: The future object representing the result of the action execution.

◆ _goal_response_callback()

None yasmin_ros.action_state.ActionState._goal_response_callback ( self,
Future future )
protected
Callback for handling the goal response.

This method retrieves the goal handle and sets up the result callback.

Args:
    future: The future object representing the result of the goal sending operation.

◆ cancel_state()

None yasmin_ros.action_state.ActionState.cancel_state ( self)
Cancel the current action state.

This function cancels the goal sent to the action server, if it exists.

◆ execute()

str yasmin_ros.action_state.ActionState.execute ( self,
Blackboard blackboard )
Execute the action and return the outcome.

This function creates a goal using the provided goal handler, sends the
goal to the action server, and waits for the result or feedback.

Args:
    blackboard (Blackboard): A shared pointer to the blackboard used for communication.

Returns:
    str: A string representing the outcome of the action execution.
        Possible outcomes include SUCCEED, ABORT, CANCEL, or TIMEOUT.

Member Data Documentation

◆ _action_client

ActionClient yasmin_ros.action_state.ActionState._action_client
protected
Initial value:
= ROSClientsCache.get_or_create_action_client(
self._node,
action_type,
action_name,
callback_group,
)

Shared pointer to the action client (reused from cache if available).

◆ _action_done_event

Event yasmin_ros.action_state.ActionState._action_done_event = Event()
protected

Event used to wait for action completion.

◆ _action_name

str yasmin_ros.action_state.ActionState._action_name = action_name
protected

Name of the action to communicate with.

◆ _action_result

yasmin_ros.action_state.ActionState._action_result = None
protected

Shared pointer to the action result.

◆ _action_status

GoalStatus yasmin_ros.action_state.ActionState._action_status = None
protected

Status of the action execution.

◆ _action_type

Type yasmin_ros.action_state.ActionState._action_type = action_type
protected

Action type for caching.

◆ _create_goal_handler

Callable[[Blackboard], Any] yasmin_ros.action_state.ActionState._create_goal_handler = create_goal_handler
protected

Handler function for creating goals.

◆ _feedback_handler

Callable[[Blackboard, Any], None] yasmin_ros.action_state.ActionState._feedback_handler = feedback_handler
protected

Handler function for processing feedback.

◆ _get_result_callback

yasmin_ros.action_state.ActionState._get_result_callback = self._goal_handle.get_result_async()
protected

◆ _goal_handle

ClientGoalHandle yasmin_ros.action_state.ActionState._goal_handle = None
protected

Handle for the current goal.

◆ _goal_handle_lock

RLock yasmin_ros.action_state.ActionState._goal_handle_lock = RLock()
protected

Lock to manage access to the goal handle.

◆ _goal_response_callback

yasmin_ros.action_state.ActionState._goal_response_callback
protected
Initial value:
= self._action_client.send_goal_async(
goal, feedback_callback=feedback_handler
)

◆ _maximum_retry

int yasmin_ros.action_state.ActionState._maximum_retry = maximum_retry
protected

Maximum number of retries.

◆ _node

Node yasmin_ros.action_state.ActionState._node = node
protected

Shared pointer to the ROS 2 node.

◆ _response_timeout

yasmin_ros.action_state.ActionState._response_timeout = response_timeout
protected

Timeout for the action response.

◆ _result_handler

Callable[[Blackboard, Any], str] yasmin_ros.action_state.ActionState._result_handler = result_handler
protected

Handler function for processing results.

◆ _wait_timeout

yasmin_ros.action_state.ActionState._wait_timeout = wait_timeout
protected

Maximum time to wait for the action server.


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