sendGoal
Send goal message to action server
Syntax
Description
sendGoal(
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 immediately.client
,goalMsg
)
If the ActionFcn
, FeedbackFcn
,
and ResultFcn
callbacks of the client 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.
Examples
Create and Send ROS Action Goal Message
This example shows how to create goal messages and send them to an active ROS action server on a ROS network. You must create a ROS action client to connect to this server.
Start ROS-Enabled Virtual Machine
Download and install the virtual machine (VM) using the instructions in Get Started with Gazebo and Simulated TurtleBot example.
Start the Ubuntu® VM desktop.
On the Ubuntu desktop, click ROS Noetic Terminal.
Launch ROS Action Server in ROS-Enabled VM
Source the appropriate ROS environment setup script in the ROS noetic terminal before running any ROS commands.
source ~/Documents/mw_catkin_ws/devel/setup.bash
Run the action server in the ROS noetic terminal.
roslaunch turtlebot_actions server_turtlebot_move.launch
Connect to ROS from MATLAB
Connect to the ROS node using rosinit
with the IP address of the ROS-enabled VM.
rosIP = "192.168.198.128"; % IP address rosinit(rosIP,11311) % Initialize ROS connection
Initializing global node /matlab_global_node_19677 with NodeURI http://192.168.198.1:61572/ and MasterURI http://192.168.198.128:11311.
Create ROS Action Client
Create a ROS action client using rosactionclient
and get a goal message. The action client object actClient
connects to the already running ROS action server. The goalMsg
is a valid goal message. Update the message parameters with your specific goal.
[actClient,goalMsg] = rosactionclient("/turtlebot_move");
disp(goalMsg)
ROS TurtlebotMoveGoal message with properties: MessageType: 'turtlebot_actions/TurtlebotMoveGoal' TurnDistance: 0 ForwardDistance: 0 Use showdetails to show the contents of the message
Create ROS Message Using ROS Action Client
Create a message using rosmessage
function and the action client object. This message sends linear and angular velocity commands to a Turtlebot® robot.
goalMsg = rosmessage(actClient); disp(goalMsg)
ROS TurtlebotMoveGoal message with properties: MessageType: 'turtlebot_actions/TurtlebotMoveGoal' TurnDistance: 0 ForwardDistance: 0 Use showdetails to show the contents of the message
Send Goal Message to Action Server
Modify the goal message parameters and send the goal to the action server.
goalMsg.ForwardDistance = 2; % in meters
sendGoal(actClient,goalMsg)
Send and Cancel ROS Action Goals
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/
Input Arguments
client
— ROS action client
SimpleActionClient
object handle
ROS action client, specified as a SimpleActionClient
object
handle. This simple action client enables you to track a single goal
at a time.
goalMsg
— ROS action goal message
Message
object handle | structure
ROS action goal message, specified as a Message
object handle or structure.
Update this message with your goal details and send it to the ROS action
client using sendGoal
or sendGoalAndWait
.
Note
In a future release, ROS Toolbox will use message structures instead of objects for ROS messages.
To use message structures now, set the "DataFormat"
name-value
argument to "struct"
. For more information, see ROS Message Structures.
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
Usage notes and limitations:
Supported only for the Build Type,
Executable
.Usage in MATLAB Function block is not supported.
Version History
Introduced in R2019bR2021a: ROS Message Structures
You can now create messages as structures with fields matching the message object properties. Using structures typically improves performance of creating, updating, and using ROS messages, but message fields are no longer validated when set. Message types and corresponding field values from the structures are validated when sent across the network.
To use ROS messages as structures, use the "DataFormat"
name-value
argument when creating your publishers, subscribers, or other ROS objects. Any messages
generated from these objects will utilize structures.
pub = rospublisher("/scan","sensor_msgs/LaserScan","DataFormat","struct") msg = rosmessage(pub)
You can also create messages as structures directly, but make sure to specify the data
format as "struct"
for the publisher, subscriber, or other ROS objects as
well. ROS objects still use message objects by default.
msg = rosmessage("/scan","sensor_msgs/LaserScan","DataFormat","struct") ... pub = rospublisher("/scan","sensor_msgs/LaserScan","DataFormat","struct")
In a future release, ROS messages will use structures by default and ROS message objects will be removed.
For more information, see Improve Performance of ROS Using Message Structures.
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 (한국어)