Main Content

ros2message

Create ROS 2 message structures

Since R2019b

Description

example

msg = ros2message(msgType) creates a structure compatible with ROS 2 messages of type msgType.

msg = rosmessage(pub) creates an empty message determined by the topic published by the ROS 2 publisher pub.

msg = rosmessage(sub) creates an empty message determined by the subscribed topic of the ROS 2 subscriber sub.

msg = ros2message(client) creates an empty message determined by the action associated with the ROS 2 action client, client.

msg = ros2message(server) creates an empty result message determined by the action associated with the ROS 2 action server, server.

Examples

collapse all

Create a ROS 2 string message.

strMsg = ros2message('std_msgs/String')
strMsg = struct with fields:
    MessageType: 'std_msgs/String'
           data: ''

Create an empty ROS 2 laser scan message.

scanMsg = ros2message("sensor_msgs/LaserScan")
scanMsg = struct with fields:
        MessageType: 'sensor_msgs/LaserScan'
             header: [1x1 struct]
          angle_min: 0
          angle_max: 0
    angle_increment: 0
     time_increment: 0
          scan_time: 0
          range_min: 0
          range_max: 0
             ranges: 0
        intensities: 0

Input Arguments

collapse all

Message type for a ROS 2 topic, specified as a character vector.

ROS 2 publisher, specified as a ros2publisher object handle.

ROS 2 subscriber, specified as a ros2subscriber object handle.

ROS 2 action client, specified as a ros2actionclient object handle.

ROS 2 action server, specified as a ros2actionserver object handle.

Output Arguments

collapse all

ROS 2 message for a given topic, returned as a message structure.

Extended Capabilities

Version History

Introduced in R2019b

expand all