Skip to content

Commit

Permalink
Add message definitions for ROS2 jazzy (#6)
Browse files Browse the repository at this point in the history
### 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
achim-k and maxwellmlin authored Jan 13, 2025
1 parent 62ba9fe commit 5b4bf99
Show file tree
Hide file tree
Showing 152 changed files with 7,564 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# Goal ID
unique_identifier_msgs/UUID goal_id

# Time when the goal was accepted
builtin_interfaces/Time stamp

================================================================================
MSG: unique_identifier_msgs/UUID
# A universally unique identifier (UUID).
#
# http://en.wikipedia.org/wiki/Universally_unique_identifier
# http://tools.ietf.org/html/rfc4122.html

uint8[16] uuid

Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
# An action goal can be in one of these states after it is accepted by an action
# server.
#
# For more information, see http://design.ros2.org/articles/actions.html

# Indicates status has not been properly set.
int8 STATUS_UNKNOWN = 0

# The goal has been accepted and is awaiting execution.
int8 STATUS_ACCEPTED = 1

# The goal is currently being executed by the action server.
int8 STATUS_EXECUTING = 2

# The client has requested that the goal be canceled and the action server has
# accepted the cancel request.
int8 STATUS_CANCELING = 3

# The goal was achieved successfully by the action server.
int8 STATUS_SUCCEEDED = 4

# The goal was canceled after an external request from an action client.
int8 STATUS_CANCELED = 5

# The goal was terminated by the action server without an external request.
int8 STATUS_ABORTED = 6

# Goal info (contains ID and timestamp).
GoalInfo goal_info

# Action goal state-machine status.
int8 status

================================================================================
MSG: action_msgs/GoalInfo
# Goal ID
unique_identifier_msgs/UUID goal_id

# Time when the goal was accepted
builtin_interfaces/Time stamp

================================================================================
MSG: unique_identifier_msgs/UUID
# A universally unique identifier (UUID).
#
# http://en.wikipedia.org/wiki/Universally_unique_identifier
# http://tools.ietf.org/html/rfc4122.html

uint8[16] uuid

Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
# An array of goal statuses.
GoalStatus[] status_list

================================================================================
MSG: action_msgs/GoalStatus
# An action goal can be in one of these states after it is accepted by an action
# server.
#
# For more information, see http://design.ros2.org/articles/actions.html

# Indicates status has not been properly set.
int8 STATUS_UNKNOWN = 0

# The goal has been accepted and is awaiting execution.
int8 STATUS_ACCEPTED = 1

# The goal is currently being executed by the action server.
int8 STATUS_EXECUTING = 2

# The client has requested that the goal be canceled and the action server has
# accepted the cancel request.
int8 STATUS_CANCELING = 3

# The goal was achieved successfully by the action server.
int8 STATUS_SUCCEEDED = 4

# The goal was canceled after an external request from an action client.
int8 STATUS_CANCELED = 5

# The goal was terminated by the action server without an external request.
int8 STATUS_ABORTED = 6

# Goal info (contains ID and timestamp).
GoalInfo goal_info

# Action goal state-machine status.
int8 status

================================================================================
MSG: action_msgs/GoalInfo
# Goal ID
unique_identifier_msgs/UUID goal_id

# Time when the goal was accepted
builtin_interfaces/Time stamp

================================================================================
MSG: unique_identifier_msgs/UUID
# A universally unique identifier (UUID).
#
# http://en.wikipedia.org/wiki/Universally_unique_identifier
# http://tools.ietf.org/html/rfc4122.html

uint8[16] uuid

Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@

# The stamp should store the time at which this goal was requested.
# It is used by an action server when it tries to preempt all
# goals that were requested before a certain time
builtin_interfaces/Time stamp

# The id provides a way to associate feedback and
# result message with specific goal requests. The id
# specified must be unique.
string id

Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
GoalID goal_id
uint8 status
uint8 PENDING = 0 # The goal has yet to be processed by the action server.
uint8 ACTIVE = 1 # The goal is currently being processed by the action server.
uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
# and has since completed its execution (Terminal State).
uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server
# (Terminal State).
uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
# to some failure (Terminal State).
uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
# because the goal was unattainable or invalid (Terminal State).
uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
# and has not yet completed execution.
uint8 RECALLING = 7 # The goal received a cancel request before it started executing, but
# the action server has not yet confirmed that the goal is canceled.
uint8 RECALLED = 8 # The goal received a cancel request before it started executing
# and was successfully cancelled (Terminal State).
uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not
# be sent over the wire by an action server.

# Allow for the user to associate a string with GoalStatus for debugging.
string text

================================================================================
MSG: actionlib_msgs/GoalID

# The stamp should store the time at which this goal was requested.
# It is used by an action server when it tries to preempt all
# goals that were requested before a certain time
builtin_interfaces/Time stamp

# The id provides a way to associate feedback and
# result message with specific goal requests. The id
# specified must be unique.
string id

Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
# Stores the statuses for goals that are currently being tracked
# by an action server
std_msgs/Header header
GoalStatus[] status_list

================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data
# in a particular coordinate frame.

# Two-integer timestamp that is expressed as seconds and nanoseconds.
builtin_interfaces/Time stamp

# Transform frame with which this data is associated.
string frame_id

================================================================================
MSG: actionlib_msgs/GoalStatus
GoalID goal_id
uint8 status
uint8 PENDING = 0 # The goal has yet to be processed by the action server.
uint8 ACTIVE = 1 # The goal is currently being processed by the action server.
uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
# and has since completed its execution (Terminal State).
uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server
# (Terminal State).
uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
# to some failure (Terminal State).
uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
# because the goal was unattainable or invalid (Terminal State).
uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
# and has not yet completed execution.
uint8 RECALLING = 7 # The goal received a cancel request before it started executing, but
# the action server has not yet confirmed that the goal is canceled.
uint8 RECALLED = 8 # The goal received a cancel request before it started executing
# and was successfully cancelled (Terminal State).
uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not
# be sent over the wire by an action server.

# Allow for the user to associate a string with GoalStatus for debugging.
string text

================================================================================
MSG: actionlib_msgs/GoalID

# The stamp should store the time at which this goal was requested.
# It is used by an action server when it tries to preempt all
# goals that were requested before a certain time
builtin_interfaces/Time stamp

# The id provides a way to associate feedback and
# result message with specific goal requests. The id
# specified must be unique.
string id

Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
# Duration defines a period between two time points.
# Messages of this datatype are of ROS Time following this design:
# https://design.ros2.org/articles/clock_and_time.html

# Seconds component, range is valid over any possible int32 value.
int32 sec

# Nanoseconds component in the range of [0, 1e9).
uint32 nanosec

Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# This message communicates ROS Time defined here:
# https://design.ros2.org/articles/clock_and_time.html

# The seconds component, valid over all int32 values.
int32 sec

# The nanoseconds component, valid in the range [0, 1e9).
uint32 nanosec

Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
# This message is used to send diagnostic information about the state of the robot.
std_msgs/Header header # for timestamp
DiagnosticStatus[] status # an array of components being reported on

================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data
# in a particular coordinate frame.

# Two-integer timestamp that is expressed as seconds and nanoseconds.
builtin_interfaces/Time stamp

# Transform frame with which this data is associated.
string frame_id

================================================================================
MSG: diagnostic_msgs/DiagnosticStatus
# This message holds the status of an individual component of the robot.

# Possible levels of operations.
byte OK=0
byte WARN=1
byte ERROR=2
byte STALE=3

# Level of operation enumerated above.
byte level
# A description of the test/component reporting.
string name
# A description of the status.
string message
# A hardware unique string.
string hardware_id
# An array of values associated with the status.
KeyValue[] values


================================================================================
MSG: diagnostic_msgs/KeyValue
# What to label this value when viewing.
string key
# A value to track over time.
string value

Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
# This message holds the status of an individual component of the robot.

# Possible levels of operations.
byte OK=0
byte WARN=1
byte ERROR=2
byte STALE=3

# Level of operation enumerated above.
byte level
# A description of the test/component reporting.
string name
# A description of the status.
string message
# A hardware unique string.
string hardware_id
# An array of values associated with the status.
KeyValue[] values


================================================================================
MSG: diagnostic_msgs/KeyValue
# What to label this value when viewing.
string key
# A value to track over time.
string value

Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# What to label this value when viewing.
string key
# A value to track over time.
string value

Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
# This expresses acceleration in free space broken into its linear and angular parts.
Vector3 linear
Vector3 angular

================================================================================
MSG: geometry_msgs/Vector3
# This represents a vector in free space.

# This is semantically different than a point.
# A vector is always anchored at the origin.
# When a transform is applied to a vector, only the rotational component is applied.

float64 x
float64 y
float64 z

================================================================================
MSG: geometry_msgs/Vector3
# This represents a vector in free space.

# This is semantically different than a point.
# A vector is always anchored at the origin.
# When a transform is applied to a vector, only the rotational component is applied.

float64 x
float64 y
float64 z

Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# An accel with reference coordinate frame and timestamp
std_msgs/Header header
Accel accel

================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data
# in a particular coordinate frame.

# Two-integer timestamp that is expressed as seconds and nanoseconds.
builtin_interfaces/Time stamp

# Transform frame with which this data is associated.
string frame_id

================================================================================
MSG: geometry_msgs/Accel
# This expresses acceleration in free space broken into its linear and angular parts.
Vector3 linear
Vector3 angular

================================================================================
MSG: geometry_msgs/Vector3
# This represents a vector in free space.

# This is semantically different than a point.
# A vector is always anchored at the origin.
# When a transform is applied to a vector, only the rotational component is applied.

float64 x
float64 y
float64 z

Loading

0 comments on commit 5b4bf99

Please sign in to comment.