Main Content

ros2actionclient

Create ROS 2 action client

Since R2023a

Description

Use the ros2actionclient object to connect to an action server and request the execution of action goals. You can send multiple goals from an action client, get feedback on the execution progress, and cancel goals at any time.

Creation

Description

client = ros2actionclient(node,actionname,actiontype) creates a client for the ROS 2 action with name actionname and type actiontype. It attaches the action client to the ROS 2 node specified by the ros2node object, node. If the action server offering actionname is not available, the function does not display an error.

client = ros2actionclient(node,actionname,actiontype,Name=Value) sets the rest of the properties based on the additional options specified by one or more Name=Value pair arguments.

example

[client,goalMsg] = ros2actionclient(___) returns a goal message initialized with default values for the action type of the client, using any of the arguments from the previous syntaxes. You can use this message to modify the goal and send it to the action server.

example

Properties

expand all

ROS 2 action name, returned as a character vector. The action name must match one of the topics that ros2 action list outputs. For more information, see ros2.

Action type for a ROS action, returned as a string scalar or character vector. You can get the action type of an action using ros2 action type <action_name>. For more information, see ros2.

This property is read-only.

Indicator of whether the client is connected to a ROS 2 action server, returned as false or true. Use waitForserver to wait until the server is connected when setting up an action client.

Quality of Service (QoS) settings for sending goal to the action server, returned as a character vector. When you set this QoS setting as a name-value argument, you must specify it as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Lease Duration

  • Liveliness

Quality of Service (QoS) settings for getting result from the action server, returned as a character vector. When you set this QoS setting as a name-value argument, you must specify it as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Lease Duration

  • Liveliness

Quality of Service (QoS) settings for canceling goals sent to the action server, returned as a character vector. When you set this QoS setting as a name-value argument, you must specify it as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Lease Duration

  • Liveliness

Quality of Service (QoS) settings for receiving feedback from the action server, returned as a character vector. When you set this QoS setting as a name-value argument, you must specify it as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Lease Duration

  • Liveliness

Quality of Service (QoS) settings for receiving goal execution status from the action server, returned as a character vector. When you set this QoS setting as a name-value argument, you must specify it as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

Object Functions

ros2messageCreate ROS 2 message structures
waitForServerWait for ROS 2 action server to be ready for sending goals
sendGoalSend goal message to ROS 2 action server
getStatusGet execution status of specific goal sent by ROS 2 action client
getResultGet result of specific goal associated with goal handle
cancelGoalCancel specific goal sent by ROS 2 action client
cancelGoalAndWaitCancel specific goal sent by ROS 2 action client and wait for cancel response
cancelGoalsBeforeCancel goals sent by ROS 2 action client before timestamp
cancelGoalsBeforeAndWaitCancel goals sent by ROS 2 action client before timestamp and wait for cancel response
cancelAllGoalsCancel all active goals sent by ROS 2 action client
cancelAllGoalsAndWaitCancel all active goals sent by ROS 2 action client and wait for cancel response

Examples

collapse all

This example shows how to create a ROS 2 action client and execute the action. Action types must be set up beforehand with an action server running. This example uses the /fibonacci action. Follow these steps to set up the action server:

  1. Create a ROS 2 package with the action definition. For instructions on setting up a /fibonacci action, see Creating an Action.

  2. Create a ROS 2 package with the action server implementation. For more information on setting up the /fibonacci action server, see Writing an Action Server.

  3. Use the ros2genmsg function for the ROS 2 package with action definition from Step 1, and generate action messages in MATLAB®.

To run the /fibonacci action server, use this command on the ROS 2 system:

ros2 run action_tutorials_cpp fibonacci_action_server

Set Up ROS 2 Action Client

List the actions available on the network. The /fibonacci action must be on the list.

ros2 action list
/fibonacci

Get the action type for the /fibonacci action.

ros2 action type /fibonacci
action_tutorials_interfaces/Fibonacci

Create a ROS 2 node.

node = ros2node("/node_1");

Create an action client by specifying the node, action name, and action type. Set the quality of service (QoS) parameters.

[client,goalMsg] = ros2actionclient(node,"fibonacci",...
"action_tutorials_interfaces/Fibonacci", ...
CancelServiceQoS=struct(Depth=200,History="keeplast"), ...
FeedbackTopicQoS=struct(Depth=200,History="keepall"));

Wait for the action client to connect to the server.

status = waitForServer(client)
status = logical
   1

The /fibonacci action will calculate the Fibonacci sequence for a given order specified in the goal message. The goal message was returned when creating the action client and can be modified to send goals to the ROS action server. Set the order to an int32 value of 8. If the input requires a 1-D array, set it as a column vector.

goalMsg.order = int32(8);

Send Goal and Execute Action

Before sending the goal, define the callback options framework for the goal execution process. In this example, you specify a callback function to execute when the server returns a feedback response and the final result using the name-value arguments.

callbackOpts = ros2ActionSendGoalOptions(FeedbackFcn=@helperFeedbackCallback,ResultFcn=@helperResultCallback);

Send the goal to the action server using the sendGoal function. Specify the callback options. During goal execution, you see outputs from the feedback and result callbacks displayed on the MATLAB® command window.

goalHandle = sendGoal(client,goalMsg,callbackOpts);
Goal with GoalUUID 3d10ab880f960666fde5666f45f621a accepted by server, waiting for result!
Partial sequence feedback for goal 3d10ab880f960666fde5666f45f621a is 0  1  1
Partial sequence feedback for goal 3d10ab880f960666fde5666f45f621a is 0  1  1  2
Partial sequence feedback for goal 3d10ab880f960666fde5666f45f621a is 0  1  1  2  3
Partial sequence feedback for goal 3d10ab880f960666fde5666f45f621a is 0  1  1  2  3  5
Partial sequence feedback for goal 3d10ab880f960666fde5666f45f621a is 0  1  1  2  3  5  8
Partial sequence feedback for goal 3d10ab880f960666fde5666f45f621a is 0   1   1   2   3   5   8  13
Partial sequence feedback for goal 3d10ab880f960666fde5666f45f621a is 0   1   1   2   3   5   8  13  21
Full sequence result for goal 3d10ab880f960666fde5666f45f621a is 0   1   1   2   3   5   8  13  21

Get the status of goal execution.

exStatus = getStatus(client,goalHandle)
exStatus = int8
    2

Get the result using the action client and goal handle inputs. Display the result. The getResult function returns the sequence as a column vector.

resultMsg = getResult(client,goalHandle);
rosShowDetails(resultMsg)
ans = 
    '
       MessageType :  action_tutorials_interfaces/FibonacciResult
       sequence    :  [0, 1, 1, 2, 3, 5, 8, 13, 21]'

Alternatively, you can only use the goal handle as input to get the result.

resultMsg = getResult(goalHandle);
rosShowDetails(resultMsg)
ans = 
    '
       MessageType :  action_tutorials_interfaces/FibonacciResult
       sequence    :  [0, 1, 1, 2, 3, 5, 8, 13, 21]'

Helper Functions

helperFeedbackCallback defines the callback function to execute when the client receives a feedback response from the action server.

function helperFeedbackCallback(goalHandle,feedbackMsg)
    seq = feedbackMsg.partial_sequence;
    disp(['Partial sequence feedback for goal ',goalHandle.GoalUUID,' is ',num2str(seq')])
end

helperResultCallback defines the callback function to execute when the client receives the result message from the action server.

function helperResultCallback(goalHandle,wrappedResultMsg)
    seq = wrappedResultMsg.result.sequence;
    disp(['Full sequence result for goal ',goalHandle.GoalUUID,' is ',num2str(seq')])
end

This example shows how to send and cancel ROS 2 action goals. Action types must be set up beforehand with an action server running. This example uses the /fibonacci action. Follow these steps to set up the action server:

  1. Create a ROS 2 package with the action definition. For instructions on setting up a /fibonacci action, see Creating an Action.

  2. Create a ROS 2 package with the action server implementation. For more information on setting up the /fibonacci action server, see Writing an Action Server.

  3. Use the ros2genmsg function for the ROS 2 package with action definition from Step 1, and generate action messages in MATLAB®.

To run the /fibonacci action server, use this command on the ROS 2 system:

ros2 run action_tutorials_cpp fibonacci_action_server

Set Up ROS 2 Action Client

Create a ROS 2 node.

node = ros2node("/node_1");

Create an action client for /fibonacci action by specifying the node, action name, and action type. Set the quality of service (QoS) parameters.Wait for the action client to connect to the server.

[client,goalMsg] = ros2actionclient(node,"fibonacci",...
"action_tutorials_interfaces/Fibonacci", ...
CancelServiceQoS=struct(Depth=200,History="keeplast"), ...
FeedbackTopicQoS=struct(Depth=200,History="keepall"));
status = waitForServer(client)
status = logical
   1

Before sending the goal, define the callback options framework for the goal execution process. In this example, you specify a callback function to execute when the server returns a feedback response.

callbackOpts = ros2ActionSendGoalOptions(FeedbackFcn=@helperFeedbackCallback);

Send and Cancel Goals

The /fibonacci action will calculate the /fibonacci sequence for a given order specified in the goal message. The goal message was returned when creating the action client and can be modified to send goals to the ROS action server. Set the order to an int32 value of 8.

goalMsg.order = int32(8);

Create a new goal message and set the order to an int32 value of 10.

goalMsg2 = ros2message(client);
goalMsg2.order = int32(10);

Send both the goals to the action server using the sendGoal function. Specify the same callback options for both goals.

goalHandle = sendGoal(client,goalMsg,callbackOpts);
goalHandle2 = sendGoal(client,goalMsg2,callbackOpts);
Goal with GoalUUID ca8dbca2b8608a6f2add01b298f6930 accepted by server, waiting for result!
Partial sequence feedback for goal ca8dbca2b8608a6f2add01b298f6930 is 0  1  1
Goal with GoalUUID f493913f4acd2224f31145ae74bbc35 accepted by server, waiting for result!
Partial sequence feedback for goal f493913f4acd2224f31145ae74bbc35 is 0  1  1

Cancel the specific goal associated with the sequence order 8. Use the goal handle object associated with that goal as input to the cancelGoal function, and specify the cancel callback to execute once the client receives the cancel response. This function returns immediately without waiting for the cancel response to arrive.

cancelGoal(client,goalHandle,CancelFcn=@helperCancelGoalCallback)
Goal ca8dbca2b8608a6f2add01b298f6930 is cancelled with return code 0

You can wait until the cancel response arrives from the server by using the cancelGoalAndWait function. Cancel the goal associated with the sequence order of 10 and wait until the client receives the cancel response.

cancelResponse = cancelGoalAndWait(client,goalHandle2)
cancelResponse = struct with fields:
              MessageType: 'action_msgs/CancelGoalResponse'
               ERROR_NONE: 0
           ERROR_REJECTED: 1
    ERROR_UNKNOWN_GOAL_ID: 2
    ERROR_GOAL_TERMINATED: 3
              return_code: 0
          goals_canceling: [1×1 struct]

Cancel Goals Before Timestamp

Send the goal message with sequence order 10. Note the timestamp in a ROS 2 message by using the ros2time function.

goalHandle = sendGoal(client,goalMsg2,callbackOpts);
timeStampMsg = ros2time(node,"now");
Goal with GoalUUID d8268c566b234e8784f0f1a8ec12b2 accepted by server, waiting for result!
Partial sequence feedback for goal d8268c566b234e8784f0f1a8ec12b2 is 0  1  1

Then, send a second goal message with sequence order 8. Note the timestamp.

goalHandle2 = sendGoal(client,goalMsg,callbackOpts);
timeStampMsg2 = ros2time(node,"now");
Goal with GoalUUID 9585bff2ba44bf60daa630a952b458be accepted by server, waiting for result!
Partial sequence feedback for goal 9585bff2ba44bf60daa630a952b458be is 0  1  1

Cancel the goal sent before the first time stamp using cancelGoalsBefore function.

cancelGoalsBefore(client,timeStampMsg,CancelFcn=@helperCancelGoalsCallback)
Goals cancelled with return code 0

Use the cancelGoalsBeforeAndWait function to cancel the goal sent before second time stamp and wait for the cancel response.

cancelResponse = cancelGoalsBeforeAndWait(client,timeStampMsg2)
cancelResponse = struct with fields:
              MessageType: 'action_msgs/CancelGoalResponse'
               ERROR_NONE: 0
           ERROR_REJECTED: 1
    ERROR_UNKNOWN_GOAL_ID: 2
    ERROR_GOAL_TERMINATED: 3
              return_code: 0
          goals_canceling: [1×1 struct]

Cancel All Goals

Cancel all the active goals that the client sent.

goalHandle = sendGoal(client,goalMsg,callbackOpts);
cancelAllGoals(client,CancelFcn=@helperCancelGoalsCallback);
Goals cancelled with return code 0

Cancel all the active goals that the client sent and wait for cancel response.

goalHandle2 = sendGoal(client,goalMsg2,callbackOpts);
cancelResponse = cancelAllGoalsAndWait(client)
cancelResponse = struct with fields:
              MessageType: 'action_msgs/CancelGoalResponse'
               ERROR_NONE: 0
           ERROR_REJECTED: 1
    ERROR_UNKNOWN_GOAL_ID: 2
    ERROR_GOAL_TERMINATED: 3
              return_code: 0
          goals_canceling: [1×1 struct]

Helper Functions

helperFeedbackCallback defines the callback function to execute when the client receives a feedback response from the action server.

function helperFeedbackCallback(goalHandle,feedbackMsg)
seq = feedbackMsg.partial_sequence;
disp(['Partial sequence feedback for goal ',goalHandle.GoalUUID,' is ',num2str(seq')])
end

helperCancelGoalCallback defines the callback function to execute when the client receives a cancel response after canceling a specific goal.

function helperCancelGoalCallback(goalHandle,cancelMsg)
code = cancelMsg.return_code;
disp(['Goal ',goalHandle.GoalUUID,' is cancelled with return code ',num2str(code)])
end

helperCancelGoalsCallback defines the callback function to execute when the client receives a cancel response after canceling a set of goals.

function helperCancelGoalsCallback(cancelMsg)
code = cancelMsg.return_code;
disp(['Goals cancelled with return code ',num2str(code)])
end

Limitations

  • If a ROS 2 action server and the action clients connected to it are running in the same MATLAB® session, the server cannot process cancel requests from the client.

Extended Capabilities

Version History

Introduced in R2023a