Main Content

ros2actionserver

Create ROS 2 Action Server

Since R2023b

Description

The ros2actionserver object creates a ROS 2 action server in MATLAB®. You can use a ros2actionclient object from another MATLAB session to create an action client, connect to the action server, and request the execution of action goals. When a connected client sends a goal execution request, the server executes the callback function ExecuteGoalFcn. The server can provide periodic feedback on execution progress to the clients, preempt a goal upon receiving a cancel request, and abort a goal if an error occurs during goal execution. ros2actionserver can accept multiple goals, but executes the goals in a first-in, first-out manner.

An action is defined by a type and three messages: one message for the goal, one for the feedback, and one for the result. On receiving a goal, the server calls the goal reception callback to decide whether to accept or reject the goal. If the server accepts the goal, the server goal execution callback must periodically send feedback to the client during goal execution, and return an appropriate result when goal execution completes. The behavior of the action server is inherently asynchronous because it becomes active only when an action client connects to the ROS 2 network and issues a goal execution request.

Creation

Description

server = ros2actionserver(node,actionname,actiontype,ExecuteGoalFcn=cb) creates an action server object, server, that corresponds to the ROS 2 action of the specified name actionname and type actiontype and attaches it to the ROS 2 node specified by the ros2node object node. You must also specify the ExecuteGoalFcn property as a function handle callback, cb, which handles goal execution when the client sends a goal.

example

server = ros2actionserver(node,actionname,actiontype,ExecuteGoalFcn=cb,Name=Value) sets additional properties using one or more Name=Value arguments.

Properties

expand all

This property is read-only.

ROS 2 action name, stored as a character vector. The actionname argument sets this property.

This property is read-only.

ROS 2 action type, stored as a string scalar or character vector. The actiontype argument sets this property. The action type must match one of the actions returned by ros2type.getActionList.

This property is read-only.

Server can accept more than one goal, stored as an 'on' or 'off' character vector. The MultiGoalMode name-value argument sets this property. If MultiGoalMode is 'on', the action server accepts more than one goal, but executes them in a first-in, first-out manner.

Callback for goal execution, specified as a function handle or cell array. The server executes this function after accepting a goal. In the first element of the cell array, specify either a function handle, string scalar, or character vector representing a function name. In subsequent elements, specify user data.

The action callback function requires at least four input arguments with two outputs. The first input argument, src, is the associated action server object. The second input argument, goalStruct is a structure that contains the goal message sent by the action client and the unique ID of the goal. The third input argument is the default feedback message defaultFeedbackMsg. The fourth argument is the default result message defaultResultMsg. The callback function returns a result message, result, based on the input goal message and sends it back to the action client. Use the default result message as a starting point for constructing the result message. The callback also returns success as true if the goal was successfully reached, or as false if the goal was aborted or preempted. The function header for the callback must be of the form:

function [result,success] = executeGoalCallback(src,goalStruct,defaultFeedbackMsg,defaultResultMsg)

Specify the ExecuteGoalFcn property while creating the action server using the name-value argument as:

server = ros2actionserver(actionname,actiontype,ExecuteGoalFcn=@executeGoalCallback)

Alternatively, you can pass additional parameters to the callback function by specifying both the callback function and the additional parameters as elements of a cell array. The function header must be of the form:

function [result,success] = actionCallback(src,goalStruct,defaultFeedbackMsg,defaultResultMsg,userData)

Specify the ExecuteGoalFcn property while creating the action server using the name-value argument as:

server = ros2actionserver(actionname,actiontype,ExecuteGoalFcn={@executeGoalCallback,userData})

Callback for new goal reception, specified as a function handle or cell array. This function is triggered after receiving a new goal. In the first element of the cell array, specify either a function handle, string scalar, or character vector representing a function name. In subsequent elements, specify user data.

The receive goal callback function requires at least two input arguments. The first input argument, src, is the associated action server object. The second input argument, goalStruct is a structure that contains the goal message sent by the action client and the unique ID of the goal. You can use the handleGoalResponse function within the callback to accept or reject the newly received goal and send the status back to the client. The function header for the callback must be of the form:

function receiveGoalCallback(src,goalStruct)
  fprintf('[Server] Goal received, UUID: %s\n', goalStruct.goalUUID);
  if reject condition
    handleGoalResponse(src,goalStruct,'REJECT');
  else
    handleGoalResponse(src,goalStruct,'ACCEPT_AND_EXECUTE');
  end
end

Specify the ReceiveGoalFcn property while creating the action server using the name-value argument as:

server = ros2actionserver(actionname,actiontype,ExecuteGoalFcn=@executeGoalCallback,ReceiveGoalFcn=@receiveGoalCallback)

Alternatively, you can pass additional parameters to the callback function by specifying both the callback function and the additional parameters as elements of a cell array. The function header must be of the form:

function receiveGoalCallback(src,goalStruct,userData)

Specify the ExecuteGoalFcn property while creating the action server using the name-value argument as:

server = ros2actionserver(actionname,actiontype,ExecuteGoalFcn={@executeGoalCallback,userData},ReceiveGoalFcn={@receiveGoalCallback,userData})

Callback for goal cancellation, specified as a function handle or cell array. This function is triggered after receiving a cancel request. In the first element of the cell array, specify either a function handle, string scalar, or character vector representing a function name. In subsequent elements, specify user data.

The cancel goal callback function requires at least two input arguments. The first input argument, src, is the associated action server object. The second input argument, goalStruct is a structure that contains the goal message sent by the action client and the unique ID of the goal. The function header for the callback must be of the form:

function cancelGoalCallback(src,goalStruct)

Specify the CancelGoalFcn property while creating the action server using the name-value argument as:

server = ros2actionserver(actionname,actiontype,ExecuteGoalFcn=@executeGoalCallback,CancelGoalFcn=@cancelGoalCallback)

Alternatively, you can pass additional parameters to the callback function by specifying both the callback function and the additional parameters as elements of a cell array. The function header must be of the form:

function cancelGoalCallback(src,goalStruct,userData)

Specify the ExecuteGoalFcn property while creating the action server using the name-value argument as:

server = ros2actionserver(actionname,actiontype,ExecuteGoalFcn={@executeGoalCallback,userData},CancelGoalFcn={@cancelGoalCallback,userData})

Quality of Service (QoS) settings for sending goal acceptance response from the action server, specified as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

The object stores this property as a character vector.

Quality of Service (QoS) settings for sending result response from the action server, specified as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

The object stores this property as a character vector.

Quality of Service (QoS) settings for sending cancel goal response from the action server, specified as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

The object stores this property as a character vector.

Quality of Service (QoS) settings for sending feedback to the action client, specified as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

The object stores this property as a character vector.

Quality of Service (QoS) settings for sending goal execution status to the action client, specified as a structure with the one or more of these fields:

  • History

  • Depth

  • Reliability

  • Durability

  • Deadline

  • Lifespan

  • Liveliness

  • Lease Duration

The object stores this property as a character vector.

Object Functions

ros2messageCreate ROS 2 message structures
getFeedbackMessageCreate new ROS 2 action feedback message
handleGoalResponseAccept or reject new ROS 2 action goal and send status
isPreemptRequestedCheck if a goal has been preempted
sendFeedbackSend feedback to ROS 2 action client during goal execution

Examples

collapse all

This example shows how to create a ROS 2 action server, connect an action client to it, receive a goal, and execute it.

Create a ROS 2 node.

node = ros2node("/node_1");

Set up an action server for calculating Fibbonacci sequence. Specify the goal execution, reception and cancel callbacks.

server = ros2actionserver(node,"/fibbonacci","example_interfaces/Fibonacci",ReceiveGoalFcn=@goalReceptionCB,...
                          ExecuteGoalFcn=@goalExecutionCB,CancelGoalFcn=@cancelGoalCB)
server = 
  ros2actionserver with properties:

          ActionName: '/fibbonacci'
          ActionType: 'example_interfaces/Fibonacci'
       MultiGoalMode: 'on'
      ExecuteGoalFcn: @goalExecutionCB
      ReceiveGoalFcn: @goalReceptionCB
       CancelGoalFcn: @cancelGoalCB
      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'

Create an action client and specify a goal message to calculate the Fibbonacci sequence up to 10 terms past the first term 0.

client = ros2actionclient(node,"/fibbonacci","example_interfaces/Fibonacci");
waitForServer(client);
goalMsg = ros2message(client);
goalMsg.order = int32(10);

Send the goal. Use ros2ActionSendGoalOptions function to specify callback options when the client receives feedback and result messages from the server.

callbackOpts = ros2ActionSendGoalOptions(FeedbackFcn=@printFeedback,ResultFcn=@printResult);
goalHandle = sendGoal(client,goalMsg,callbackOpts);

Supporting Functions

goalReceptionCB is the goal reception callback that is triggered when the action server receives a new goal. Use the handleGoalResponse object function to accept or reject a new goal.

function goalReceptionCB(src,goalStruct)
    fprintf("[Server] Goal received, UUID: %s\n",goalStruct.goalUUID)
    if goalStruct.goal.order < 1
        % Reject Goal
        handleGoalResponse(src,goalStruct,'REJECT');
    else
        handleGoalResponse(src,goalStruct,'ACCEPT_AND_EXECUTE');
    end
end

goalExecutionCB is the goal execution callback that is triggered after a new goal is accepted and the server is ready to execute it. In this example, use goalExecutionCB to calculate the Fibonacci sequence for the number of terms specified in the goal message. 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.

function [result,success] = goalExecutionCB(src,goalStruct,defaultFeedbackMsg,defaultResultMsg)
    fprintf('[Server] Goal accepted and executing, UUID: %s\n', goalStruct.goalUUID);
    success = true;
    result = defaultResultMsg;
    feedback = defaultFeedbackMsg;
    feedback.sequence = int32([0;1]);
    for k=1:goalStruct.goal.order-1
        % Check that the client has not preempted the goal
        if isPreemptRequested(src,goalStruct)
            success = false;
            break
        end

        % Periodically send feedback to the client
        feedback.sequence = [feedback.sequence; int32(0)];
        feedback.sequence(end) = feedback.sequence(end-1) + feedback.sequence(end-2);
        sendFeedback(src,goalStruct,feedback);
    end

    if success
        result.sequence = feedback.sequence;
    end
end

cancelGoalCB is the cancel goal callback that is triggered after the server receives a cancel request from the client.

function cancelGoalCB(~,goalStruct)
    fprintf('[Server] Received request to cancel goal with UUID: %s\n', goalStruct.goalUUID);
end

printFeedback function is triggered when the client receives the feedback message from the server.

function printFeedback(goalHandle,resp)
    seq = resp.sequence;
    fprintf("[Client] Feedback: Fibonacci sequence for goal %s calculated currently: [", goalHandle.GoalUUID);
    for i=1:numel(seq)
        fprintf(" %d",seq(i));
    end
   fprintf(' ]\n');
end

printResult function is triggered when the client receives the result message from the server.

function printResult(goalHandle,resp)
    seq = resp.result.sequence;
    fprintf("[Client] Result: Fibonacci sequence for goal %s is: [", goalHandle.GoalUUID);
    for i=1:numel(seq)
        fprintf(" %d",seq(i));
    end
    fprintf(' ]\n');
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 R2023b