Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Add message definitions for ROS2 jazzy (#6)
### Changelog Add message definitions for ROS2 jazzy ### Docs None ### Description Applies foxglove/rosmsg-msgs-common#21 to this repo. I have only made a few corrections: - Remove `service_msgs` and `type_description_interfaces` as I don't consider these messages definitions very common - Adds `tf2_msgs` which were not included in the original PR --- <details> <summary>diff -r msgdefs/ros2iron/ msgdefs/ros2jazzy > /tmp/diff.txt</summary> <pre> Only in msgdefs/ros2jazzy/geometry_msgs/msg: PolygonInstance.msg Only in msgdefs/ros2jazzy/geometry_msgs/msg: PolygonInstanceStamped.msg diff -r msgdefs/ros2iron/geometry_msgs/msg/TransformStamped.msg msgdefs/ros2jazzy/geometry_msgs/msg/TransformStamped.msg 5c5 < # <a href="https://index.ros.org/p/tf2/">tf2</a> package. --- > # <a href="https://docs.ros.org/en/rolling/p/tf2/">tf2</a> package. Only in msgdefs/ros2jazzy/geometry_msgs/msg: VelocityStamped.msg diff -r msgdefs/ros2iron/nav_msgs/msg/OccupancyGrid.msg msgdefs/ros2jazzy/nav_msgs/msg/OccupancyGrid.msg 7,8c7,8 < # The map data, in row-major order, starting with (0,0). < # Cell (1, 0) will be listed second, representing the next cell in the x direction. --- > # The map data, in row-major order, starting with (0,0). > # Cell (1, 0) will be listed second, representing the next cell in the x direction. 10c10 < # The values inside are application dependent, but frequently, --- > # The values inside are application dependent, but frequently, 12c12 < # -1 represents unknown. --- > # -1 represents unknown. diff -r msgdefs/ros2iron/rcl_interfaces/msg/FloatingPointRange.msg msgdefs/ros2jazzy/rcl_interfaces/msg/FloatingPointRange.msg 10c10 < # --- > # diff -r msgdefs/ros2iron/rcl_interfaces/msg/IntegerRange.msg msgdefs/ros2jazzy/rcl_interfaces/msg/IntegerRange.msg 19c19 < # --- > # diff -r msgdefs/ros2iron/rcl_interfaces/msg/Log.msg msgdefs/ros2jazzy/rcl_interfaces/msg/Log.msg 3c3 < ## --- > ## 15c15 < byte DEBUG=10 --- > uint8 DEBUG=10 19c19 < byte INFO=20 --- > uint8 INFO=20 23c23 < byte WARN=30 --- > uint8 WARN=30 26c26 < byte ERROR=40 --- > uint8 ERROR=40 29c29 < byte FATAL=50 --- > uint8 FATAL=50 diff -r msgdefs/ros2iron/rcl_interfaces/msg/ParameterDescriptor.msg msgdefs/ros2jazzy/rcl_interfaces/msg/ParameterDescriptor.msg 49c49 < # --- > # 89c89 < # --- > # diff -r msgdefs/ros2iron/rcl_interfaces/msg/ParameterEventDescriptors.msg msgdefs/ros2jazzy/rcl_interfaces/msg/ParameterEventDescriptors.msg 137c137 < # --- > # 177c177 < # --- > # diff -r msgdefs/ros2iron/rcl_interfaces/msg/SetParametersResult.msg msgdefs/ros2jazzy/rcl_interfaces/msg/SetParametersResult.msg 5,6c5,6 < # Reason why the setting was either successful or a failure. This should only be < # used for logging and user interfaces. --- > # Reason why the setting was a failure. On success, the contents of this field > # are undefined. This should only be used for logging and user interfaces. diff -r msgdefs/ros2iron/sensor_msgs/msg/CompressedImage.msg msgdefs/ros2jazzy/sensor_msgs/msg/CompressedImage.msg 11,12c11,39 < # Acceptable values: < # jpeg, png, tiff --- > # Acceptable values differ by the image transport used: > # - compressed_image_transport: > # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # - CODEC is one of [jpeg, png, tiff] > # - COMPRESSED_PIXFMT is only appended for color images > # and is the pixel format used by the compression > # algorithm. Valid values for jpeg encoding are: > # [bgr8, rgb8]. Valid values for png encoding are: > # [bgr8, rgb8, bgr16, rgb16]. > # If the field is empty or does not correspond to the > # above pattern, the image is treated as bgr8 or mono8 > # jpeg image (depending on the number of channels). > # - compressed_depth_image_transport: > # ORIG_PIXFMT; compressedDepth CODEC > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # It is usually one of [16UC1, 32FC1]. > # - CODEC is one of [png, rvl] > # If the field is empty or does not correspond to the > # above pattern, the image is treated as png image. > # - Other image transports can store whatever values they > # need for successful decoding of the image. Refer to > # documentation of the other transports for details. diff -r msgdefs/ros2iron/sensor_msgs/msg/NavSatFix.msg msgdefs/ros2jazzy/sensor_msgs/msg/NavSatFix.msg 66a67 > int8 STATUS_UNKNOWN = -2 # status is not yet set 72c73 < int8 status --- > int8 status -2 # STATUS_UNKNOWN 76a78 > uint16 SERVICE_UNKNOWN = 0 # Remember service is a bitfield, so checking (service & SERVICE_UNKNOWN) will not work. Use == instead. diff -r msgdefs/ros2iron/sensor_msgs/msg/NavSatStatus.msg msgdefs/ros2jazzy/sensor_msgs/msg/NavSatStatus.msg 6a7 > int8 STATUS_UNKNOWN = -2 # status is not yet set 12c13 < int8 status --- > int8 status -2 # STATUS_UNKNOWN 16a18 > uint16 SERVICE_UNKNOWN = 0 # Remember service is a bitfield, so checking (service & SERVICE_UNKNOWN) will not work. Use == instead. diff -r msgdefs/ros2iron/trajectory_msgs/msg/MultiDOFJointTrajectory.msg msgdefs/ros2jazzy/trajectory_msgs/msg/MultiDOFJointTrajectory.msg 6c6 < # that has the same length as the array of joint names, and has the same order of joints as --- > # that has the same length as the array of joint names, and has the same order of joints as diff -r msgdefs/ros2iron/visualization_msgs/msg/InteractiveMarkerControl.msg msgdefs/ros2jazzy/visualization_msgs/msg/InteractiveMarkerControl.msg 107a108 > int32 ARROW_STRIP=12 141c142 < # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) --- > # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ARROW_STRIP, etc.) 149c150 < # a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] --- > # a format acceptable to (resource retriever)[https://docs.ros.org/en/rolling/p/resource_retriever/] 228,229c229,257 < # Acceptable values: < # jpeg, png, tiff --- > # Acceptable values differ by the image transport used: > # - compressed_image_transport: > # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # - CODEC is one of [jpeg, png, tiff] > # - COMPRESSED_PIXFMT is only appended for color images > # and is the pixel format used by the compression > # algorithm. Valid values for jpeg encoding are: > # [bgr8, rgb8]. Valid values for png encoding are: > # [bgr8, rgb8, bgr16, rgb16]. > # If the field is empty or does not correspond to the > # above pattern, the image is treated as bgr8 or mono8 > # jpeg image (depending on the number of channels). > # - compressed_depth_image_transport: > # ORIG_PIXFMT; compressedDepth CODEC > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # It is usually one of [16UC1, 32FC1]. > # - CODEC is one of [png, rvl] > # If the field is empty or does not correspond to the > # above pattern, the image is treated as png image. > # - Other image transports can store whatever values they > # need for successful decoding of the image. Refer to > # documentation of the other transports for details. diff -r msgdefs/ros2iron/visualization_msgs/msg/InteractiveMarkerInit.msg msgdefs/ros2jazzy/visualization_msgs/msg/InteractiveMarkerInit.msg 236a237 > int32 ARROW_STRIP=12 270c271 < # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) --- > # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ARROW_STRIP, etc.) 278c279 < # a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] --- > # a format acceptable to (resource retriever)[https://docs.ros.org/en/rolling/p/resource_retriever/] 331,332c332,360 < # Acceptable values: < # jpeg, png, tiff --- > # Acceptable values differ by the image transport used: > # - compressed_image_transport: > # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # - CODEC is one of [jpeg, png, tiff] > # - COMPRESSED_PIXFMT is only appended for color images > # and is the pixel format used by the compression > # algorithm. Valid values for jpeg encoding are: > # [bgr8, rgb8]. Valid values for png encoding are: > # [bgr8, rgb8, bgr16, rgb16]. > # If the field is empty or does not correspond to the > # above pattern, the image is treated as bgr8 or mono8 > # jpeg image (depending on the number of channels). > # - compressed_depth_image_transport: > # ORIG_PIXFMT; compressedDepth CODEC > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # It is usually one of [16UC1, 32FC1]. > # - CODEC is one of [png, rvl] > # If the field is empty or does not correspond to the > # above pattern, the image is treated as png image. > # - Other image transports can store whatever values they > # need for successful decoding of the image. Refer to > # documentation of the other transports for details. diff -r msgdefs/ros2iron/visualization_msgs/msg/InteractiveMarker.msg msgdefs/ros2jazzy/visualization_msgs/msg/InteractiveMarker.msg 219a220 > int32 ARROW_STRIP=12 253c254 < # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) --- > # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ARROW_STRIP, etc.) 261c262 < # a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] --- > # a format acceptable to (resource retriever)[https://docs.ros.org/en/rolling/p/resource_retriever/] 333,334c334,362 < # Acceptable values: < # jpeg, png, tiff --- > # Acceptable values differ by the image transport used: > # - compressed_image_transport: > # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # - CODEC is one of [jpeg, png, tiff] > # - COMPRESSED_PIXFMT is only appended for color images > # and is the pixel format used by the compression > # algorithm. Valid values for jpeg encoding are: > # [bgr8, rgb8]. Valid values for png encoding are: > # [bgr8, rgb8, bgr16, rgb16]. > # If the field is empty or does not correspond to the > # above pattern, the image is treated as bgr8 or mono8 > # jpeg image (depending on the number of channels). > # - compressed_depth_image_transport: > # ORIG_PIXFMT; compressedDepth CODEC > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # It is usually one of [16UC1, 32FC1]. > # - CODEC is one of [png, rvl] > # If the field is empty or does not correspond to the > # above pattern, the image is treated as png image. > # - Other image transports can store whatever values they > # need for successful decoding of the image. Refer to > # documentation of the other transports for details. diff -r msgdefs/ros2iron/visualization_msgs/msg/InteractiveMarkerUpdate.msg msgdefs/ros2jazzy/visualization_msgs/msg/InteractiveMarkerUpdate.msg 267a268 > int32 ARROW_STRIP=12 301c302 < # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) --- > # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ARROW_STRIP, etc.) 309c310 < # a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] --- > # a format acceptable to (resource retriever)[https://docs.ros.org/en/rolling/p/resource_retriever/] 362,363c363,391 < # Acceptable values: < # jpeg, png, tiff --- > # Acceptable values differ by the image transport used: > # - compressed_image_transport: > # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # - CODEC is one of [jpeg, png, tiff] > # - COMPRESSED_PIXFMT is only appended for color images > # and is the pixel format used by the compression > # algorithm. Valid values for jpeg encoding are: > # [bgr8, rgb8]. Valid values for png encoding are: > # [bgr8, rgb8, bgr16, rgb16]. > # If the field is empty or does not correspond to the > # above pattern, the image is treated as bgr8 or mono8 > # jpeg image (depending on the number of channels). > # - compressed_depth_image_transport: > # ORIG_PIXFMT; compressedDepth CODEC > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # It is usually one of [16UC1, 32FC1]. > # - CODEC is one of [png, rvl] > # If the field is empty or does not correspond to the > # above pattern, the image is treated as png image. > # - Other image transports can store whatever values they > # need for successful decoding of the image. Refer to > # documentation of the other transports for details. diff -r msgdefs/ros2iron/visualization_msgs/msg/MarkerArray.msg msgdefs/ros2jazzy/visualization_msgs/msg/MarkerArray.msg 22a23 > int32 ARROW_STRIP=12 56c57 < # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) --- > # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ARROW_STRIP, etc.) 64c65 < # a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] --- > # a format acceptable to (resource retriever)[https://docs.ros.org/en/rolling/p/resource_retriever/] 143,144c144,172 < # Acceptable values: < # jpeg, png, tiff --- > # Acceptable values differ by the image transport used: > # - compressed_image_transport: > # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # - CODEC is one of [jpeg, png, tiff] > # - COMPRESSED_PIXFMT is only appended for color images > # and is the pixel format used by the compression > # algorithm. Valid values for jpeg encoding are: > # [bgr8, rgb8]. Valid values for png encoding are: > # [bgr8, rgb8, bgr16, rgb16]. > # If the field is empty or does not correspond to the > # above pattern, the image is treated as bgr8 or mono8 > # jpeg image (depending on the number of channels). > # - compressed_depth_image_transport: > # ORIG_PIXFMT; compressedDepth CODEC > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # It is usually one of [16UC1, 32FC1]. > # - CODEC is one of [png, rvl] > # If the field is empty or does not correspond to the > # above pattern, the image is treated as png image. > # - Other image transports can store whatever values they > # need for successful decoding of the image. Refer to > # documentation of the other transports for details. diff -r msgdefs/ros2iron/visualization_msgs/msg/Marker.msg msgdefs/ros2jazzy/visualization_msgs/msg/Marker.msg 18a19 > int32 ARROW_STRIP=12 52c53 < # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) --- > # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ARROW_STRIP, etc.) 60c61 < # a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] --- > # a format acceptable to (resource retriever)[https://docs.ros.org/en/rolling/p/resource_retriever/] 139,140c140,168 < # Acceptable values: < # jpeg, png, tiff --- > # Acceptable values differ by the image transport used: > # - compressed_image_transport: > # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # - CODEC is one of [jpeg, png, tiff] > # - COMPRESSED_PIXFMT is only appended for color images > # and is the pixel format used by the compression > # algorithm. Valid values for jpeg encoding are: > # [bgr8, rgb8]. Valid values for png encoding are: > # [bgr8, rgb8, bgr16, rgb16]. > # If the field is empty or does not correspond to the > # above pattern, the image is treated as bgr8 or mono8 > # jpeg image (depending on the number of channels). > # - compressed_depth_image_transport: > # ORIG_PIXFMT; compressedDepth CODEC > # where: > # - ORIG_PIXFMT is pixel format of the raw image, i.e. > # the content of sensor_msgs/Image/encoding with > # values from include/sensor_msgs/image_encodings.h > # It is usually one of [16UC1, 32FC1]. > # - CODEC is one of [png, rvl] > # If the field is empty or does not correspond to the > # above pattern, the image is treated as png image. > # - Other image transports can store whatever values they > # need for successful decoding of the image. Refer to > # documentation of the other transports for details. </pre> </details> --------- Co-authored-by: Maxwell Lin <git@maxwellmlin.com>
- Loading branch information