msg = receive(sub,timeout)
specifies in timeout the number of seconds to
wait for a message. If a message is not received within the timeout
limit, the software produces an error.
Connect to a ROS network. Set up a sample ROS network. The '/scan' topic is being published on the network.
rosinit
Initializing ROS master on http://bat6346glnxa64:33423/.
Initializing global node /matlab_global_node_07536 with NodeURI http://bat6346glnxa64:35561/
exampleHelperROSCreateSampleNetwork
Create a subscriber for the '/scan' topic. Wait for the subscriber to register with the master.
sub = rossubscriber('/scan');
pause(1);
Receive data from the subscriber as a ROS message. Specify a 10-second timeout.
msg2 = receive(sub,10)
msg2 =
ROS LaserScan message with properties:
MessageType: 'sensor_msgs/LaserScan'
Header: [1x1 Header]
AngleMin: -0.5216
AngleMax: 0.5243
AngleIncrement: 0.0016
TimeIncrement: 0
ScanTime: 0.0330
RangeMin: 0.4500
RangeMax: 10
Ranges: [640x1 single]
Intensities: [0x1 single]
Use showdetails to show the contents of the message
Shutdown the timers used by sample network.
exampleHelperROSShutDownSampleNetwork
Shut down ROS network.
rosshutdown
Shutting down global node /matlab_global_node_07536 with NodeURI http://bat6346glnxa64:35561/
Shutting down ROS master on http://bat6346glnxa64:33423/.
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'
MessageType: 'geometry_msgs/Point'
LatestMessage: [1x1 Point]
BufferSize: 1
NewMessageFcn: []
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_09838 with NodeURI http://bat6346glnxa64:41509/
Shutting down ROS master on http://bat6346glnxa64:43469/.