Explore ROS 2 Actions: Action Client and Action Server Guide
Action is another communication mechanism meant for long-running tasks. Think of actions communication as a series of follow-up phone calls to complete a complex task that requires multiple steps and takes some time, like planning an event. You call an event planner, discuss the requirements, and then they provide you with updates at different stages of the planning process. You may also need to check in on progress or make changes along the way.
You can use actions for tasks that take time and require incremental or periodic feedback. Actions are comprised of two components: the action client and the action server.
- Client — An action client, say - Node 1is a node which requests a goal to be completed on its behalf. It will wait for feedbacks and a result upon completion.
- Server — An action server, say - Node 2is a node which will accept the goal, and perform the procedures required. It will send out feedback as the action progresses and returns a full result when the goal is achieved.

Action Interface
Action messages are described in a .action file. Actions are used
			for long-running tasks, where a client node sends a goal to a server node, which
			provides feedback on the task's progress and sends a result upon completion. Hence, an
			action file is made of three parts/messages: a goal, feedback, and a result.
You can view the list of available action message types by using ros2 msg
				list
ros2 msg list
action_msgs/CancelGoalRequest action_msgs/CancelGoalResponse action_msgs/GoalInfo action_msgs/GoalStatus action_msgs/GoalStatusArray actionlib_msgs/GoalID actionlib_msgs/GoalStatus actionlib_msgs/GoalStatusArray example_interfaces/FibonacciFeedback example_interfaces/FibonacciGoal example_interfaces/FibonacciResult...
This list contains action message types of predefined message interface definitions.
			You can create a message of any of these predefined types such as
				example_interfaces/Fibonacci.
This example shows how to create an action client and goal message.
Create a ROS 2 node for action client.
node_1 = ros2node("/node_1");Use ros2actionclient to create an action client and specify a goal
			message.
[client,goalMsg] = ros2actionclient(node_1, "/fibonacci", "example_interfaces/Fibonacci")
client = 
  ros2actionclient with properties:
           ActionName: '/fibonacci'
           ActionType: 'example_interfaces/Fibonacci'
    IsServerConnected: 0
       GoalServiceQoS: 'History: keeplast, Depth: 10, Reliability: reliable, Durability: volatile, Deadline: Inf, Lifespan: Inf, Liveliness: automatic, Lease Duration: Inf'
     ResultServiceQoS: 'History: keeplast, Depth: 10, Reliability: reliable, Durability: volatile, Deadline: Inf, Lifespan: Inf, Liveliness: automatic, Lease Duration: Inf'
     CancelServiceQoS: 'History: keeplast, Depth: 10, Reliability: reliable, Durability: volatile, Deadline: Inf, Lifespan: Inf, Liveliness: automatic, Lease Duration: Inf'
     FeedbackTopicQoS: 'History: keeplast, Depth: 10, Reliability: reliable, Durability: volatile, Deadline: Inf, Lifespan: Inf, Liveliness: automatic, Lease Duration: Inf'
       StatusTopicQoS: 'History: keeplast, Depth: 1, Reliability: reliable, Durability: transientlocal, Deadline: Inf, Lifespan: Inf, Liveliness: automatic, Lease Duration: Inf'
goalMsg = struct with fields:
    MessageType: 'example_interfaces/FibonacciGoal'
          order: 0
We will calculate the Fibonacci sequence up to 10. Set the order
			field of goalMsg as 10.
goalMsg.order = int32(10)
goalMsg = struct with fields:
    MessageType: 'example_interfaces/FibonacciGoal'
          order: 10
Send Action Goal, Monitor Feedback and Receive Result
This example walks you through the process of using ROS 2 actions in MATLAB to control a robot point head, directing its camera to a specific direction. This process demonstrates how to set up an action server and client, handle goal reception, execute the goal with feedback, and manage goal preemption and cancellation.
To begin with the action server, first specify the goal execution, reception and cancel callback functions. You must define these functions in separate code files respectively and call them while creating the action server.
- ReceiveGoalFcn=@receiveGoalCallback: Sets the- receiveGoalCallbackcallback function to handle incoming goal requests.
- ExecuteGoalFcn=@executeGoalCallback: Sets the- executeGoalCallbackcallback function to handle goal execution.
- CancelGoalFcn=@cancelGoalCallback: Sets the- cancelGoalCallbackcallback function to handle goal cancellations.
The receiveGoalCallback function is the goal reception callback
			that triggers when the action server receives a new goal. Use the
				handleGoalResponse object function to accept or reject a new
			goal. If the received goal is empty, it rejects the goal. If the goal is not empty, it
			accepts and executes the goal.
function receiveGoalCallback(src,goalStruct) fprintf('Goal received with UUID : %s\n', goalStruct.goalUUID); if isempty(goalStruct.goal) fprintf('Goal with UUID %s is rejected\n', goalStruct.goalUUID); handleGoalResponse(src,goalStruct,'REJECT'); else fprintf('Goal with UUID %s is accepted and executing\n', goalStruct.goalUUID); targetPoint = goalStruct.goal.target; imgWidth = 512; imgHeight = 384; % Check if the target point is within the image boundaries if targetPoint.point.x < 1 || targetPoint.point.x > imgWidth || ... targetPoint.point.y < 1 || targetPoint.point.y > imgHeight handleGoalResponse(src,goalStruct,'REJECT'); else handleGoalResponse(src,goalStruct,'ACCEPT_AND_EXECUTE'); end end end
 First, check whether the client has preempted the goal using the
				isPreemptRequested object function. If not, continue goal
			execution and send periodic feedback to the client about the goal execution
			status.
A preemption request is a mechanism that allows an action server to stop the execution of a current goal before it completes, in order to start working on a new goal. This is particularly useful in scenarios where priorities change dynamically, and the system needs to react to new, more urgent requests.
In this example, isPreemptRequested(src,goalStruct) checks if a
			preemption request has been made. If a preemption request is detected, the loop breaks,
			and the success flag is set to false, indicating
			that the goal was not completed successfully due to preemption.
function [result, success] = executeGoalCallback(src,goalStruct,defaultFeedbackMsg,defaultResultMsg) disp('Executing goal...'); % Simulate moving the head feedbackMsg = defaultFeedbackMsg; success = true; result = defaultResultMsg; % Simulate time taken to move the head targetPoint = goalStruct.goal.target; % Simulate a successful result if isPreemptRequested(src,goalStruct) success = false; end img = imread('peppers.png'); width = 100; height = 100; imgWidth = 512; imgHeight = 384; x = targetPoint.point.x; y = targetPoint.point.y; persistent initial_x; persistent initial_y; if isempty(initial_x) initial_x = 1; initial_y = 1; end x_steps = x - initial_x + 1; y_steps = y - initial_y + 1; for i=1:abs(x_steps) if isPreemptRequested(src,goalStruct) success = false; break end initial_x = initial_x + sign(x_steps); initial_x = max(1, min(initial_x, imgWidth - width + 1)); % Ensure within bounds imgPortion = img(initial_y:(initial_y+height-1), initial_x:(initial_x+width-1), :); imshow(imgPortion); sendFeedback(src,goalStruct,feedbackMsg); pause(0.01); end % Move in y direction for i=1:abs(y_steps) if isPreemptRequested(src,goalStruct) success = false; break end initial_y = initial_y + sign(y_steps); initial_y = max(1, min(initial_y, imgHeight - height + 1)); % Ensure within bounds imgPortion = img(initial_y:(initial_y+height-1), initial_x:(initial_x+width-1), :); imshow(imgPortion); sendFeedback(src,goalStruct,feedbackMsg); pause(0.01); end end
Now, create a ROS 2 node for the action server using
				ros2actionserver function. Choose the
				control_msgs/PointHead action message type as it supports
			controlling of the direction of the robot's camera
% Initialize ROS 2 node for the action server node2 = ros2node("matlab_pointhead_action_server"); % Create an action server for the PointHead action server = ros2actionserver(node2, "name", "control_msgs/PointHead", ... ReceiveGoalFcn=@receiveGoalCallback, ... ExecuteGoalFcn=@executeGoalCallback, ... CancelGoalFcn=@cancelGoalCallback); disp('PointHead action server started.');
The cancelGoalCallback function is the cancel goal callback that
			triggers after the server receives a cancel request from the client.
Note
To the limitation of ROS 2 actions, you must run the
					ros2actionserver and the ros2actionclient
				connected to it in different MATLAB® sessions for the server process to cancel requests from the
				client.
function cancelGoalCallback(~,goalStruct) fprintf('[Server] Received request to cancel goal with UUID: %s\n', goalStruct.goalUUID); end
Recall the action client client and goal message
				goalMsg that you created earlier. Similarly, for this example,
			create an action client and specify the goal message as the robot point head's target
			point within a defined duration and velocity. In this example, the client requests the
			server to move a robot camera's point head to capture a specified portion of an
			image.
Create the action client using the same control_msgs/PointHead
			action message type as it supports direction control of the robot's camera by setting
			these three fields:
- target— Specifies the point in space where the camera should point.
- min_duration— Defines the minimum duration for achieving the goal.
- max_velocity— Sets the maximum velocity for moving the camera.
% Initialize ROS 2 node for the action client node1 = ros2node("matlab_pointhead_controller"); % Create an action client for the PointHead action actionClient = ros2actionclient(node1, "name", "control_msgs/PointHead"); % Wait for the action server to be available waitForServer(actionClient); disp("Connected with Server....") % Time delay between actions (in seconds) timeDelay = 1.0; % Create a goal message for the PointHead action goalMsg = ros2message(actionClient); % Set the target point in the frame of the head targetPoint = ros2message("geometry_msgs/PointStamped"); targetPoint.header.frame_id = 'base_link'; % Replace with your frame id targetPoint.point.x = 100; targetPoint.point.y = 100; targetPoint.point.z = 0; % Set the goal message fields goalMsg.target = targetPoint; goalMsg.min_duration.Sec = 1; % Minimum duration of the movement goalMsg.max_velocity = 1.0; % Maximum velocity of the movement
Use ros2ActionSendGoalOptions function to specify callback options
			when the client receives feedback and result messages from the server. Ensure to define
			the callback functions in separate code
			files.
callbackOpts = ros2ActionSendGoalOptions(FeedbackFcn=@helperFeedbackCallback,ResultFcn=@printResult);
The helperFeedbackCallback function is triggered when the client
			receives the feedback message from the server.
function helperFeedbackCallback(goalStruct,feedbackMsg) disp(['[Client] Feedback : Pointing angle error is ', num2str(feedbackMsg.pointing_angle_error), ' for goal ', goalStruct.GoalUUID]); end
The printResult function is triggered when the client receives the
			result message from the server.
function printResult(goalStruct, result) code = result.code; disp(['[Client] Goal ',goalStruct.GoalUUID,' is completed with return code ',num2str(code)]); end
Use sendGoal to send the goal and wait for the result.
result = sendGoal(actionClient, goalMsg, callbackOpts);
During the goal execution, you see the following outputs from the feedback and result callbacks displayed on the MATLAB® command window.
PointHead action server started. [Server] Goal received with UUID : 2de88fdde97e7da9a61eae87c3769a [Server] Goal with UUID 2de88fdde97e7da9a61eae87c3769a is accepted and executing [Server] Executing goal... Connected with Server.... Goal with GoalUUID 2de88fdde97e7da9a61eae87c3769a accepted by server, waiting for result! [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Feedback : Pointing angle error is 0 for goal 2de88fdde97e7da9a61eae87c3769a [Client] Goal 2de88fdde97e7da9a61eae87c3769a is completed with return code 4
You shall also see the output, which demonstrates that the specified image moving in a particular direction within a plot for a specified duration and at a specified velocity, is essentially the result of simulating the robot's camera movement in particular directions.

The helperCancelGoalCallback function is responsible for handling
			the server's response to the cancellation request.
function helperCancelGoalCallback(goalHandle,cancelMsg) code = cancelMsg.return_code; disp(['Goal ',goalHandle.GoalUUID,' is cancelled with return code ',num2str(code)]); end
Call cancelGoal to trigger this callback at any point of time after
			sending the goal, if you wish to cancel the goal.
cancelGoal(actionClient, result, CancelFcn=@helperCancelGoalCallback);
Custom Message Support for ROS 2 Actions
While leveraging standard action interfaces proves useful, there are scenarios where creating custom ROS 2 action messages becomes essential to meet specific needs within your robotic applications. For instance, if you need to broaden the functionality of generating Fibonacci sequences to cover real and complex numbers, ROS 2 enables you to define custom actions in your packages. The ROS Toolbox extends support for generating custom ROS 2 action messages, detailed in ROS 2 Custom Message Support
To generate ROS 2 custom messages, you can use the ros2genmsg function to read ROS
			2 custom message definitions in the specified folder path. The designated folder should
			contain one or more ROS 2 packages containing action message definitions in
				.action files. Additionally, you can create a shareable ZIP
			archive of the generated custom messages. This archive facilitates registering the
			custom messages on another machine using ros2RegisterMessages.
In MATLAB, you typically don't write .action files directly.
			Instead, you create custom messages using ROS 2 package tools and then use them in
				MATLAB. For more information, see Create Custom Messages from ROS 2 Package.
See Also
ros2actionclient | ros2actionserver