image_transport_codecs package

Generic API working with codecs as plugins

Encoding and decoding of images compressed with any image transport.

Example usage:

from image_transport_codecs import decode, encode
from sensor_msgs.msg import CompressedImage, Image

raw = Image()
... # fill the image
compressed, err = encode(raw, "compressed")
if compressed is None:
  rospy.logerr("Error encoding image: " + err)
  return False
# work with the CompressedImage instance in variable compressed

# beware, for decoding, we do not specify "raw", but the codec used for encoding
raw2, err = decode(compressed, "compressed")
if raw2 is None:
  rospy.logerr("Error encoding image: " + err)
  return False
# work with the Image instance in variable raw2

# or you can work directly with a particular codec if you know which one you want in advance:
from image_transport_codecs import compressed_codec

compressed2, err = compressed_codec.encode(raw)
class image_transport_codecs.CompressedImageContent(format, data)

Bases: object

The part of a compressed message that represents the actual image data (i.e. data that can be passed to an external decoder).

It is not guaranteed for every codec that its encoded messages carry some standalone meaning. If there is no meaning, it will just produce empty content messages.

Variables:
  • format – Format of the image. This should be a string recognized by OpenCV, ffmpeg or similar tools.
  • data – The image content.
image_transport_codecs.decode(compressed, topic_or_codec, config=None)

Decode the given compressed image encoded with any codec into a raw image.

Parameters:
Returns:

Tuple of raw image and error string. If the decoding fails, image is None and error string is filled.

Return type:

(sensor_msgs/Image or None, str)

image_transport_codecs.dict_to_config(d)

Convert configuration dict to dynamic_reconfigure/Config.

Parameters:d (dict or dynamic_reconfigure/Config or None) – Configuration dict (or already the message, in which case it is just returned).
Returns:The config message.
Return type:dynamic_reconfigure/Config
image_transport_codecs.encode(raw, topic_or_codec, config=None)

Encode the given raw image into a compressed image with a suitable codec.

Parameters:
  • raw (sensor_msgs/Image) – The raw image.
  • topic_or_codec (str) – Name of the topic where this image should be published or explicit name of the codec.
  • config (dict or dynamic_reconfigure/Config or None) – Configuration of the encoding process. You can use the same values as those offered by dynamic reconfigure of the corresponding image_transport publisher.
Returns:

Tuple of compressed image and error string. If the compression fails (e.g. wrong image dimensions or bit depth), image is None and error string is filled.

Return type:

(genpy.Message or None, str)

image_transport_codecs.get_compressed_image_content(compressed, topic_or_codec, match_format='')

Return the part of the encoded message that represents the actual image data (i.e. the part that can be passed to external decoders or saved to a file). If the codec messages have no such meaning, empty result is returned.

Parameters:
  • compressed (genpy.Message) – The compressed image.
  • topic_or_codec (str) – Name of the topic this image comes from or explicit name of the codec.
  • match_format (str) – If nonempty, the image data is only returned if their format field would match the given one. The matching should be case-insensitive.
Returns:

If it makes sense, the contained image bytes as first tuple member. If not, empty result. If an error occurred, it is reported in the second tuple member.

Return type:

(CompressedImageContent or None, str)

Helpers for parsing the sensor_msgs/CompressedImage format field

Methods for parsing the values of field sensor_msgs::CompressedImage::format for compressed and compressedDepth codecs.

class image_transport_codecs.parse_compressed_format.CompressedDepthTransportCompressionFormat

Bases: enum.Enum

Compression format of compressedDepth codec (PNG/RVL). RVL is only usable in Noetic.

PNG = 'png'

PNG compression

RVL = 'rvl'

RVL compression (added in Noetic)

class image_transport_codecs.parse_compressed_format.CompressedDepthTransportFormat

Bases: image_transport_codecs.parse_compressed_format.CompressedDepthTransportFormat

Decoded meaning of field sensor_msgs::CompressedImage::format for compressedDepth transport.

Parameters:
  • format (CompressedDepthTransportCompressionFormat) – The compression format (PNG/RVL).
  • format_string (str) – Text version of the compression format (“png”/”rvl”).
  • rawEncoding (str) – Encoding of the raw image (before compression, after decompression).
  • bitDepth (int) – Number of bits used for encoding one raw channel value.

Create new instance of CompressedDepthTransportFormat(format, format_string, raw_encoding, bit_depth)

class image_transport_codecs.parse_compressed_format.CompressedTransportCompressionFormat

Bases: enum.Enum

Compression format of compressed codec (JPEG/PNG).

JPEG = 'jpeg'

JPEG compression

PNG = 'png'

PNG compression

class image_transport_codecs.parse_compressed_format.CompressedTransportFormat

Bases: image_transport_codecs.parse_compressed_format.CompressedTransportFormat

Decoded meaning of field sensor_msgs::CompressedImage::format for compressed transport.

Parameters:
  • format (CompressedTransportCompressionFormat) – The compression format (JPEG/PNG).
  • format_string (str) – Text version of the compression format (“jpeg”/”png”).
  • rawEncoding (str) – Encoding of the raw image (before compression, after decompression).
  • compressedEncoding (str) – Encoding of the compressed image (i.e. bgr8 for JPEG).
  • numChannels (int) – Number of channels of the raw image data (1 for mono/depth images, 3-4 for color).
  • bitDepth (int) – Number of bits used for encoding one raw channel value.
  • isColor (bool) – Whether the image is a color image or not.

Create new instance of CompressedTransportFormat(format, format_string, raw_encoding, compressed_encoding, num_channels, bit_depth, is_color)

image_transport_codecs.parse_compressed_format.extract_compressed_depth_transport_format(image_encoding, compression_format)

Create the CompressedDepthTransportFormat structure for the given raw image compressed with the given method.

Parameters:
Returns:

Tuple of the parsed structure or error string. If the parsing fails, structure is None and error string is filled.

Return type:

(CompressedDepthTransportFormat or None, str)

image_transport_codecs.parse_compressed_format.extract_compressed_transport_format(image_encoding, compression_format)

Create the CompressedTransportFormat structure for the given raw image compressed with the given method.

Parameters:
Returns:

Tuple of the parsed structure or error string. If the parsing fails, structure is None and error string is filled.

Return type:

(CompressedTransportFormat or None, str)

image_transport_codecs.parse_compressed_format.guess_any_compressed_image_transport_format(image)

Parse the string from field sensor_msgs/CompressedImage.format using either compressed or compressedDepth transport. Selection between the two formats is done automatically and it might peek into the first 64 bytes of the compressed byte stream in the image.

Parameters:image (sensor_msgs/CompressedImage) – The image whose transport format should be parsed.
Returns:Tuple of the parsed formats or error string. If the format belongs to compressed codec, the first tuple item will contain the format structure and the second item will be None. If the format belongs to `compressedDepth codec, the first tuple item will be None and the second item will be the format structure. If the parsing fails, first two items are None and error string is filled in the third item.
Return type:(CompressedTransportFormat or None, CompressedDepthTransportFormat or None, str)
image_transport_codecs.parse_compressed_format.make_compressed_depth_transport_format(format)

Convert the CompressedDepthTransportFormat structure into a string to be filled in field sensor_msgs::CompressedImage::format of compressedDepth transport image.

Parameters:format (CompressedDepthTransportFormat) – The format to convert.
Returns:The string for the format field.
Return type:(str or None, str)
image_transport_codecs.parse_compressed_format.make_compressed_transport_format(format)

Convert the CompressedTransportFormat structure into a string to be filled in field sensor_msgs::CompressedImage::format of compressed transport image.

Parameters:format (CompressedTransportFormat) – The format to convert.
Returns:The string for the format field.
Return type:(str or None, str)
image_transport_codecs.parse_compressed_format.parse_compressed_depth_transport_format(format)

Parse the string from field sensor_msgs::CompressedImage::format using compressedDepth transport into CompressedTransportFormat structure.

Parameters:format (str or sensor_msgs/CompressedImage) – The format field text, or a sensor_msgs/CompressedImage.
Returns:Tuple of the parsed structure or error string. If the parsing fails, structure is None and error string is filled.
Return type:(CompressedTransportFormat or None, str)
image_transport_codecs.parse_compressed_format.parse_compressed_transport_format(format)

Parse the string from field sensor_msgs::CompressedImage::format using compressed transport into CompressedTransportFormat structure.

Parameters:format (str or sensor_msgs/CompressedImage) – The format field text, or a sensor_msgs/CompressedImage.
Returns:Tuple of the parsed structure or error string. If the parsing fails, structure is None and error string is filled.
Return type:(CompressedTransportFormat or None, str)

Builtin codecs

If you directly know what codec to use, you can use these direct encode/decode APIs to get a speedup.

compressed_codec

Encoding and decoding of images compressed with the ‘compressed’ transport.

image_transport_codecs.compressed_codec.decode(compressed, config=None)

Decode the given sensor_msgs/CompressedImage encoded with “compressedDepth” codec into a raw image.

Parameters:
Returns:

Tuple of raw image and error string. If decoding failed, the image is None and error string is filled.

Return type:

(sensor_msgs/Image or None, str)

image_transport_codecs.compressed_codec.encode(raw, config=None)

Encode the given raw image into a sensor_msgs/CompressedImage with “compressed” codec.

Parameters:
Returns:

Tuple of compressed image and error string. If the compression fails (e.g. wrong image dimensions or bit depth), the image is None and error string is filled.

Return type:

(sensor_msgs/CompressedImage or None, str)

image_transport_codecs.compressed_codec.has_extra_jpeg_options()

Return whether the JPEG encoder has options jpeg_progressive, jpeg_optimize and jpeg_restart_interval.

Returns:Whether the JPEG encoder has options jpeg_progressive, jpeg_optimize and jpeg_restart_interval.
Return type:bool

compressed_depth_codec

Encoding and decoding of images compressed with the ‘compressedDepth’ transport.

image_transport_codecs.compressed_depth_codec.decode(compressed, config=None)

Decode the given sensor_msgs/CompressedImage encoded with “compressedDepth” codec into a raw image.

Parameters:
Returns:

Tuple of raw image and error string. If the decoding fails, image is None and error string is filled.

Return type:

(sensor_msgs/Image or None, str)

image_transport_codecs.compressed_depth_codec.encode(raw, config=None)

Encode the given raw image into a sensor_msgs/CompressedImage with “compressedDepth” codec.

Parameters:
Returns:

Tuple of compressed image and error string. If the compression fails (e.g. wrong image dimensions or bit depth), image is None and error string is filled.

Return type:

(sensor_msgs/CompressedImage or None, str)

image_transport_codecs.compressed_depth_codec.has_rvl()

Whether the RVL encoding is available (should be only on Noetic).

Returns:Whether RVL is available.
Return type:bool