Main Content

receive

Wait for new ROS message

Since R2019b

Description

example

msg = receive(sub) waits for MATLAB® to receive a topic message from the specified subscriber, sub, and returns it as msg.

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, this function will display an error.

example

[msg,status,statustext] = receive(___) returns a status indicating whether a message has been received successfully, and a statustext that captures additional information about the status, using any of the arguments from the previous syntaxes. If an error condition occurs, such as no message received within the specified timeout, the status will be false, and this function will not display an error.

Examples

collapse all

Connect to a ROS network. Set up a sample ROS network. The '/scan' topic is being published on the network.

rosinit
Launching ROS Core...
Done in 0.53389 seconds.
Initializing ROS master on http://172.29.206.170:60383.
Initializing global node /matlab_global_node_91866 with NodeURI http://dcc598343glnxa64:34299/ and MasterURI http://localhost:60383.
exampleHelperROSCreateSampleNetwork

Create a subscriber for the '/scan' topic using message structures. Wait for the subscriber to register with the master.

sub = rossubscriber('/scan','DataFormat','struct');
pause(1);

Receive data from the subscriber as a ROS message structure. Specify a 10-second timeout.

[msg2,status,statustext] = receive(sub,10)
msg2 = struct with fields:
       MessageType: 'sensor_msgs/LaserScan'
            Header: [1x1 struct]
          AngleMin: -0.5467
          AngleMax: 0.5467
    AngleIncrement: 0.0017
     TimeIncrement: 0
          ScanTime: 0.0330
          RangeMin: 0.4500
          RangeMax: 10
            Ranges: [640x1 single]
       Intensities: []

status = logical
   1

statustext = 
'success'

Shutdown the timers used by sample network.

exampleHelperROSShutDownSampleNetwork

Shut down ROS network.

rosshutdown
Shutting down global node /matlab_global_node_91866 with NodeURI http://dcc598343glnxa64:34299/ and MasterURI http://localhost:60383.
Shutting down ROS master on http://172.29.206.170:60383.

Input Arguments

collapse all

ROS subscriber, specified as a Subscriber object handle. You can create the subscriber using rossubscriber.

Timeout for receiving a message, specified as a scalar in seconds.

Output Arguments

collapse all

ROS message, returned as a Message object handle or structure.

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.

Status of the message reception, returned as a logical scalar. If no message is received, status will be false.

Note

Use the status output argument when you use receive for code generation. This will avoid runtime errors and outputs the status instead, which can be reacted to in the calling code.

Status text associated with the message reception, returned as one of the following:

  • 'success' — The message was successfully received.

  • 'timeout' — The message was not received within the specified timeout.

  • 'unknown' — The message was not received due to unknown errors.

Tips

For code generation:

  • Use the status output argument when you call receive in the entry-point function. This will avoid runtime errors and instead, outputs the status of message reception, which can be reacted to in the calling code.

Extended Capabilities

Version History

Introduced in R2019b

expand all