Contenido principal

Read Image

Extract image from ROS Image message

  • Read Image ROS 1

Libraries:
ROS Toolbox / ROS

Description

The Read Image block extracts an image from a ROS sensor_msgs/Image or sensor_msgs/CompressedImage message. You can select the ROS message parameters of a topic active on a live ROS network or specify the message parameters separately. The ROS messages are specified as a nonvirtual bus. Use the Subscribe block output to receive a message from a ROS network and input the message to the Read Image block.

Note

When reading ROS image messages from the network, the Data property of the message can exceed the maximum array length set in Simulink®. To increase the maximum array length for all message types in the model, from the Prepare section under Simulation tab, select ROS Toolbox > Variable Size Messages. Uncheck Use default limits for this message type and then in the Maximum length column, increase the length based on the number of pixels in the image.

Examples

Ports

Input

expand all

ROS sensor_msgs/Image or sensor_msgs/CompressedImage message, specified as a nonvirtual bus. You can use the Subscribe block to get a message from an active ROS network.

Data Types: bus

Output

expand all

Extracted image signal from ROS message, returned as an M-by-N-by-3 matrix for color images, and an M-by-N matrix for grayscale images. The matrix contains the pixel data from the Data property of the ROS message.

Data Types: single | double | int8 | int16 | int32 | uint8 | uint16

Alpha channel for image, returned as an M-by-N matrix. This matrix is the same height and width as the image output. Each element has a value in the range [0,1] that indicates the opacity of the corresponding pixel, with a value of 0 being completely transparent.

Note

For CompressedImage messages, the alpha channel returns all zeros if the Show Alpha output port is enabled.

Data Types: single | double | int8 | int16 | int32 | uint8 | uint16

Error code for image conversion, returned as a scalar. The error code values are:

  • 0 — Successfully converted the image message.

  • 1 — Incorrect image encoding. Check that the incoming message encoding matches the Image Encoding parameter.

  • 2 — The dimensions of the image message exceed the limits specified in the Maximum Image Size parameter.

  • 3 — The Data field of the image message was truncated. See Manage Array Sizes for ROS Messages in Simulink to increase the maximum length of the array.

  • 4 — Image decompression failed.

Data Types: uint8

Parameters

expand all

Maximum image size, specified as a two-element [height width] vector.

Click Configure using ROS to set this parameter automatically using an active topic on a ROS network. You must be connected to the ROS network.

Image encoding for the input ImageMsg. Select the supported encoding type which matches the Encoding property of the message. For more information about encoding types, see rosReadImage.

Toggle Alpha channel output port if your encoding supports an Alpha channel.

Dependencies

Only certain encoding types support alpha channels. The Image Encoding parameter determines if this parameter appears in the block mask.

Toggle the ErrorCode port to monitor errors.

Toggle variable-size signal output. Variable-sized signals should only be used if the image size is expected to change over time. For more information about variable sized signals, see Variable-Size Signal Basics (Simulink).

Extended Capabilities

expand all

Version History

Introduced in R2019b