send
Publish ROS message to topic
Syntax
Description
Examples
Create, Send, and Receive ROS Messages
Set up a publisher and subscriber to send and receive a message on a ROS network.
Connect to a ROS network.
rosinit
Launching ROS Core... Done in 0.72026 seconds. Initializing ROS master on http://172.20.221.140:53240. Initializing global node /matlab_global_node_25542 with NodeURI http://dcc031654glnxa64:44579/ and MasterURI http://localhost:53240.
Create a publisher with a specific topic and message type. You can also return a default message to send using this publisher.
[pub,msg] = rospublisher('position','geometry_msgs/Point');
Modify the message before sending it over the network.
msg.X = 1; msg.Y = 2; send(pub,msg);
Create a subscriber and wait for the latest message. Verify the message is the one you sent.
sub = rossubscriber('position')
sub = Subscriber with properties: TopicName: '/position' LatestMessage: [1x1 Point] MessageType: 'geometry_msgs/Point' BufferSize: 1 MessagePreprocessingEnabled: 0 NewMessageFcn: [] DataFormat: 'object'
pause(1); sub.LatestMessage
ans = ROS Point message with properties: MessageType: 'geometry_msgs/Point' X: 1 Y: 2 Z: 0 Use showdetails to show the contents of the message
Shut down the ROS network.
rosshutdown
Shutting down global node /matlab_global_node_25542 with NodeURI http://dcc031654glnxa64:44579/ and MasterURI http://localhost:53240. Shutting down ROS master on http://172.20.221.140:53240.
Input Arguments
pub
— ROS publisher
Publisher
object handle
ROS publisher, specified as a Publisher
object handle. You can create the
object using rospublisher
.
msg
— ROS message
Message
object handle | structure
ROS message, specified as a Message
object handle or structure. You can
create object using rosmessage
.
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
struct
messages.
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.
See Also
receive
| rosmessage
| rostopic
| rossubscriber
| rospublisher
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 (한국어)