diff --git a/sensor_msgs/msg/CompressedImage.msg b/sensor_msgs/msg/CompressedImage.msg index 12a724d5..9ef18a30 100644 --- a/sensor_msgs/msg/CompressedImage.msg +++ b/sensor_msgs/msg/CompressedImage.msg @@ -1,13 +1,16 @@ # This message contains a compressed image. -std_msgs/Header header # Header timestamp should be acquisition time of image +std_msgs/Header header # Header timestamp should be acquisition time of image # Header frame_id should be optical frame of camera # origin of frame should be optical center of cameara # +x should point to the right in the image # +y should point down in the image # +z should point into to plane of the image -string format # Specifies the format of the data +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +string pixel_format # Specifies the format of the data # Acceptable values differ by the image transport used: # - compressed_image_transport: # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] @@ -38,4 +41,10 @@ string format # Specifies the format of the data # need for successful decoding of the image. Refer to # documentation of the other transports for details. +string compression_type # Compression type used (jpeg, png, theora, etc) + +uint64 sequence_number # sequence number +uint64 flags # flags (for example: KEYFRAME) +uint8 is_bigendian # is this data bigendian? + uint8[] data # Compressed image buffer