writeImage

Write MATLAB image to ROS image message

Description

example

writeImage(msg,img) converts the MATLAB® image, img, to a message object and stores the ROS compatible image data in the message object, 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 property of the message.

writeImage(msg,img,alpha) converts the MATLAB image, img, to a message object. 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.

Examples

collapse all

Read an image.

image = imread('imageMap.png');

Create a ROS image message. Specify the default encoding for the image. Write the image to the message.

msg = rosmessage('sensor_msgs/Image');
msg.Encoding = 'rgb8';
writeImage(msg,image);

Input Arguments

collapse all

'sensor_msgs/Image' ROS image message, specified as an Image object handle. 'sensor_msgs/Image' image messages are not supported.

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.

Tips

You must specify the correct encoding of the input image in the Encoding property 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 property of the message.

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

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.

See Also

Introduced in R2019b