Main Content

rosactionclient

Create ROS action client

Since R2019b

Description

Use the rosactionclient to connect to an action server using a SimpleActionClient object and request the execution of action goals. You can get feedback on the execution process and cancel the goal at any time. The SimpleActionClient object encapsulates a simple action client and enables you to track a single goal at a time.

Creation

Description

example

client = rosactionclient(actionname) creates a client for the specified ROS ActionName. The client determines the action type automatically. If the action is not available, this function displays an error.

Use rosactionclient to connect to an action server and request the execution of action goals. You can get feedback on the execution progress and cancel the goal at any time.

client = rosactionclient(actionname,actiontype) creates an action client with the specified name and type (ActionType). If the action is not available, or the name and type do not match, the function displays an error.

[client,goalMsg] = rosactionclient(___) returns a goal message to send the action client created using any of the arguments from the previous syntaxes. The Goal message is initialized with default values for that message.

If the ActionFcn, FeedbackFcn, and ResultFcn callbacks are defined, they are called when the goal is processing on the action server. All callbacks associated with a previously sent goal are disabled, but the previous goal is not canceled.

[___] = rosactionclient(___,"DataFormat","struct") uses message structures instead of objects. For more information, see ROS Message Structures.

client = ros.SimpleActionClient(node,actionname) creates a client for the specified ROS action name. The node is the Node object that is connected to the ROS network. The client determines the action type automatically. If the action is not available, the function displays an error.

client = ros.SimpleActionClient(node,actionname,actiontype) creates an action client with the specified name and type. You can get the type of an action using rosaction type actionname.

client = ros.SimpleActionClient(___,"DataFormat","struct") uses message structures instead of objects. For more information, see ROS Message Structures.

Properties

expand all

ROS action name, returned as a character vector. The action name must match one of the topics that rosaction("list") outputs.

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

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

Tracked goal, returned as a ROS message. This message is the last goal message this client sent. The goal message depends on the action type.

Goal state, returned as one of the following:

  • 'pending' — Goal was received, but has not yet been accepted or rejected.

  • 'active' — Goal was accepted and is running on the server.

  • 'succeeded' — Goal executed successfully.

  • 'preempted' — An action client canceled the goal before it finished executing.

  • 'aborted' — The goal was aborted before it finished executing. The action server typically aborts a goal.

  • 'rejected' — The goal was not accepted after being in the 'pending' state. The action server typically triggers this status.

  • 'recalled' — A client canceled the goal while it was in the 'pending' state.

  • 'lost' — An internal error occurred in the action client.

Activation function, returned as a function handle. This function executes when GoalState is set to 'active'. By default, the function displays 'Goal is active.'. You can set the function to [] to have the action client do nothing upon activation.

Feedback function, returned as a function handle. This function executes when a new feedback message is received from the action server. By default, the function displays the details of the message. You can set the function to [] to have the action client not give any feedback.

Result function, returned as a function handle. This function executes when the server finishes executing the goal and returns a result state and message. By default, the function displays the state and details of the message. You can set the function to [] to have the action client do nothing once the goal is completed.

Message format, specified as "object" or "struct". You must set this property on creation using the name-value input. For more information, see ROS Message Structures.

Object Functions

cancelGoalCancel last goal sent by client
cancelAllGoalsCancel all goals on action server
rosmessageCreate ROS messages
sendGoalSend goal message to action server
sendGoalAndWaitSend goal message and wait for result
waitForServerWait for action server to start

Examples

collapse all

This example shows how to create a ROS action client and execute the action. Action types must be set up beforehand with an action server running.

You must have set up the '/fibonacci' action type. To run this action server, use the following command on the ROS system:

rosrun actionlib_tutorials fibonacci_server

Connect to a ROS network. You must be connected to a ROS network to gather information about what actions are available. Replace ipaddress with your network address.

ipaddress = '192.168.203.133';
rosinit(ipaddress,11311)
Initializing global node /matlab_global_node_81947 with NodeURI http://192.168.203.1:54283/

List actions available on the network. The only action set up on this network is the '/fibonacci' action.

rosaction list
/fibonacci

Create an action client by specifying the action name. Use structures for ROS messages.

[actClient,goalMsg] = rosactionclient('/fibonacci','DataFormat','struct');

Wait for the action client to connect to the server.

waitForServer(actClient);

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);

Send the goal and wait for its completion. Specify a timeout of 10 seconds to complete the action.

[resultMsg,resultState] = sendGoalAndWait(actClient,goalMsg,10);
rosShowDetails(resultMsg)
ans = 
    '
       MessageType :  actionlib_tutorials/FibonacciResult
       Sequence    :  [0, 1, 1, 2, 3, 5, 8, 13, 21]'

Disconnect from the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_81947 with NodeURI http://192.168.203.1:54283/

This example shows how to send and cancel goals for ROS actions. Action types must be setup beforehand with an action server running.

You must have set up the '/fibonacci' action type. To run this action server, use the following command on the ROS system:

rosrun actionlib_tutorials fibonacci_server

First, set up a ROS action client. Then, send a goal message with modified parameters. Finally, cancel your goal and all goals on the action server.

Connect to a ROS network with a specified IP address. Create a ROS action client connected to the ROS network using rosactionclient. Specify the action name. Wait for the client to be connected to the server.

rosinit('192.168.203.133',11311)
Initializing global node /matlab_global_node_18287 with NodeURI http://192.168.203.1:55284/
[actClient,goalMsg] = rosactionclient('/fibonacci','DataFormat','struct');
waitForServer(actClient);

Send a goal message with modified parameters. Wait for the goal to finish executing.

goalMsg.Order = int32(4);
[resultMsg,resultState] = sendGoalAndWait(actClient,goalMsg)
resultMsg = struct with fields:
    MessageType: 'actionlib_tutorials/FibonacciResult'
       Sequence: [0 1 1 2 3]

resultState = 
'succeeded'
rosShowDetails(resultMsg)
ans = 
    '
       MessageType :  actionlib_tutorials/FibonacciResult
       Sequence    :  [0, 1, 1, 2, 3]'

Send a new goal message without waiting.

goalMsg.Order = int32(5);
sendGoal(actClient,goalMsg)

Cancel the goal on the ROS action client, actClient.

cancelGoal(actClient)

Cancel all the goals on the action server that actClient is connected to.

cancelAllGoals(actClient)

Delete the action client.

delete(actClient)

Disconnect from the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_18287 with NodeURI http://192.168.203.1:55284/

Extended Capabilities

Version History

Introduced in R2019b

expand all