diff --git a/diagnostic_msgs/QUALITY_DECLARATION.md b/diagnostic_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..ae9ba815 --- /dev/null +++ b/diagnostic_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,114 @@ +This document is a declaration of software quality for the `diagnostic_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `diagnostic_msgs` Quality Declaration + +The package `diagnostic_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`diagnostic_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`diagnostic_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`diagnostic_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`diagnostic_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`diagnostic_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`diagnostic_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`diagnostic_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `diagnostic_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`diagnostic_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`diagnostic_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/diagnostic_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`diagnostic_msgs` has the following runtime ROS dependencies: +* `builtin_interfaces` +* `geometry_msgs` +* `rosidl_default_runtime` +* `std_msgs` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`diagnostic_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`diagnostic_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/diagnostic_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/diagnostic_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/diagnostic_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/diagnostic_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/diagnostic_msgs/README.md b/diagnostic_msgs/README.md new file mode 100644 index 00000000..0f06adb5 --- /dev/null +++ b/diagnostic_msgs/README.md @@ -0,0 +1,17 @@ +# diagnostic_msgs + +This package provides several messages and services for ROS node diagnostics. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [DiagnosticArray](msg/DiagnosticArray.msg): Used to send diagnostic information about the state of the robot. +* [DiagnosticStatus](msg/DiagnosticStatus.msg): Holds the status of an individual component of the robot. +* [KeyValue](msg/KeyValue.msg): Associates diagnostic values with their labels. + +## Services (.srv) +* [AddDiagnostics](srv/AddDiagnostics.srv): Used as part of the process for loading analyzers at runtime, not for use as a standalone service. +* [SelfTest](srv/SelfTest.srv): Call this service to perform a diagnostic check. + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/diagnostic_msgs/msg/KeyValue.msg b/diagnostic_msgs/msg/KeyValue.msg index 57598cfd..2362c504 100644 --- a/diagnostic_msgs/msg/KeyValue.msg +++ b/diagnostic_msgs/msg/KeyValue.msg @@ -1,4 +1,3 @@ - # What to label this value when viewing. string key # A value to track over time. diff --git a/geometry_msgs/QUALITY_DECLARATION.md b/geometry_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..18bda6d8 --- /dev/null +++ b/geometry_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,112 @@ +This document is a declaration of software quality for the `geometry_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `geometry_msgs` Quality Declaration + +The package `geometry_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`geometry_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`geometry_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`geometry_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`geometry_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`geometry_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`geometry_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`geometry_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `geometry_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`geometry_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`geometry_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/geometry_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`geometry_msgs` has the following runtime ROS dependencies: +* `rosidl_default_runtime` +* `std_msgs` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`geometry_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`geometry_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/geometry_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/geometry_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/geometry_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/geometry_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/geometry_msgs/README.md b/geometry_msgs/README.md new file mode 100644 index 00000000..9cf5bf9f --- /dev/null +++ b/geometry_msgs/README.md @@ -0,0 +1,40 @@ +# geometry_msgs + +This package provides messages for common geometric primitives such as points, vectors, and poses. These primitives are designed to provide a common data type and facilitate interoperability throughout the system. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [Accel](msg/Accel.msg): Expresses acceleration in free space broken into its linear and angular parts. +* [AccelStamped](msg/AccelStamped.msg): An accel with reference coordinate frame and timestamp. +* [AccelWithCovariance](msg/AccelWithCovariance.msg): Acceleration in free space with uncertainty. +* [AccelWithCovarianceStamped](msg/AccelWithCovarianceStamped.msg): An estimated accel with reference coordinate frame and timestamp. +* [Inertia](msg/Inertia.msg): Expresses the inertial properties of a link. +* [InertiaStamped](msg/InertiaStamped.msg): An Inertia with reference coordinate frame and timestamp. +* [Point32](msg/Point32.msg): The position of a 3-dimensional point in free space, with 32-bit fields. +* [Point](msg/Point.msg): The position of a 3-dimensional point in free space. +* [PointStamped](msg/PointStamped.msg): Point with reference coordinate frame and timestamp. +* [Polygon](msg/Polygon.msg): A specification of a polygon where the first and last points are assumed to be connected. +* [PolygonStamped](msg/PolygonStamped.msg): A Polygon with reference coordinate frame and timestamp. +* [Pose2D](msg/Pose2D.msg): **Deprecated as of Foxy and will potentially be removed in any following release.** +* [PoseArray](msg/PoseArray.msg): An array of poses with a header for global reference. +* [Pose](msg/Pose.msg): A representation of pose in free space, composed of position and orientation. +* [PoseStamped](msg/PoseStamped.msg): A Pose with reference coordinate frame and timestamp. +* [PoseWithCovariance](msg/PoseWithCovariance.msg): A pose in free space with uncertainty. +* [PoseWithCovarianceStamped](msg/PoseWithCovarianceStamped.msg): An estimated pose with a reference coordinate frame and timestamp. +* [Quaternion](msg/Quaternion.msg): An orientation in free space in quaternion form. +* [QuaternionStamped](msg/QuaternionStamped.msg): An orientation with reference coordinate frame and timestamp. +* [Transform](msg/Transform.msg): The transform between two coordinate frames in free space. +* [TransformStamped](msg/TransformStamped.msg): A transform from coordinate frame header.frame_id to the coordinate frame child_frame_id. +* [Twist](msg/Twist.msg): Velocity in 3-dimensional free space broken into its linear and angular parts. +* [TwistStamped](msg/TwistStamped.msg): A twist with reference coordinate frame and timestamp. +* [TwistWithCovariance](msg/TwistWithCovariance.msg): Velocity in 3-dimensional free space with uncertainty. +* [TwistWithCovarianceStamped](msg/TwistWithCovarianceStamped.msg): An estimated twist with reference coordinate frame and timestamp. +* [Vector3](msg/Vector3.msg): Represents a vector in 3-dimensional free space. +* [Vector3Stamped](msg/Vector3Stamped.msg): Represents a Vector3 with reference coordinate frame and timestamp. +* [Wrench](msg/Wrench.msg): Represents force in free space, separated into its linear and angular parts. +* [WrenchStamped](msg/WrenchStamped.msg): A wrench with reference coordinate frame and timestamp. + + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/geometry_msgs/msg/Inertia.msg b/geometry_msgs/msg/Inertia.msg index 8903ac27..8b214dfb 100644 --- a/geometry_msgs/msg/Inertia.msg +++ b/geometry_msgs/msg/Inertia.msg @@ -1,4 +1,3 @@ - # Mass [kg] float64 m diff --git a/nav_msgs/QUALITY_DECLARATION.md b/nav_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..406a8f07 --- /dev/null +++ b/nav_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,114 @@ +This document is a declaration of software quality for the `nav_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `nav_msgs` Quality Declaration + +The package `nav_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`nav_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`nav_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`nav_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`nav_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`nav_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`nav_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`nav_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `nav_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`nav_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`nav_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/nav_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`nav_msgs` has the following runtime ROS dependencies: +* `builtin_interfaces` +* `geometry_msgs` +* `rosidl_default_runtime` +* `std_msgs` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`nav_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`nav_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/nav_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/nav_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/nav_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/nav_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/nav_msgs/README.md b/nav_msgs/README.md new file mode 100644 index 00000000..16cff99e --- /dev/null +++ b/nav_msgs/README.md @@ -0,0 +1,22 @@ +# nav_msgs + +This package provides several messages and services for robotic navigation. + +For more information about the navigation2 stack in ROS 2, see https://ros-planning.github.io/navigation2/. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [GridCells](msg/GridCells.msg): An array of cells in a 2D grid. +* [MapMetaData](msg/MapMetaData.msg): Basic information about the characteristics of the OccupancyGrid. +* [OccupancyGrid](msg/OccupancyGrid.msg): Represents a 2-D grid map, in which each cell represents the probability of occupancy. +* [Odometry](msg/Odometry.msg): This represents an estimate of a position and velocity in free space. +* [Path](msg/Path.msg): An array of poses that represents a Path for a robot to follow. + +## Services (.srv) +* [GetMap](srv/GetMap.srv): Get the map as a nav_msgs/OccupancyGrid. +* [GetPlan](srv/GetPlan.srv): Get a plan from the current position to the goal Pose. +* [SetMap](srv/SetMap.srv): Set a new map together with an initial pose. + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/nav_msgs/msg/MapMetaData.msg b/nav_msgs/msg/MapMetaData.msg index b11b0758..9f37e3f5 100644 --- a/nav_msgs/msg/MapMetaData.msg +++ b/nav_msgs/msg/MapMetaData.msg @@ -1,4 +1,4 @@ -# This hold basic information about the characterists of the OccupancyGrid +# This hold basic information about the characteristics of the OccupancyGrid # The time at which the map was loaded builtin_interfaces/Time map_load_time diff --git a/sensor_msgs/QUALITY_DECLARATION.md b/sensor_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..8707b28e --- /dev/null +++ b/sensor_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,136 @@ +This document is a declaration of software quality for the `sensor_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `sensor_msgs` Quality Declaration + +The package `sensor_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`sensor_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`sensor_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `include`, `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`sensor_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`sensor_msgs` contains C++ code and is therefore concerned with ABI stability. It will not break ABI stability within a released ROS distribution. + +## Change Control Process [2] + +`sensor_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`sensor_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`sensor_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `sensor_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There is an automated test which runs a linter that ensures each file has a license statement. + +Most recent test results can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/sensor_msgs/copyright/) + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +### Feature Testing [4.i] + +Most of the features in sensor_msgs have corresponding tests which simulate typical usage, and they are located in the `test` directory. +New features are required to have tests before being added. + +Results of these feature tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/(root)/sensor_msgs/) + +### Public API Testing [4.ii] + +Each part of the public non-generated C++ API has tests, and new additions or changes to the public API require tests before being added. +The tests aim to cover both typical usage and corner cases, but are quantified by contributing to code coverage. + +Results of these API tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/(root)/sensor_msgs/) + +### Coverage [4.iii] + +`sensor_msgs` does not currently track test coverage. + +### Performance [4.iv] + +`sensor_msgs` does not currently have performance tests. + +### Linters and Static Analysis [4.v] + +`sensor_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/sensor_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`sensor_msgs` has the following runtime ROS dependencies: +* `builtin_interfaces` +* `geometry_msgs` +* `rosidl_default_runtime` +* `std_msgs` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`sensor_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`sensor_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/sensor_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/sensor_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/sensor_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/sensor_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/sensor_msgs/README.md b/sensor_msgs/README.md new file mode 100644 index 00000000..667e5365 --- /dev/null +++ b/sensor_msgs/README.md @@ -0,0 +1,51 @@ +](msg/# sensor_msgs + +This package provides many messages and services relating to sensor devices. + +Many of these messages were ported from ROS 1 and a lot of still-relevant documentation can be found through the [ROS 1 sensor_msgs wiki](http://wiki.ros.org/sensor_msgs?distro=noetic). + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## sensor_msgs c++ API +This package provides some common C++ functionality relating to manipulating a couple of particular sensor_msgs messages. + +* [fill_image.hpp](include/sensors_msgs/fill_image.hpp): Fill a Image message from type-erased data pointer. +* [image_encodings.hpp](include/sensor_msgs/image_encodings): Definitions and functionality relating to image encodings. +* [point_cloud_conversion.hpp](include/sensor_msgs/point_cloud_conversion.hpp): Functionality for converting between the deprecated PointCloud and PointCloud2 messages. +* [point_cloud2_iterator.hpp](include/sensor_msgs/point_cloud2_iterator.hpp): Tools for modifying and parsing PointCloud2 messages. +* [point_field_conversion.hpp](include/sensor_msgs/point_field_conversion.hpp): A type to enum mapping for the different PointField types, and methods to read and write in a PointCloud2 buffer for the different PointField types. + +## Messages (.msg) +* [BatteryState](msg/BatteryState.msg): Describes the power state of the battery. +* [CameraInfo](msg/CameraInfo.msg): Meta information for a camera. +* [ChannelFloat32](msg/ChannelFloat32.msg): Holds optional data associated with each point in a PointCloud message. +* [CompressedImage](msg/CompressedImage.msg): A compressed image. +* [FluidPressure](msg/FluidPressure.msg): Single pressure reading for fluids (air, water, etc) like atmospheric and barometric pressures. +* [Illuminance](msg/Illuminance.msg): Single photometric illuminance measurement. +* [Image](msg/Image.msg): An uncompressed image. +* [Imu](msg/Imu.msg): Holds data from an IMU (Inertial Measurement Unit). +* [JointState](msg/JointState.msg): Holds data to describe the state of a set of torque controlled joints. +* [JoyFeedbackArray](msg/JoyFeedbackArray.msg): An array of JoyFeedback messages. +* [JoyFeedback](msg/JoyFeedback.msg): Describes user feedback in a joystick, like an LED, rumble pad, or buzzer. +* [Joy](msg/Joy.msg): Reports the state of a joystick's axes and buttons. +* [LaserEcho](msg/LaserEcho.msg): A submessage of MultiEchoLaserScan and is not intended to be used separately. +* [LaserScan](msg/LaserScan.msg): Single scan from a planar laser range-finder. +* [MagneticField](msg/MagneticField.msg): Measurement of the Magnetic Field vector at a specific location. +* [MultiDOFJointState](msg/MultiDOFJointState.msg): Representation of state for joints with multiple degrees of freedom, following the structure of JointState. +* [MultiEchoLaserScan](msg/MultiEchoLaserScan.msg): Single scan from a multi-echo planar laser range-finder. +* [NavSatFix](msg/NavSatFix.msg): Navigation Satellite fix for any Global Navigation Satellite System. +* [NavSatStatus](msg/NavSatStatus.msg): Navigation Satellite fix status for any Global Navigation Satellite System. +* [PointCloud2](msg/PointCloud2.msg): Holds a collection of N-dimensional points, which may contain additional information such as normals, intensity, etc. +* [PointCloud](msg/PointCloud.msg): **THIS MESSAGE IS DEPRECATED AS OF FOXY, use PointCloud2 instead** +* [PointField](msg/PointField.msg): Holds the description of one point entry in the PointCloud2 message format. +* [Range](msg/Range.msg): Single range reading from an active ranger that emits energy and reports one range reading that is valid along an arc at the distance measured. +* [RegionOfInterest](msg/RegionOfInterest.msg): Used to specify a region of interest within an image. +* [RelativeHumidity](msg/RelativeHumidity.msg): A single reading from a relative humidity sensor. +* [Temperature](msg/Temperature.msg): A single temperature reading. +* [TimeReference](msg/TimeReference.msg): Measurement from an external time source not actively synchronized with the system clock. + +## Services (.srv) +* [SetCameraInfo](srv/SetCameraInfo.srv): Request that a camera stores the given CameraInfo as that camera's calibration information. + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/sensor_msgs/msg/JoyFeedback.msg b/sensor_msgs/msg/JoyFeedback.msg index 5833796c..153cc093 100644 --- a/sensor_msgs/msg/JoyFeedback.msg +++ b/sensor_msgs/msg/JoyFeedback.msg @@ -1,4 +1,3 @@ - # Declare of the type of feedback uint8 TYPE_LED = 0 uint8 TYPE_RUMBLE = 1 diff --git a/shape_msgs/QUALITY_DECLARATION.md b/shape_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..15aa9a4a --- /dev/null +++ b/shape_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,112 @@ +This document is a declaration of software quality for the `shape_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `shape_msgs` Quality Declaration + +The package `shape_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`shape_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`shape_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`shape_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`shape_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`shape_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`shape_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`shape_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `shape_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`shape_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`shape_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/shape_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`shape_msgs` has the following runtime ROS dependencies: +* `geometry_msgs` +* `rosidl_default_runtime` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`shape_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`shape_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/shape_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/shape_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/shape_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/shape_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/shape_msgs/README.md b/shape_msgs/README.md new file mode 100644 index 00000000..8fde83a4 --- /dev/null +++ b/shape_msgs/README.md @@ -0,0 +1,14 @@ +# shape_msgs + +This package provides several messages and services for describing 3-dimensional shapes. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [Mesh](msg/Mesh.msg): Holds information describing a mesh for visualization and collision detections. +* [MeshTriangle](msg/MeshTriangle.msg): A single triangle of a mesh. +* [Plane](msg/Plane.msg): Representation of a plane, using the plane equation ax + by + cz + d = 0. +* [SolidPrimitive](msg/SolidPrimitive.msg): Describe a simple shape primitive like a box, a sphere, a cylinder, and a cone. + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/std_msgs/QUALITY_DECLARATION.md b/std_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..da7d48bb --- /dev/null +++ b/std_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,112 @@ +This document is a declaration of software quality for the `std_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `std_msgs` Quality Declaration + +The package `std_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`std_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`std_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`std_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`std_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`std_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`std_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`std_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `std_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`std_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`std_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/std_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`std_msgs` has the following runtime ROS dependencies: +* `builtin_interfaces` +* `rosidl_default_runtime` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`std_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`std_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/std_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/std_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/std_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/std_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/std_msgs/README.md b/std_msgs/README.md new file mode 100644 index 00000000..55f6d2f5 --- /dev/null +++ b/std_msgs/README.md @@ -0,0 +1,48 @@ +# std_msgs + +`std_msgs` provides many basic message types. Only a few messages are intended for incorporation into higher-level messages. The primitive and primitive array types should generally not be relied upon for long-term use. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [ColorRGBA](msg/ColorRGBA.msg): A single RGBA value for representing colors. +* [Empty](msg/Empty.msg): Does not hold any information, useful when the sending of a message would provide sufficient information. +* [Header](msg/Header.msg): Standard metadata for higher-level stamped data types used to communicate timestamped data in a particular coordinate frame. + +### Primitive Types +`std_msgs` provides the following wrappers for ROS primitive types, which are documented in the msg specification. It also contains the Empty type, which is useful for sending an empty signal. However, these types do not convey semantic meaning about their contents: every message simply has a field called "data". Therefore, while the messages in this package can be useful for quick prototyping, they are NOT intended for "long-term" usage. For ease of documentation and collaboration, we recommend that existing messages be used, or new messages created, that provide meaningful field name(s). + +* [Bool](msg/Bool.msg) +* [Byte](msg/Byte.msg) +* [Char](msg/Char.msg) +* [Float32](msg/Float32.msg) +* [Float64](msg/Float64.msg) +* [Int8](msg/Int8.msg) +* [Int16](msg/Int16.msg) +* [Int32](msg/Int32.msg) +* [Int64](msg/Int64.msg) +* [String](msg/String.msg) +* [UInt8](msg/UInt8.msg) +* [UInt16](msg/UInt16.msg) +* [UInt32](msg/UInt32.msg) +* [UInt64](msg/UInt64.msg) + +### Array Types +`std_msgs` also provides the following "MultiArray" types, which can be useful for storing sensor data. However, the same caveat as above applies: it's usually "better" (in the sense of making the code easier to understand, etc.) when developers use or create non-generic message types (see discussion in this thread for more detail). + +* [ByteMultiArray](msg/ByteMultiArray.msg) +* [Float32MultiArray](msg/Float32MultiArray.msg) +* [Float64MultiArray](msg/Float64MultiArray.msg) +* [Int8MultiArray](msg/Int8MultiArray.msg) +* [Int16MultiArray](msg/Int16MultiArray.msg) +* [Int32MultiArray](msg/Int32MultiArray.msg) +* [Int64MultiArray](msg/Int64MultiArray.msg) +* [MultiArrayDimension](msg/MultiArrayDimension.msg) +* [MultiArrayLayout](msg/MultiArrayLayout.msg) +* [UInt16MultiArray](msg/UInt16MultiArray.msg) +* [UInt32MultiArray](msg/UInt32MultiArray.msg) +* [UInt64MultiArray](msg/UInt64MultiArray.msg) +* [UInt8MultiArray](msg/UInt8MultiArray.msg) + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/std_srvs/QUALITY_DECLARATION.md b/std_srvs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..4657a4fb --- /dev/null +++ b/std_srvs/QUALITY_DECLARATION.md @@ -0,0 +1,111 @@ +This document is a declaration of software quality for the `std_srvs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `std_srvs` Quality Declaration + +The package `std_srvs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`std_srvs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`std_srvs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`std_srvs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`std_srvs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`std_srvs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`std_srvs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`std_srvs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `std_srvs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`std_srvs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`std_srvs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/std_srvs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`std_srvs` has the following runtime ROS dependencies: +* `rosidl_default_runtime` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`std_srvs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`std_srvs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/std_srvs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/std_srvs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/std_srvs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/std_srvs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/std_srvs/README.md b/std_srvs/README.md new file mode 100644 index 00000000..1ecadb18 --- /dev/null +++ b/std_srvs/README.md @@ -0,0 +1,14 @@ +# std_srvs + +This package provides several service definitions for standard but simple ROS services. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Services (.srv) +* [Empty.srv](srv/Empty.srv): A service containing an empty request and response. +* [SetBool.srv](srv/SetBool.srv): Service to set a boolean state to true or false, for enabling or disabling hardware for example. +* [Trigger.srv](srv/Trigger.srv): Service with an empty request header used for triggering the activation or start of a service. + + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/stereo_msgs/QUALITY_DECLARATION.md b/stereo_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..c14431e3 --- /dev/null +++ b/stereo_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,113 @@ +This document is a declaration of software quality for the `stereo_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `stereo_msgs` Quality Declaration + +The package `stereo_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`stereo_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`stereo_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`stereo_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`stereo_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`stereo_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`stereo_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`stereo_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `stereo_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`stereo_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`stereo_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/stereo_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`stereo_msgs` has the following runtime ROS dependencies: +* `rosidl_default_runtime` +* `sensor_msgs` +* `std_msgs` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`stereo_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`stereo_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/stereo_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/stereo_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/stereo_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/stereo_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/stereo_msgs/README.md b/stereo_msgs/README.md new file mode 100644 index 00000000..4e919fc4 --- /dev/null +++ b/stereo_msgs/README.md @@ -0,0 +1,11 @@ +# stereo_msgs + +This package provides a message for describing a disparity image. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [DisparityImage](msg/DisparityImage.msg): A floating point disparity image with metadata. + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/trajectory_msgs/QUALITY_DECLARATION.md b/trajectory_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..6d5f2355 --- /dev/null +++ b/trajectory_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,114 @@ +This document is a declaration of software quality for the `trajectory_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `trajectory_msgs` Quality Declaration + +The package `trajectory_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`trajectory_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`trajectory_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`trajectory_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`trajectory_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`trajectory_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`trajectory_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`trajectory_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `trajectory_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`trajectory_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`trajectory_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/trajectory_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`trajectory_msgs` has the following runtime ROS dependencies: +* `builtin_interfaces` +* `geometry_msgs` +* `rosidl_default_runtime` +* `std_msgs` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`trajectory_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`trajectory_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/trajectory_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/trajectory_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/trajectory_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/trajectory_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/trajectory_msgs/README.md b/trajectory_msgs/README.md new file mode 100644 index 00000000..5b3d1c3c --- /dev/null +++ b/trajectory_msgs/README.md @@ -0,0 +1,14 @@ +# trajectory_msgs + +This package provides several messages for defining robotic joint trajectories. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [JointTrajectory](msg/JointTrajectory.msg): A coordinated sequence of joint configurations to be reached at prescribed time points. +* [JointTrajectoryPoint](msg/JointTrajectoryPoint.msg): A single configuration for multiple joints in a JointTrajectory. +* [MultiDOFJointTrajectory](msg/MultiDOFJointTrajectory.msg): A representation of a multi-dof joint trajectory (each point is a transformation). +* [MultiDOFJointTrajectoryPoint](msg/MultiDOFJointTrajectoryPoint.msg): A single configuration for multiple joints in a MultiDOFJointTrajectory. + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/visualization_msgs/QUALITY_DECLARATION.md b/visualization_msgs/QUALITY_DECLARATION.md new file mode 100644 index 00000000..216cce88 --- /dev/null +++ b/visualization_msgs/QUALITY_DECLARATION.md @@ -0,0 +1,114 @@ +This document is a declaration of software quality for the `visualization_msgs` package, based on the guidelines in [REP-2004](https://www.ros.org/reps/rep-2004.html). + +# `visualization_msgs` Quality Declaration + +The package `visualization_msgs` claims to be in the **Quality Level 4** category. + +Below are the rationales, notes, and caveats for this claim, organized by each requirement listed in the [Package Requirements for Quality Level 4 in REP-2004](https://www.ros.org/reps/rep-2004.html). + +## Version Policy [1] + +### Version Scheme [1.i] + +`visualization_msgs` uses `semver` according to the recommendation for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#versioning). + +### Version Stability [1.ii] + +`visualization_msgs` is not yet at a stable version, i.e. `>= 1.0.0`. + +### Public API Declaration [1.iii] + +All message and service definition files located in `msg` and `srv` directories are considered part of the public API. + +### API Stability Within a Released ROS Distribution [1.iv]/[1.vi] + +`visualization_msgs` will not break public API within a released ROS distribution, i.e. no major releases once the ROS distribution is released. + +### ABI Stability Within a Released ROS Distribution [1.v]/[1.vi] + +`visualization_msgs` does not contain any C or C++ code and therefore will not affect ABI stability. + +## Change Control Process [2] + +`visualization_msgs` follows the recommended guidelines for ROS Core packages in the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#package-requirements). + +### Change Requests [2.i] + +This package requires that all changes occur through a pull request. + +### Contributor Origin [2.ii] + +This package uses DCO as its confirmation of contributor origin policy. More information can be found in [CONTRIBUTING](../CONTRIBUTING.md). + +### Peer Review Policy [2.iii] + +Following the recommended guidelines for ROS Core packages, all pull requests must have at least 1 peer review. + +### Continuous Integration [2.iv] + +All pull requests must pass CI on all [tier 1 platforms](https://www.ros.org/reps/rep-2000.html#support-tiers) + +### Documentation Policy [2.v] + +All pull requests must resolve related documentation changes before merging. + +## Documentation + +### Feature Documentation [3.i] + +`visualization_msgs` has a list of provided [messages and services](README.md). +New messages and services require their own documentation in order to be added. + +### Public API Documentation [3.ii] + +`visualization_msgs` has embedded API documentation, but it is not currently hosted. + +### License [3.iii] + +The license for `visualization_msgs` is Apache 2.0, the type is declared in the [package.xml](package.xml) manifest file, and a full copy of the license is in the repository level [LICENSE](../LICENSE) file. + +There are no source files that are currently copyrighted in this package so files are not checked for abbreviated license statements. + +### Copyright Statements [3.iv] + +There are no currently copyrighted source files in this package. + +## Testing [4] + +`visualization_msgs` is a package providing strictly message and service definitions and therefore does not require associated tests and has no coverage or performance requirements. + +### Linters and Static Analysis [4.v] + +`visualization_msgs` uses and passes all the standard linters and static analysis tools for its generated C++ and Python code to ensure it follows the [ROS 2 Developer Guide](https://index.ros.org/doc/ros2/Contributing/Developer-Guide/#linters). + +Results of the nightly linter tests can be found [here](http://build.ros2.org/view/Epr/job/Epr__common_interfaces__ubuntu_bionic_amd64/lastBuild/testReport/visualization_msgs/). + +## Dependencies [5] + +### Direct Runtime ROS Dependencies [5.i]/[5.ii] + +`visualization_msgs` has the following runtime ROS dependencies: +* `builtin_interfaces` +* `geometry_msgs` +* `rosidl_default_runtime` +* `std_msgs` + +It has several "buildtool" dependencies, which do not affect the resulting quality of the package, because they do not contribute to the public library API. + +### Direct Runtime Non-ROS Dependencies [5.iii] + +`visualization_msgs` does not have any runtime non-ROS dependencies. + +## Platform Support [6] + +`visualization_msgs` supports all of the tier 1 platforms as described in [REP-2000](https://www.ros.org/reps/rep-2000.html#support-tiers), and tests each change against all of them. + +Currently nightly results can be seen here: +* [linux-aarch64_release](https://ci.ros2.org/view/nightly/job/nightly_linux-aarch64_release/lastBuild/testReport/visualization_msgs/) +* [linux_release](https://ci.ros2.org/view/nightly/job/nightly_linux_release/lastBuild/testReport/visualization_msgs/) +* [mac_osx_release](https://ci.ros2.org/view/nightly/job/nightly_osx_release/lastBuild/testReport/visualization_msgs/) +* [windows_release](https://ci.ros2.org/view/nightly/job/nightly_win_rel/lastBuild/testReport/visualization_msgs/) + +## Vulnerability Disclosure Policy [7.i] + +This package does not yet have a Vulnerability Disclosure Policy diff --git a/visualization_msgs/README.md b/visualization_msgs/README.md new file mode 100644 index 00000000..f9b53991 --- /dev/null +++ b/visualization_msgs/README.md @@ -0,0 +1,25 @@ +# visualization_msgs + +This package provides messages for visualizing 3D information in ROS GUI programs, particularly RViz. + +These messages were ported from ROS 1 and for now the [visualization_msgs wiki](http://wiki.ros.org/visualization_msgs) is still a good place for information about these messages and how they are used. + +For more information about ROS 2 interfaces, see [index.ros2.org](https://index.ros.org/doc/ros2/Concepts/About-ROS-Interfaces/) + +## Messages (.msg) +* [ImageMarker](msg/ImageMarker.msg): A marker to overlay on displayed images. +* [InteractiveMarker](msg/InteractiveMarker.msg): A user interaction marker for manipulating objects in 3-dimensional space in GUI programs, like RViz. +* [InteractiveMarkerControl](msg/InteractiveMarkerControl.msg): Represents a control that is to be displayed together with an interactive marker. +* [InteractiveMarkerFeedback](msg/InteractiveMarkerFeedback.msg): Feedback message sent back from the GUI, e.g. when the status of an interactive marker was modified by the user. +* [InteractiveMarkerInit](msg/InteractiveMarkerInit.msg): Used for sending initial interactive marker descriptions. +* [InteractiveMarkerPose](msg/InteractiveMarkerPose.msg): The pose of the interactive marker. +* [InteractiveMarkerUpdate](msg/InteractiveMarkerUpdate.msg): The top-level message for sending data from the interactive marker server to the client (i.e. rviz). +* [Marker](msg/Marker.msg): A non-interactive marker for displaying annotations in 3-dimensional space. +* [MarkerArray](msg/MarkerArray.msg): An array of markers. +* [MenuEntry](msg/MenuEntry.msg): Used to describe the menu/submenu/subsubmenu/etc tree. + +## Services (.srv) +* [GetInteractiveMarkers.srv](srv/GetInteractiveMarkers.srv): Get the currently available interactive markers. + +## Quality Declaration +This package claims to be in the **Quality Level 4** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. diff --git a/visualization_msgs/msg/InteractiveMarker.msg b/visualization_msgs/msg/InteractiveMarker.msg index d122d842..c2af8dc9 100644 --- a/visualization_msgs/msg/InteractiveMarker.msg +++ b/visualization_msgs/msg/InteractiveMarker.msg @@ -1,4 +1,3 @@ - # Time/frame info. # If header.time is set to 0, the marker will be retransformed into # its frame on each timestep. You will receive the pose feedback diff --git a/visualization_msgs/msg/InteractiveMarkerFeedback.msg b/visualization_msgs/msg/InteractiveMarkerFeedback.msg index cb96789d..43c754c9 100644 --- a/visualization_msgs/msg/InteractiveMarkerFeedback.msg +++ b/visualization_msgs/msg/InteractiveMarkerFeedback.msg @@ -1,4 +1,3 @@ - # Time/frame info. std_msgs/Header header diff --git a/visualization_msgs/msg/InteractiveMarkerInit.msg b/visualization_msgs/msg/InteractiveMarkerInit.msg index f4ab6e98..d73bcd04 100644 --- a/visualization_msgs/msg/InteractiveMarkerInit.msg +++ b/visualization_msgs/msg/InteractiveMarkerInit.msg @@ -1,4 +1,3 @@ - # Identifying string. Must be unique in the topic namespace # that this server works on. string server_id