sendGoal
Description
sends a goal message to the action server. The specified action client tracks this goal. The
function does not wait for the goal to be executed and returns the goal handle object,
goalHandle
= sendGoal(client
,goalMsg
)goalHandle
immediately.
specifies customized functions for goal response, feedback, and result callbacks using the
structure goalHandle
= sendGoal(client
,goalMsg
,callbackOptions
)callbackOptions
. Use the ros2ActionSendGoalOptions
function to customize callbacks and get the
associated callbackOptions
structure.
Examples
Set Up ROS 2 Action Client and Execute an Action
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:
Create a ROS 2 package with the action definition. For instructions on setting up a /
fibonacci
action, see Creating an Action.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.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
Send and Cancel ROS 2 Action Goals
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:
Create a ROS 2 package with the action definition. For instructions on setting up a /
fibonacci
action, see Creating an Action.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.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
Input Arguments
client
— ROS 2 action client
ros2actionclient
object handle
ROS 2 action client, specified as a ros2actionclient
object
handle.
goalMsg
— ROS 2 action goal message
structure
ROS 2 action goal message, specified as a message structure. Update this message
with your goal details and send it to the ROS 2 action client using the
sendGoal
function.
callbackOptions
— Callback options framework
structure
Callback options framework, specified as a structure. The fields of the structure
specify the function handles for goal response, feedback and result callbacks along with
the required data for each of the callbacks. Use the ros2ActionSendGoalOptions
function to define custom functions for each of
the callbacks and get the callback options structure.
Output Arguments
goalHandle
— Action client goal handle
ActionClientGoalHandle
object
Action client goal handle, returned as an ActionClientGoalHandle
object. 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.
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
Usage notes and limitations:
The callback functions used to send and cancel goals must be specified while creating the
ros2actionclient
object using these name-value arguments.'SendGoalOptions'
— Specify a cell array of callback options structures for sending goals that you create using theros2ActionSendGoalOptions
function.'CancelFcn'
— Specify the cancel response callback that you use with thecancelGoal
function.'CancelAllFcn'
— Specify the cancel response callback that you use with thecancelAllGoals
function.'CancelBeforeFcn'
— Specify the cancel response callback that you use with thecancelGoalsBefore
function.
Note that these arguments are used for definition of
ros2actionclient
only and must be specified again at the time of usage in the respective function.callbackOpts1 = ros2ActionSendGoalOptions(FeedbackFcn=@glfeedback,ResultFcn=@glResult); callbackOpts2 = ros2ActionSendGoalOptions(FeedbackFcn=@glfeedback2,ResultFcn=@glResult2); [client] = ros2actionClient(node,"my_action","my_action_type",SendGoalOptions={callbackOpts1,callbackOpts2},CancelFcn=@cancelGoalCB,CancelAllFcn=@cancelGoalsCB); goalMsg = ros2message(client); goalHandle = sendGoal(client,goalMsg,callbackOpts1); cancelGoal(client,goalHandle,CancelFcn=@cancelGoalCB);
Version History
Introduced in R2023a
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)