Contenu principal

rosWriteImage

Write MATLAB image to ROS or ROS 2 image message

Since R2021a

Description

msgOut = rosWriteImage(msg,img) converts the MATLAB® image, img, to a message structure and stores the ROS or ROS 2 compatible image data in the message structure, msg. The message must be a 'sensor_msgs/Image' message. 'sensor_msgs/CompressedImage' messages are not supported. The function does not perform any color space conversion, so the img input needs to have the encoding that you specify in the encoding field of the message.

msgOut = rosWriteImage(msg,img,alpha) converts the MATLAB image, img, to a message structure. If the image encoding supports an alpha channel (rgba or bgra family), specify this alpha channel in alpha. Alternatively, the input image can store the alpha channel as its fourth channel.

msgOut = rosWriteImage(___,"Encoding",encodingParam) specifies the encoding of the image message as a name-value argument using any of the previous input arguments. If the Encoding field of the message is not set, use this syntax to set the field.

Input Arguments

collapse all

ROS or ROS 2 'sensor_msgs/Image' message, specified as a message structure.

Image, specified as a matrix representing a grayscale or RGB image or as an m-by-n-by-3 array, depending on the sensor image.

Alpha channel, specified as a uint8 grayscale image. Alpha must be the same size and data type as img.

Encoding of image message, specified as a string scalar. Using this input argument overwrites the Encoding field of the input msg. For more information, see ROS Image Encoding.

Outputs

collapse all

ROS or ROS 2 'sensor_msgs/Image' image message, specified as a message structure. 'sensor_msgs/CompressedImage' messages are not supported.

You can use the same variable for the input and output argument to directly assign to the existing message.

img = uint8(10*rand(128,128,3));
msg = rosmessage("sensor_msgs/Image","DataFormat","struct");
msg = rosWriteImage(msg,img,"Encoding","rgb8");

Tips

You must specify the correct encoding of the input image in the encoding field of the image message. If you do not specify the image encoding before calling the function, the default encoding, rgb8, is used (3-channel RGB image with uint8 values). The function does not perform any color space conversion, so the img input needs to have the encoding that you specify in the encoding field of the message.

All encoding types supported for the rosReadImage are also supported in this function. For more information on supported encoding types and their representations in MATLAB, see rosReadImage.

Bayer-encoded images (bayer_rggb8, bayer_bggr8, bayer_gbrg8, bayer_grbg8, and their 16-bit equivalents) must be given as 8-bit or 16-bit single-channel images or they do not encode.

Extended Capabilities

expand all

Version History

Introduced in R2021a