Skip to content

Commit 2c044a2

Browse files
authored
sensor_msgs/CompressedImage: updated description of format field (#184)
Signed-off-by: Martin Pecka <[email protected]>
1 parent 40c3adb commit 2c044a2

File tree

1 file changed

+30
-2
lines changed

1 file changed

+30
-2
lines changed

sensor_msgs/msg/CompressedImage.msg

+30-2
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,34 @@ Header header # Header timestamp should be acquisition time of image
88
# +z should point into to plane of the image
99

1010
string format # Specifies the format of the data
11-
# Acceptable values:
12-
# jpeg, png
11+
# Acceptable values differ by the image transport used:
12+
# - compressed_image_transport:
13+
# ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT]
14+
# where:
15+
# - ORIG_PIXFMT is pixel format of the raw image, i.e.
16+
# the content of sensor_msgs/Image/encoding with
17+
# values from include/sensor_msgs/image_encodings.h
18+
# - CODEC is one of [jpeg, png]
19+
# - COMPRESSED_PIXFMT is only appended for color images
20+
# and is the pixel format used by the compression
21+
# algorithm. Valid values for jpeg encoding are:
22+
# [bgr8, rgb8]. Valid values for png encoding are:
23+
# [bgr8, rgb8, bgr16, rgb16].
24+
# If the field is empty or does not correspond to the
25+
# above pattern, the image is treated as bgr8 or mono8
26+
# jpeg image (depending on the number of channels).
27+
# - compressed_depth_image_transport:
28+
# ORIG_PIXFMT; compressedDepth CODEC
29+
# where:
30+
# - ORIG_PIXFMT is pixel format of the raw image, i.e.
31+
# the content of sensor_msgs/Image/encoding with
32+
# values from include/sensor_msgs/image_encodings.h
33+
# It is usually one of [16UC1, 32FC1].
34+
# - CODEC is one of [png, rvl]
35+
# If the field is empty or does not correspond to the
36+
# above pattern, the image is treated as png image.
37+
# - Other image transports can store whatever values they
38+
# need for successful decoding of the image. Refer to
39+
# documentation of the other transports for details.
40+
1341
uint8[] data # Compressed image buffer

0 commit comments

Comments
 (0)