Main Content

ActionClientGoalHandle

Goal handle object for ROS 2 action client goals

Since R2023a

Description

Use ActionClientGoalHandle object to inspect and interact with goals sent by ROS 2 action clients. Each goal has its unique goal handle associated with the action client that sent out the goal. You can use the properties of the ActionClientGoalHandle object to track the goal execution asynchronously. To get the goal execution result synchronously, use the getResult object function.

Creation

To create a ActionClientGoalHandle object associated with a goal, use the sendGoal function on a ros2actionclient object and send a goal from the action client to the action server.

goalHandle = sendGoal(client,goalMsg,callbackOptions)

Properties

expand all

This property is read-only.

Unique ID for the associated action client goal, returned as a nonnegative integer.

Data Types: uint8

This property is read-only.

Execution status of the associated goal, returned as a nonnegative integer. Each integer denotes a specific status as defined in the action_msgs/msg/GoalStatus ROS 2 message definition:

  • 0 — Unknown

  • 1 — Accepted

  • 2 — Executing

  • 3 — Canceling

  • 4 — Succeeded

  • 5 — Canceled

  • 6 — Aborted

Data Types: int8

This property is read-only.

Timestamp when the goal was accepted, returned as a builtin_interfaces/Time message structure.

Data Types: struct

This property is read-only.

Callback function to execute when a feedback response is received by the action client, returned as a function handle. You can customize this callback using the ros2ActionSendGoalOptions function and then specify the custom callback options when you send a goal using the sendGoal function.

Data Types: function_handle

This property is read-only.

Callback function to execute when result response is received, returned as a function handle. You can customize this callback using the ros2ActionSendGoalOptions function and then specify the custom callback options when you send a goal using the sendGoal function.

Data Types: function_handle

Object Functions

getResultGet result of specific goal associated with goal handle

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

Extended Capabilities

C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.

Version History

Introduced in R2023a