Actions

Action Client

class rclpy.action.client.ActionClient(node: Node, action_type: Type[Action[GoalT, ResultT, FeedbackT]], action_name: str, *, callback_group: CallbackGroup | None = None, goal_service_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, result_service_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, cancel_service_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, feedback_sub_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.QoSProfile, status_sub_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_action_status_default)

ROS Action client.

Create an ActionClient.

Parameters:
  • node – The ROS node to add the action client to.

  • action_type – Type of the action.

  • action_name – Name of the action. Used as part of the underlying topic and service names.

  • callback_group – Callback group to add the action client to. If None, then the node’s default callback group is used.

  • goal_service_qos_profile – QoS profile for the goal service.

  • result_service_qos_profile – QoS profile for the result service.

  • cancel_service_qos_profile – QoS profile for the cancel service.

  • feedback_sub_qos_profile – QoS profile for the feedback subscriber.

  • status_sub_qos_profile – QoS profile for the status subscriber.

add_to_wait_set(wait_set: rpyutils.import_c_library.WaitSet) None

Add entities to wait set.

destroy() None

Destroy the underlying action client handle.

async execute(taken_data: ClientGoalHandleDict[ResultT, FeedbackT]) None

Execute work after data has been taken from a ready wait set.

This will set results for Future objects for any received service responses and call any user-defined callbacks (e.g. feedback).

get_num_entities() NumberOfEntities

Return number of each type of entity used in the wait set.

is_ready(wait_set: rpyutils.import_c_library.WaitSet) bool

Return True if one or more entities are ready in the wait set.

send_goal(goal: GoalT, **kwargs: Unpack[SendGoalKWargs]) GetResultServiceResponse[ResultT] | None

Send a goal and wait for the result.

Do not call this method in a callback or a deadlock may occur.

See send_goal_async() for more info about keyword arguments.

Unlike send_goal_async(), this method returns the final result of the action (not a goal handle).

Parameters:

goal (action_type.Goal) – The goal request.

Returns:

The result response.

Return type:

action_type.Result

Raises:

TypeError if the type of the passed goal isn’t an instance of the Goal type of the provided action when the service was constructed.

send_goal_async(goal: GoalT, feedback_callback: Callable[[FeedbackT], None] | None = None, goal_uuid: unique_identifier_msgs.msg.UUID | None = None) Future[ClientGoalHandle[GoalT, ResultT, FeedbackT]]

Send a goal and asynchronously get the result.

The result of the returned Future is set to a ClientGoalHandle when receipt of the goal is acknowledged by an action server.

Parameters:
  • goal (action_type.Goal) – The goal request.

  • feedback_callback (function) – Callback function for feedback associated with the goal.

  • goal_uuid – Universally unique identifier for the goal. If None, then a random UUID is generated.

Type:

unique_identifier_msgs.UUID

Returns:

a Future instance to a goal handle that completes when the goal request has been accepted or rejected.

Return type:

rclpy.task.Future instance

Raises:

TypeError if the type of the passed goal isn’t an instance of the Goal type of the provided action when the service was constructed.

server_is_ready() bool

Check if there is an action server ready to process requests from this client.

Returns:

True if an action server is ready, False otherwise.

take_data() ClientGoalHandleDict[ResultT, FeedbackT]

Take stuff from lower level so the wait set doesn’t immediately wake again.

wait_for_server(timeout_sec: float | None = None) bool

Wait for an action sever to be ready.

Returns as soon as an action server is ready for this client.

Parameters:

timeout_sec – Number of seconds to wait until an action server is available. If None, then wait indefinitely.

Returns:

True if an action server is available, False if the timeout is exceeded.

class rclpy.action.client.ClientGoalHandle(action_client: ActionClient[GoalT, ResultT, FeedbackT], goal_id: unique_identifier_msgs.msg.UUID, goal_response: SendGoalServiceResponse)

Goal handle for working with Action Clients.

property accepted: bool
cancel_goal() action_msgs.srv.CancelGoal.Response | None

Send a cancel request for the goal and wait for the response.

Do not call this method in a callback or a deadlock may occur.

Returns:

The cancel response.

cancel_goal_async() Future[action_msgs.srv.CancelGoal.Response]

Asynchronous request for the goal be canceled.

Returns:

a Future instance that completes when the server responds.

Return type:

rclpy.task.Future instance

get_result() GetResultServiceResponse[ResultT] | None

Request the result for the goal and wait for the response.

Do not call this method in a callback or a deadlock may occur.

Returns:

The result response.

get_result_async() Future[GetResultServiceResponse[ResultT]]

Asynchronously request the goal result.

Returns:

a Future instance that completes when the result is ready.

Return type:

rclpy.task.Future instance

property goal_id: unique_identifier_msgs.msg.UUID
property stamp: builtin_interfaces.msg.Time
property status: int
class rclpy.action.client.SendGoalKWargs
feedback_callback: Callable[[FeedbackT], None] | None
goal_uuid: unique_identifier_msgs.msg.UUID | None

Action Server

class rclpy.action.server.ActionServer(node: Node, action_type: ~typing.Type[~rclpy.type_support.Action[~rclpy.type_support.GoalT, ~rclpy.type_support.ResultT, ~rclpy.type_support.FeedbackT]], action_name: str, execute_callback: ~typing.Callable[[~rclpy.action.server.ServerGoalHandle[~rclpy.type_support.GoalT, ~rclpy.type_support.ResultT, ~rclpy.type_support.FeedbackT]], ~rclpy.type_support.ResultT], *, callback_group: Optional[CallbackGroup] = None, goal_callback: ~typing.Callable[[action_msgs.srv._cancel_goal.CancelGoal.Request], ~rclpy.action.server.GoalResponse] = <function default_goal_callback>, handle_accepted_callback: ~typing.Callable[[~rclpy.action.server.ServerGoalHandle[~rclpy.type_support.GoalT, ~rclpy.type_support.ResultT, ~rclpy.type_support.FeedbackT]], None] = <function default_handle_accepted_callback>, cancel_callback: ~typing.Callable[[action_msgs.srv._cancel_goal.CancelGoal.Request], ~rclpy.action.server.CancelResponse] = <function default_cancel_callback>, goal_service_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, result_service_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, cancel_service_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, feedback_pub_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.QoSProfile, status_pub_qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_action_status_default, result_timeout: int = 10)

ROS Action server.

Create an ActionServer.

Parameters:
  • node – The ROS node to add the action server to.

  • action_type – Type of the action.

  • action_name – Name of the action. Used as part of the underlying topic and service names.

  • execute_callback – Callback function for processing accepted goals. This is called if when ServerGoalHandle.execute() is called for a goal handle that is being tracked by this action server.

  • callback_group – Callback group to add the action server to. If None, then the node’s default callback group is used.

  • goal_callback – Callback function for handling new goal requests.

  • handle_accepted_callback – Callback function for handling newly accepted goals. Passes an instance of ServerGoalHandle as an argument.

  • cancel_callback – Callback function for handling cancel requests.

  • goal_service_qos_profile – QoS profile for the goal service.

  • result_service_qos_profile – QoS profile for the result service.

  • cancel_service_qos_profile – QoS profile for the cancel service.

  • feedback_pub_qos_profile – QoS profile for the feedback publisher.

  • status_pub_qos_profile – QoS profile for the status publisher.

  • result_timeout – How long in seconds a result is kept by the server after a goal reaches a terminal state.

property action_type: Type[Action[GoalT, ResultT, FeedbackT]]
add_to_wait_set(wait_set: rpyutils.import_c_library.WaitSet) None

Add entities to wait set.

destroy() None

Destroy the underlying action server handle.

async execute(taken_data: ServerGoalHandleDict[GoalT]) None

Execute work after data has been taken from a ready wait set.

This will set results for Future objects for any received service responses and call any user-defined callbacks (e.g. feedback).

get_num_entities() NumberOfEntities

Return number of each type of entity used in the wait set.

is_ready(wait_set: rpyutils.import_c_library.WaitSet) bool

Return True if one or more entities are ready in the wait set.

notify_execute(goal_handle: ServerGoalHandle[GoalT, ResultT, FeedbackT], execute_callback: Callable[[ServerGoalHandle[GoalT, ResultT, FeedbackT]], ResultT] | None) None
notify_goal_done() None
register_cancel_callback(cancel_callback: Callable[[action_msgs.srv._cancel_goal.CancelGoal.Request], CancelResponse] | None) None

Register a callback for handling cancel requests.

The purpose of the cancel callback is to decide if a request to cancel an on-going (or queued) goal should be accepted or rejected. The callback should take one parameter containing the cancel request and must return a CancelResponse value.

There can only be one cancel callback per ActionServer, therefore calling this function will replace any previously registered callback.

Parameters:

cancel_callback – Callback function, if None, then unregisters any previously registered callback.

register_execute_callback(execute_callback: Callable[[ServerGoalHandle[GoalT, ResultT, FeedbackT]], ResultT]) None

Register a callback for executing action goals.

The purpose of the execute callback is to execute the action goal and return a result when finished.

The callback should take one parameter containing goal request and must return a result instance (i.e. action_type.Result).

There can only be one execute callback per ActionServer, therefore calling this function will replace any previously registered callback.

Parameters:

execute_callback – Callback function. Must not be None.

register_goal_callback(goal_callback: Callable[[SendGoalServiceRequest[GoalT]], GoalResponse] | None) None

Register a callback for handling new goal requests.

The purpose of the goal callback is to decide if a new goal should be accepted or rejected. The callback should take the goal request message as a parameter and must return a GoalResponse value.

There can only be one goal callback per ActionServer, therefore calling this function will replace any previously registered callback.

Parameters:

goal_callback – Callback function, if None, then unregisters any previously registered callback.

register_handle_accepted_callback(handle_accepted_callback: Callable[[ServerGoalHandle[GoalT, ResultT, FeedbackT]], None] | None) None

Register a callback for handling newly accepted goals.

The provided function is called whenever a new goal has been accepted by this action server. The function should expect an instance of ServerGoalHandle as an argument, which represents a handle to the goal that was accepted. The goal handle can be used to interact with the goal, e.g. publish feedback, update the status, or execute a deferred goal.

There can only be one handle accepted callback per ActionServer, therefore calling this function will replace any previously registered callback.

Parameters:

goal_callback – Callback function, if None, then unregisters any previously registered callback.

take_data() ServerGoalHandleDict[GoalT]

Take stuff from lower level so the wait set doesn’t immediately wake again.

class rclpy.action.server.CancelResponse(value, names=<not given>, *values, module=None, qualname=None, type=None, start=1, boundary=None)

Possible cancel responses.

ACCEPT = 2
REJECT = 1
class rclpy.action.server.GoalResponse(value, names=<not given>, *values, module=None, qualname=None, type=None, start=1, boundary=None)

Possible goal responses.

ACCEPT = 2
REJECT = 1
class rclpy.action.server.ServerGoalHandle(action_server: ActionServer[GoalT, ResultT, FeedbackT], goal_info: action_msgs.msg.GoalInfo, goal_request: GoalT)

Goal handle for working with Action Servers.

Accept a new goal with the given action server.

Instances of this class should only be constructed in the ActionServer class. Instances for accepted goals will be passed to the user-defined goal execution functions.

If the goal fails to be accepted, then a RuntimeError is raised.

Parameters:
  • action_server – The ActionServer to accept the goal.

  • goal_info – GoalInfo message.

  • goal_request – The user defined goal request message from an ActionClient.

abort() None
canceled() None
destroy() None
execute(execute_callback: Callable[[ServerGoalHandle[GoalT, ResultT, FeedbackT]], ResultT] | None = None) None
property goal_id: unique_identifier_msgs.msg.UUID
property is_active: bool
property is_cancel_requested: bool
publish_feedback(feedback: FeedbackMessage[FeedbackT]) None
property request: GoalT
property status: int
succeed() None
rclpy.action.server.default_cancel_callback(cancel_request: action_msgs.srv._cancel_goal.CancelGoal.Request) Literal[CancelResponse.REJECT]

No cancellations.

rclpy.action.server.default_goal_callback(goal_request: SendGoalServiceRequest[Any]) Literal[GoalResponse.ACCEPT]

Accept all goals.

rclpy.action.server.default_handle_accepted_callback(goal_handle: ServerGoalHandle[Any, Any, Any]) None

Execute the goal.