rclpy.action.client module

class rclpy.action.client.ActionClient(node, action_type, action_name, *, callback_group=None, goal_service_qos_profile=rclpy.qos.qos_profile_services_default, result_service_qos_profile=rclpy.qos.qos_profile_services_default, cancel_service_qos_profile=rclpy.qos.qos_profile_services_default, feedback_sub_qos_profile=rclpy.qos.QoSProfile, status_sub_qos_profile=rclpy.qos.qos_profile_action_status_default)

Bases: Waitable

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)

Add entities to wait set.

destroy()

Destroy the underlying action client handle.

async execute(taken_data)

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()

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

is_ready(wait_set)

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

send_goal(goal, **kwargs)

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, feedback_callback=None, goal_uuid=None)

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()

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()

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

wait_for_server(timeout_sec=None)

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, goal_id, goal_response)

Bases: object

Goal handle for working with Action Clients.

property accepted
cancel_goal()

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()

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()

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()

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
property stamp
property status