├── .gitignore ├── README.md ├── common_interfaces ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE └── package.xml ├── diagnostic_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg │ ├── DiagnosticArray.msg │ ├── DiagnosticStatus.msg │ └── KeyValue.msg ├── package.xml └── srv │ ├── AddDiagnostics.srv │ └── SelfTest.srv ├── docs └── APIReviewFoxy.md ├── geometry_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg │ ├── Accel.msg │ ├── AccelStamped.msg │ ├── AccelWithCovariance.msg │ ├── AccelWithCovarianceStamped.msg │ ├── Inertia.msg │ ├── InertiaStamped.msg │ ├── Point.msg │ ├── Point32.msg │ ├── PointStamped.msg │ ├── Polygon.msg │ ├── PolygonInstance.msg │ ├── PolygonInstanceStamped.msg │ ├── PolygonStamped.msg │ ├── Pose.msg │ ├── Pose2D.msg │ ├── PoseArray.msg │ ├── PoseStamped.msg │ ├── PoseWithCovariance.msg │ ├── PoseWithCovarianceStamped.msg │ ├── Quaternion.msg │ ├── QuaternionStamped.msg │ ├── Transform.msg │ ├── TransformStamped.msg │ ├── Twist.msg │ ├── TwistStamped.msg │ ├── TwistWithCovariance.msg │ ├── TwistWithCovarianceStamped.msg │ ├── Vector3.msg │ ├── Vector3Stamped.msg │ ├── VelocityStamped.msg │ ├── Wrench.msg │ └── WrenchStamped.msg └── package.xml ├── nav_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg │ ├── Goals.msg │ ├── GridCells.msg │ ├── MapMetaData.msg │ ├── OccupancyGrid.msg │ ├── Odometry.msg │ └── Path.msg ├── package.xml └── srv │ ├── GetMap.srv │ ├── GetPlan.srv │ ├── LoadMap.srv │ └── SetMap.srv ├── sensor_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── include │ └── sensor_msgs │ │ ├── distortion_models.hpp │ │ ├── fill_image.hpp │ │ ├── image_encodings.hpp │ │ ├── impl │ │ └── point_cloud2_iterator.hpp │ │ ├── point_cloud2_iterator.hpp │ │ ├── point_cloud_conversion.hpp │ │ └── point_field_conversion.hpp ├── msg │ ├── BatteryState.msg │ ├── CameraInfo.msg │ ├── ChannelFloat32.msg │ ├── CompressedImage.msg │ ├── FluidPressure.msg │ ├── Illuminance.msg │ ├── Image.msg │ ├── Imu.msg │ ├── JointState.msg │ ├── Joy.msg │ ├── JoyFeedback.msg │ ├── JoyFeedbackArray.msg │ ├── LaserEcho.msg │ ├── LaserScan.msg │ ├── MagneticField.msg │ ├── MultiDOFJointState.msg │ ├── MultiEchoLaserScan.msg │ ├── NavSatFix.msg │ ├── NavSatStatus.msg │ ├── PointCloud.msg │ ├── PointCloud2.msg │ ├── PointField.msg │ ├── Range.msg │ ├── RegionOfInterest.msg │ ├── RelativeHumidity.msg │ ├── Temperature.msg │ └── TimeReference.msg ├── package.xml ├── srv │ └── SetCameraInfo.srv └── test │ ├── test_image_encodings.cpp │ ├── test_pointcloud_conversion.cpp │ └── test_pointcloud_iterator.cpp ├── sensor_msgs_py ├── CHANGELOG.rst ├── CONTRIBUTING.md ├── LICENSE ├── package.xml ├── pytest.ini ├── resource │ └── sensor_msgs_py ├── sensor_msgs_py │ ├── __init__.py │ ├── numpy_compat.py │ └── point_cloud2.py ├── setup.cfg ├── setup.py └── test │ ├── test_copyright.py │ ├── test_flake8.py │ ├── test_pep257.py │ ├── test_point_cloud2.py │ └── test_xmllint.py ├── shape_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg │ ├── Mesh.msg │ ├── MeshTriangle.msg │ ├── Plane.msg │ └── SolidPrimitive.msg └── package.xml ├── std_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg │ ├── Bool.msg │ ├── Byte.msg │ ├── ByteMultiArray.msg │ ├── Char.msg │ ├── ColorRGBA.msg │ ├── Empty.msg │ ├── Float32.msg │ ├── Float32MultiArray.msg │ ├── Float64.msg │ ├── Float64MultiArray.msg │ ├── Header.msg │ ├── Int16.msg │ ├── Int16MultiArray.msg │ ├── Int32.msg │ ├── Int32MultiArray.msg │ ├── Int64.msg │ ├── Int64MultiArray.msg │ ├── Int8.msg │ ├── Int8MultiArray.msg │ ├── MultiArrayDimension.msg │ ├── MultiArrayLayout.msg │ ├── String.msg │ ├── UInt16.msg │ ├── UInt16MultiArray.msg │ ├── UInt32.msg │ ├── UInt32MultiArray.msg │ ├── UInt64.msg │ ├── UInt64MultiArray.msg │ ├── UInt8.msg │ └── UInt8MultiArray.msg └── package.xml ├── std_srvs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── package.xml └── srv │ ├── Empty.srv │ ├── SetBool.srv │ └── Trigger.srv ├── stereo_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg │ └── DisparityImage.msg └── package.xml ├── trajectory_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg │ ├── JointTrajectory.msg │ ├── JointTrajectoryPoint.msg │ ├── MultiDOFJointTrajectory.msg │ └── MultiDOFJointTrajectoryPoint.msg └── package.xml └── visualization_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── CONTRIBUTING.md ├── LICENSE ├── QUALITY_DECLARATION.md ├── README.md ├── msg ├── ImageMarker.msg ├── InteractiveMarker.msg ├── InteractiveMarkerControl.msg ├── InteractiveMarkerFeedback.msg ├── InteractiveMarkerInit.msg ├── InteractiveMarkerPose.msg ├── InteractiveMarkerUpdate.msg ├── Marker.msg ├── MarkerArray.msg ├── MenuEntry.msg ├── MeshFile.msg └── UVCoordinate.msg ├── package.xml └── srv └── GetInteractiveMarkers.srv /.gitignore: -------------------------------------------------------------------------------- 1 | # Compiled Object files 2 | *.slo 3 | *.lo 4 | *.o 5 | *.obj 6 | 7 | # Precompiled Headers 8 | *.gch 9 | *.pch 10 | 11 | # Compiled Dynamic libraries 12 | *.so 13 | *.dylib 14 | *.dll 15 | 16 | # Fortran module files 17 | *.mod 18 | 19 | # Compiled Static libraries 20 | *.lai 21 | *.la 22 | *.a 23 | *.lib 24 | 25 | # Executables 26 | *.exe 27 | *.out 28 | *.app 29 | 30 | # Python temporary files 31 | *.pyc 32 | __pycache__/ 33 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # common_interfaces 2 | A set of packages which contain common interface files (.msg and .srv). 3 | 4 | 5 | ## Purpose 6 | 7 | Isolating the messages to communicate between stacks in a shared dependency allows nodes in dependent stacks to communicate without requiring dependencies upon each other. 8 | This repository has been designed to contain the most common messages used between multiple packages to provide a shared dependency which will eliminate a problematic circular dependency. 9 | 10 | ## Contributing 11 | 12 | For how to contribute see [CONTRIBUTING.md](common_interfaces/CONTRIBUTING.md) 13 | -------------------------------------------------------------------------------- /common_interfaces/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package common_interfaces 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | * Removed deprecated actionlib_msgs (`#280 `_) 8 | * Contributors: Alejandro Hernández Cordero 9 | 10 | 5.6.0 (2025-04-25) 11 | ------------------ 12 | 13 | 5.5.0 (2025-03-20) 14 | ------------------ 15 | 16 | 5.4.2 (2024-11-20) 17 | ------------------ 18 | 19 | 5.4.1 (2024-06-17) 20 | ------------------ 21 | 22 | 5.4.0 (2024-04-26) 23 | ------------------ 24 | 25 | 5.3.4 (2024-04-16) 26 | ------------------ 27 | 28 | 5.3.3 (2024-04-10) 29 | ------------------ 30 | 31 | 5.3.2 (2024-04-10) 32 | ------------------ 33 | * Clarify the license. (`#241 `_) 34 | In particular, every package in this repository is Apache 2.0 35 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 36 | and LICENSE files down into the individual packages, and 37 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 38 | file (it already had the correct LICENSE file). 39 | * Contributors: Chris Lalancette 40 | 41 | 5.3.1 (2024-03-28) 42 | ------------------ 43 | 44 | 5.3.0 (2024-01-24) 45 | ------------------ 46 | 47 | 5.2.2 (2023-12-26) 48 | ------------------ 49 | 50 | 5.2.1 (2023-11-06) 51 | ------------------ 52 | 53 | 5.2.0 (2023-06-07) 54 | ------------------ 55 | 56 | 5.1.0 (2023-04-27) 57 | ------------------ 58 | 59 | 5.0.0 (2023-04-11) 60 | ------------------ 61 | 62 | 4.7.0 (2023-02-13) 63 | ------------------ 64 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 65 | * Contributors: Audrow Nash 66 | 67 | 4.6.1 (2022-11-02) 68 | ------------------ 69 | 70 | 4.6.0 (2022-09-13) 71 | ------------------ 72 | 73 | 4.5.0 (2022-05-19) 74 | ------------------ 75 | 76 | 4.4.0 (2022-04-29) 77 | ------------------ 78 | 79 | 4.3.0 (2022-04-29) 80 | ------------------ 81 | 82 | 4.2.1 (2022-03-31) 83 | ------------------ 84 | 85 | 4.2.0 (2022-03-30) 86 | ------------------ 87 | 88 | 4.1.1 (2022-03-26) 89 | ------------------ 90 | 91 | 4.1.0 (2022-03-01) 92 | ------------------ 93 | 94 | 4.0.0 (2021-12-14) 95 | ------------------ 96 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 97 | * Contributors: Audrow Nash 98 | 99 | 3.0.0 (2021-08-24) 100 | ------------------ 101 | 102 | 2.3.0 (2021-08-11) 103 | ------------------ 104 | 105 | 2.2.3 (2021-04-27) 106 | ------------------ 107 | 108 | 2.2.2 (2021-04-06) 109 | ------------------ 110 | 111 | 2.2.1 (2021-01-25) 112 | ------------------ 113 | 114 | 2.2.0 (2020-12-10) 115 | ------------------ 116 | * Update package maintainers. (`#132 `_) 117 | * Contributors: Michel Hidalgo 118 | 119 | 2.1.0 (2020-07-21) 120 | ------------------ 121 | 122 | 2.0.2 (2020-07-21) 123 | ------------------ 124 | 125 | 2.0.1 (2020-05-26) 126 | ------------------ 127 | 128 | 1.0.0 (2020-05-20) 129 | ------------------ 130 | -------------------------------------------------------------------------------- /common_interfaces/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(common_interfaces NONE) 4 | 5 | find_package(ament_cmake REQUIRED) 6 | 7 | if(BUILD_TESTING) 8 | find_package(ament_lint_auto REQUIRED) 9 | ament_lint_auto_find_test_dependencies() 10 | endif() 11 | 12 | ament_package() 13 | -------------------------------------------------------------------------------- /common_interfaces/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /common_interfaces/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | common_interfaces 5 | 5.7.0 6 | common_interfaces contains messages and services that are widely used by other ROS packages. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | Scott K Logan 16 | 17 | ament_cmake 18 | 19 | builtin_interfaces 20 | diagnostic_msgs 21 | geometry_msgs 22 | nav_msgs 23 | sensor_msgs 24 | shape_msgs 25 | std_msgs 26 | std_srvs 27 | stereo_msgs 28 | trajectory_msgs 29 | visualization_msgs 30 | 31 | ament_lint_auto 32 | ament_lint_common 33 | 34 | 35 | ament_cmake 36 | 37 | 38 | -------------------------------------------------------------------------------- /diagnostic_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package diagnostic_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | 8 | 5.6.0 (2025-04-25) 9 | ------------------ 10 | 11 | 5.5.0 (2025-03-20) 12 | ------------------ 13 | 14 | 5.4.2 (2024-11-20) 15 | ------------------ 16 | 17 | 5.4.1 (2024-06-17) 18 | ------------------ 19 | 20 | 5.4.0 (2024-04-26) 21 | ------------------ 22 | * Update quality declaration documents (`#245 `_) 23 | * Contributors: Christophe Bedard 24 | 25 | 5.3.4 (2024-04-16) 26 | ------------------ 27 | 28 | 5.3.3 (2024-04-10) 29 | ------------------ 30 | 31 | 5.3.2 (2024-04-10) 32 | ------------------ 33 | * Clarify the license. (`#241 `_) 34 | In particular, every package in this repository is Apache 2.0 35 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 36 | and LICENSE files down into the individual packages, and 37 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 38 | file (it already had the correct LICENSE file). 39 | * Contributors: Chris Lalancette 40 | 41 | 5.3.1 (2024-03-28) 42 | ------------------ 43 | 44 | 5.3.0 (2024-01-24) 45 | ------------------ 46 | 47 | 5.2.2 (2023-12-26) 48 | ------------------ 49 | 50 | 5.2.1 (2023-11-06) 51 | ------------------ 52 | 53 | 5.2.0 (2023-06-07) 54 | ------------------ 55 | 56 | 5.1.0 (2023-04-27) 57 | ------------------ 58 | 59 | 5.0.0 (2023-04-11) 60 | ------------------ 61 | 62 | 4.7.0 (2023-02-13) 63 | ------------------ 64 | * Update common_interfaces to C++17. (`#215 `_) 65 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 66 | * Contributors: Audrow Nash, Chris Lalancette 67 | 68 | 4.6.1 (2022-11-02) 69 | ------------------ 70 | 71 | 4.6.0 (2022-09-13) 72 | ------------------ 73 | 74 | 4.5.0 (2022-05-19) 75 | ------------------ 76 | 77 | 4.4.0 (2022-04-29) 78 | ------------------ 79 | 80 | 4.3.0 (2022-04-29) 81 | ------------------ 82 | 83 | 4.2.1 (2022-03-31) 84 | ------------------ 85 | 86 | 4.2.0 (2022-03-30) 87 | ------------------ 88 | 89 | 4.1.1 (2022-03-26) 90 | ------------------ 91 | 92 | 4.1.0 (2022-03-01) 93 | ------------------ 94 | * Interface packages should fully on the interface packages that they depend on (`#173 `_) 95 | * Contributors: Grey 96 | 97 | 4.0.0 (2021-12-14) 98 | ------------------ 99 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 100 | * Contributors: Audrow Nash 101 | 102 | 3.0.0 (2021-08-24) 103 | ------------------ 104 | 105 | 2.3.0 (2021-08-11) 106 | ------------------ 107 | 108 | 2.2.3 (2021-04-27) 109 | ------------------ 110 | 111 | 2.2.2 (2021-04-06) 112 | ------------------ 113 | * Change index.ros.org -> docs.ros.org. (`#149 `_) 114 | * updating quality declaration links (re: `ros2/docs.ros2.org#52 `_) (`#145 `_) 115 | * Contributors: Chris Lalancette, shonigmann 116 | 117 | 2.2.1 (2021-01-25) 118 | ------------------ 119 | 120 | 2.2.0 (2020-12-10) 121 | ------------------ 122 | * Update QDs to QL 1 (`#135 `_) 123 | * Update package maintainers. (`#132 `_) 124 | * Updated Quality Level to 2 (`#131 `_) 125 | * Contributors: Alejandro Hernández Cordero, Michel Hidalgo, Stephen Brawner 126 | 127 | 2.1.0 (2020-07-21) 128 | ------------------ 129 | 130 | 2.0.2 (2020-07-21) 131 | ------------------ 132 | * Update Quality levels to level 3 (`#124 `_) 133 | * Add Security Vulnerability Policy pointing to REP-2006. (`#120 `_) 134 | * Contributors: Chris Lalancette, brawner 135 | 136 | 2.0.1 (2020-05-26) 137 | ------------------ 138 | * QD Update Version Stability to stable version (`#121 `_) 139 | * Contributors: Alejandro Hernández Cordero 140 | 141 | 1.0.0 (2020-05-20) 142 | ------------------ 143 | * Add current-level quality declarations (`#109 `_) 144 | * Contributors: brawner 145 | -------------------------------------------------------------------------------- /diagnostic_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(diagnostic_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(rosidl_default_generators REQUIRED) 16 | find_package(std_msgs REQUIRED) 17 | 18 | set(msg_files 19 | "msg/DiagnosticArray.msg" 20 | "msg/DiagnosticStatus.msg" 21 | "msg/KeyValue.msg" 22 | ) 23 | set(srv_files 24 | "srv/AddDiagnostics.srv" 25 | "srv/SelfTest.srv" 26 | ) 27 | rosidl_generate_interfaces(${PROJECT_NAME} 28 | ${msg_files} 29 | ${srv_files} 30 | DEPENDENCIES std_msgs 31 | ADD_LINTER_TESTS 32 | ) 33 | 34 | ament_export_dependencies(rosidl_default_runtime) 35 | 36 | ament_package() 37 | -------------------------------------------------------------------------------- /diagnostic_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /diagnostic_msgs/README.md: -------------------------------------------------------------------------------- 1 | # diagnostic_msgs 2 | 3 | This package provides several messages and services for ROS node diagnostics. 4 | 5 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 6 | 7 | ## Messages (.msg) 8 | * [DiagnosticArray](msg/DiagnosticArray.msg): Used to send diagnostic information about the state of the robot. 9 | * [DiagnosticStatus](msg/DiagnosticStatus.msg): Holds the status of an individual component of the robot. 10 | * [KeyValue](msg/KeyValue.msg): Associates diagnostic values with their labels. 11 | 12 | ## Services (.srv) 13 | * [AddDiagnostics](srv/AddDiagnostics.srv): Used as part of the process for loading analyzers at runtime, not for use as a standalone service. 14 | * [SelfTest](srv/SelfTest.srv): Call this service to perform a diagnostic check. 15 | 16 | ## Quality Declaration 17 | This package claims to be in the **Quality Level 1** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 18 | -------------------------------------------------------------------------------- /diagnostic_msgs/msg/DiagnosticArray.msg: -------------------------------------------------------------------------------- 1 | # This message is used to send diagnostic information about the state of the robot. 2 | std_msgs/Header header # for timestamp 3 | DiagnosticStatus[] status # an array of components being reported on 4 | -------------------------------------------------------------------------------- /diagnostic_msgs/msg/DiagnosticStatus.msg: -------------------------------------------------------------------------------- 1 | # This message holds the status of an individual component of the robot. 2 | 3 | # Possible levels of operations. 4 | byte OK=0 5 | byte WARN=1 6 | byte ERROR=2 7 | byte STALE=3 8 | 9 | # Level of operation enumerated above. 10 | byte level 11 | # A description of the test/component reporting. 12 | string name 13 | # A description of the status. 14 | string message 15 | # A hardware unique string. 16 | string hardware_id 17 | # An array of values associated with the status. 18 | KeyValue[] values 19 | 20 | -------------------------------------------------------------------------------- /diagnostic_msgs/msg/KeyValue.msg: -------------------------------------------------------------------------------- 1 | # What to label this value when viewing. 2 | string key 3 | # A value to track over time. 4 | string value 5 | -------------------------------------------------------------------------------- /diagnostic_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | diagnostic_msgs 5 | 5.7.0 6 | A package containing some diagnostics related message and service definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | builtin_interfaces 22 | geometry_msgs 23 | std_msgs 24 | 25 | rosidl_default_runtime 26 | 27 | ament_lint_common 28 | 29 | rosidl_interface_packages 30 | 31 | 32 | ament_cmake 33 | 34 | 35 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/AddDiagnostics.srv: -------------------------------------------------------------------------------- 1 | # This service is used as part of the process for loading analyzers at runtime, 2 | # and should be used by a loader script or program, not as a standalone service. 3 | # Information about dynamic addition of analyzers can be found at 4 | # http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime 5 | 6 | # The load_namespace parameter defines the namespace where parameters for the 7 | # initialization of analyzers in the diagnostic aggregator have been loaded. The 8 | # value should be a global name (i.e. /my/name/space), not a relative 9 | # (my/name/space) or private (~my/name/space) name. Analyzers will not be added 10 | # if a non-global name is used. The call will also fail if the namespace 11 | # contains parameters that follow a namespace structure that does not conform to 12 | # that expected by the analyzer definitions. See 13 | # http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators 14 | # and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer 15 | # for examples of the structure of yaml files which are expected to have been 16 | # loaded into the namespace. 17 | string load_namespace 18 | --- 19 | 20 | # True if diagnostic aggregator was updated with new diagnostics, False 21 | # otherwise. A false return value means that either there is a bond in the 22 | # aggregator which already used the requested namespace, or the initialization 23 | # of analyzers failed. 24 | bool success 25 | 26 | # Message with additional information about the success or failure 27 | string message 28 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/SelfTest.srv: -------------------------------------------------------------------------------- 1 | --- 2 | string id 3 | byte passed 4 | DiagnosticStatus[] status 5 | -------------------------------------------------------------------------------- /geometry_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(geometry_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(rosidl_default_generators REQUIRED) 16 | find_package(std_msgs REQUIRED) 17 | 18 | set(msg_files 19 | "msg/Accel.msg" 20 | "msg/AccelStamped.msg" 21 | "msg/AccelWithCovariance.msg" 22 | "msg/AccelWithCovarianceStamped.msg" 23 | "msg/Inertia.msg" 24 | "msg/InertiaStamped.msg" 25 | "msg/Point.msg" 26 | "msg/Point32.msg" 27 | "msg/PointStamped.msg" 28 | "msg/Polygon.msg" 29 | "msg/PolygonInstance.msg" 30 | "msg/PolygonInstanceStamped.msg" 31 | "msg/PolygonStamped.msg" 32 | "msg/Pose.msg" 33 | "msg/Pose2D.msg" 34 | "msg/PoseArray.msg" 35 | "msg/PoseStamped.msg" 36 | "msg/PoseWithCovariance.msg" 37 | "msg/PoseWithCovarianceStamped.msg" 38 | "msg/Quaternion.msg" 39 | "msg/QuaternionStamped.msg" 40 | "msg/Transform.msg" 41 | "msg/TransformStamped.msg" 42 | "msg/Twist.msg" 43 | "msg/TwistStamped.msg" 44 | "msg/TwistWithCovariance.msg" 45 | "msg/TwistWithCovarianceStamped.msg" 46 | "msg/Vector3.msg" 47 | "msg/Vector3Stamped.msg" 48 | "msg/VelocityStamped.msg" 49 | "msg/Wrench.msg" 50 | "msg/WrenchStamped.msg" 51 | ) 52 | rosidl_generate_interfaces(${PROJECT_NAME} 53 | ${msg_files} 54 | DEPENDENCIES std_msgs 55 | ADD_LINTER_TESTS 56 | ) 57 | 58 | ament_export_dependencies(rosidl_default_runtime) 59 | 60 | ament_package() 61 | -------------------------------------------------------------------------------- /geometry_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /geometry_msgs/README.md: -------------------------------------------------------------------------------- 1 | # geometry_msgs 2 | 3 | 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. 4 | 5 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 6 | 7 | ## Messages (.msg) 8 | * [Accel](msg/Accel.msg): Expresses acceleration in free space broken into its linear and angular parts. 9 | * [AccelStamped](msg/AccelStamped.msg): An accel with reference coordinate frame and timestamp. 10 | * [AccelWithCovariance](msg/AccelWithCovariance.msg): Acceleration in free space with uncertainty. 11 | * [AccelWithCovarianceStamped](msg/AccelWithCovarianceStamped.msg): An estimated accel with reference coordinate frame and timestamp. 12 | * [Inertia](msg/Inertia.msg): Expresses the inertial properties of a link. 13 | * [InertiaStamped](msg/InertiaStamped.msg): An Inertia with reference coordinate frame and timestamp. 14 | * [Point32](msg/Point32.msg): The position of a 3-dimensional point in free space, with 32-bit fields. 15 | * [Point](msg/Point.msg): The position of a 3-dimensional point in free space. 16 | * [PointStamped](msg/PointStamped.msg): Point with reference coordinate frame and timestamp. 17 | * [Polygon](msg/Polygon.msg): A specification of a polygon where the first and last points are assumed to be connected. 18 | * [PolygonInstance](msg/PolygonInstance.msg): A specification of a polygon where the first and last points are assumed to be connected. Contains an identification field for disambiguation of multiple instances. 19 | * [PolygonInstanceStamped](msg/PolygonInstanceStamped.msg): A Polygon with reference coordinate frame and timestamp. Contains an identification field for disambiguation of multiple instances. 20 | * [PolygonStamped](msg/PolygonStamped.msg): A Polygon with reference coordinate frame and timestamp. 21 | * [Pose2D](msg/Pose2D.msg): **Deprecated as of Foxy and will potentially be removed in any following release.** 22 | * [PoseArray](msg/PoseArray.msg): An array of poses with a header for global reference. 23 | * [Pose](msg/Pose.msg): A representation of pose in free space, composed of position and orientation. 24 | * [PoseStamped](msg/PoseStamped.msg): A Pose with reference coordinate frame and timestamp. 25 | * [PoseWithCovariance](msg/PoseWithCovariance.msg): A pose in free space with uncertainty. 26 | * [PoseWithCovarianceStamped](msg/PoseWithCovarianceStamped.msg): An estimated pose with a reference coordinate frame and timestamp. 27 | * [Quaternion](msg/Quaternion.msg): An orientation in free space in quaternion form. 28 | * [QuaternionStamped](msg/QuaternionStamped.msg): An orientation with reference coordinate frame and timestamp. 29 | * [Transform](msg/Transform.msg): The transform between two coordinate frames in free space. 30 | * [TransformStamped](msg/TransformStamped.msg): A transform from coordinate frame header.frame_id to the coordinate frame child_frame_id. 31 | * [Twist](msg/Twist.msg): Velocity in 3-dimensional free space broken into its linear and angular parts. 32 | * [TwistStamped](msg/TwistStamped.msg): A twist with reference coordinate frame and timestamp. 33 | * [TwistWithCovariance](msg/TwistWithCovariance.msg): Velocity in 3-dimensional free space with uncertainty. 34 | * [TwistWithCovarianceStamped](msg/TwistWithCovarianceStamped.msg): An estimated twist with reference coordinate frame and timestamp. 35 | * [Vector3](msg/Vector3.msg): Represents a vector in 3-dimensional free space. 36 | * [Vector3Stamped](msg/Vector3Stamped.msg): Represents a Vector3 with reference coordinate frame and timestamp. 37 | * [Wrench](msg/Wrench.msg): Represents force in free space, separated into its linear and angular parts. 38 | * [WrenchStamped](msg/WrenchStamped.msg): A wrench with reference coordinate frame and timestamp. 39 | 40 | 41 | ## Quality Declaration 42 | This package claims to be in the **Quality Level 1** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 43 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Accel.msg: -------------------------------------------------------------------------------- 1 | # This expresses acceleration in free space broken into its linear and angular parts. 2 | Vector3 linear 3 | Vector3 angular 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelStamped.msg: -------------------------------------------------------------------------------- 1 | # An accel with reference coordinate frame and timestamp 2 | std_msgs/Header header 3 | Accel accel 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This expresses acceleration in free space with uncertainty. 2 | 3 | Accel accel 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimated accel with reference coordinate frame and timestamp. 2 | std_msgs/Header header 3 | AccelWithCovariance accel 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Inertia.msg: -------------------------------------------------------------------------------- 1 | # Mass [kg] 2 | float64 m 3 | 4 | # Center of mass [m] 5 | geometry_msgs/Vector3 com 6 | 7 | # Inertia Tensor [kg-m^2] 8 | # | ixx ixy ixz | 9 | # I = | ixy iyy iyz | 10 | # | ixz iyz izz | 11 | float64 ixx 12 | float64 ixy 13 | float64 ixz 14 | float64 iyy 15 | float64 iyz 16 | float64 izz 17 | -------------------------------------------------------------------------------- /geometry_msgs/msg/InertiaStamped.msg: -------------------------------------------------------------------------------- 1 | # An Inertia with a time stamp and reference frame. 2 | 3 | std_msgs/Header header 4 | Inertia inertia 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Point.msg: -------------------------------------------------------------------------------- 1 | # This contains the position of a point in free space 2 | float64 x 3 | float64 y 4 | float64 z 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Point32.msg: -------------------------------------------------------------------------------- 1 | # This contains the position of a point in free space(with 32 bits of precision). 2 | # It is recommended to use Point wherever possible instead of Point32. 3 | # 4 | # This recommendation is to promote interoperability. 5 | # 6 | # This message is designed to take up less space when sending 7 | # lots of points at once, as in the case of a PointCloud. 8 | 9 | float32 x 10 | float32 y 11 | float32 z 12 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PointStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Point with reference coordinate frame and timestamp 2 | 3 | std_msgs/Header header 4 | Point point 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Polygon.msg: -------------------------------------------------------------------------------- 1 | # A specification of a polygon where the first and last points are assumed to be connected 2 | 3 | Point32[] points 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PolygonInstance.msg: -------------------------------------------------------------------------------- 1 | # A specification of a polygon where the first and last points are assumed to be connected 2 | # It includes a unique identification field for disambiguating multiple instances 3 | 4 | geometry_msgs/Polygon polygon 5 | int64 id 6 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PolygonInstanceStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Polygon with reference coordinate frame and timestamp 2 | # It includes a unique identification field for disambiguating multiple instances 3 | 4 | std_msgs/Header header 5 | geometry_msgs/PolygonInstance polygon 6 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PolygonStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Polygon with reference coordinate frame and timestamp 2 | 3 | std_msgs/Header header 4 | Polygon polygon 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Pose.msg: -------------------------------------------------------------------------------- 1 | # A representation of pose in free space, composed of position and orientation. 2 | 3 | Point position 4 | Quaternion orientation 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Pose2D.msg: -------------------------------------------------------------------------------- 1 | # Deprecated as of Foxy and will potentially be removed in any following release. 2 | # Please use the full 3D pose. 3 | 4 | # In general our recommendation is to use a full 3D representation of everything and for 2D specific applications make the appropriate projections into the plane for their calculations but optimally will preserve the 3D information during processing. 5 | 6 | # If we have parallel copies of 2D datatypes every UI and other pipeline will end up needing to have dual interfaces to plot everything. And you will end up with not being able to use 3D tools for 2D use cases even if they're completely valid, as you'd have to reimplement it with different inputs and outputs. It's not particularly hard to plot the 2D pose or compute the yaw error for the Pose message and there are already tools and libraries that can do this for you.# This expresses a position and orientation on a 2D manifold. 7 | 8 | float64 x 9 | float64 y 10 | float64 theta 11 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseArray.msg: -------------------------------------------------------------------------------- 1 | # An array of poses with a header for global reference. 2 | 3 | std_msgs/Header header 4 | 5 | Pose[] poses 6 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseStamped.msg: -------------------------------------------------------------------------------- 1 | # A Pose with reference coordinate frame and timestamp 2 | 3 | std_msgs/Header header 4 | Pose pose 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This represents a pose in free space with uncertainty. 2 | 3 | Pose pose 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This expresses an estimated pose with a reference coordinate frame and timestamp 2 | 3 | std_msgs/Header header 4 | PoseWithCovariance pose 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Quaternion.msg: -------------------------------------------------------------------------------- 1 | # This represents an orientation in free space in quaternion form. 2 | 3 | float64 x 0 4 | float64 y 0 5 | float64 z 0 6 | float64 w 1 7 | -------------------------------------------------------------------------------- /geometry_msgs/msg/QuaternionStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an orientation with reference coordinate frame and timestamp. 2 | 3 | std_msgs/Header header 4 | Quaternion quaternion 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Transform.msg: -------------------------------------------------------------------------------- 1 | # This represents the transform between two coordinate frames in free space. 2 | 3 | Vector3 translation 4 | Quaternion rotation 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TransformStamped.msg: -------------------------------------------------------------------------------- 1 | # This expresses a transform from coordinate frame header.frame_id 2 | # to the coordinate frame child_frame_id at the time of header.stamp 3 | # 4 | # This message is mostly used by the 5 | # tf2 package. 6 | # See its documentation for more information. 7 | # 8 | # The child_frame_id is necessary in addition to the frame_id 9 | # in the Header to communicate the full reference for the transform 10 | # in a self contained message. 11 | 12 | # The frame id in the header is used as the reference frame of this transform. 13 | std_msgs/Header header 14 | 15 | # The frame id of the child frame to which this transform points. 16 | string child_frame_id 17 | 18 | # Translation and rotation in 3-dimensions of child_frame_id from header.frame_id. 19 | Transform transform 20 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Twist.msg: -------------------------------------------------------------------------------- 1 | # This expresses velocity in free space broken into its linear and angular parts. 2 | 3 | Vector3 linear 4 | Vector3 angular 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistStamped.msg: -------------------------------------------------------------------------------- 1 | # A twist with reference coordinate frame and timestamp 2 | 3 | std_msgs/Header header 4 | Twist twist 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This expresses velocity in free space with uncertainty. 2 | 3 | Twist twist 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimated twist with reference coordinate frame and timestamp. 2 | 3 | std_msgs/Header header 4 | TwistWithCovariance twist 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Vector3.msg: -------------------------------------------------------------------------------- 1 | # This represents a vector in free space. 2 | 3 | # This is semantically different than a point. 4 | # A vector is always anchored at the origin. 5 | # When a transform is applied to a vector, only the rotational component is applied. 6 | 7 | float64 x 8 | float64 y 9 | float64 z 10 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Vector3Stamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Vector3 with reference coordinate frame and timestamp 2 | 3 | # Note that this follows vector semantics with it always anchored at the origin, 4 | # so the rotational elements of a transform are the only parts applied when transforming. 5 | 6 | std_msgs/Header header 7 | Vector3 vector 8 | -------------------------------------------------------------------------------- /geometry_msgs/msg/VelocityStamped.msg: -------------------------------------------------------------------------------- 1 | # This expresses the timestamped velocity vector of a frame 'body_frame_id' in the reference frame 'reference_frame_id' expressed from arbitrary observation frame 'header.frame_id'. 2 | # - If the 'body_frame_id' and 'header.frame_id' are identical, the velocity is observed and defined in the local coordinates system of the body 3 | # which is the usual use-case in mobile robotics and is also known as a body twist. 4 | 5 | std_msgs/Header header 6 | string body_frame_id 7 | string reference_frame_id 8 | Twist velocity 9 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Wrench.msg: -------------------------------------------------------------------------------- 1 | # This represents force in free space, separated into its linear and angular parts. 2 | 3 | Vector3 force 4 | Vector3 torque 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/WrenchStamped.msg: -------------------------------------------------------------------------------- 1 | # A wrench with reference coordinate frame and timestamp 2 | 3 | std_msgs/Header header 4 | Wrench wrench 5 | -------------------------------------------------------------------------------- /geometry_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | geometry_msgs 5 | 5.7.0 6 | A package containing some geometry related message definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | std_msgs 22 | 23 | rosidl_default_runtime 24 | 25 | ament_lint_common 26 | 27 | rosidl_interface_packages 28 | 29 | 30 | ament_cmake 31 | 32 | 33 | -------------------------------------------------------------------------------- /nav_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(nav_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(builtin_interfaces REQUIRED) 16 | find_package(geometry_msgs REQUIRED) 17 | find_package(rosidl_default_generators REQUIRED) 18 | find_package(std_msgs REQUIRED) 19 | 20 | set(msg_files 21 | "msg/Goals.msg" 22 | "msg/GridCells.msg" 23 | "msg/MapMetaData.msg" 24 | "msg/OccupancyGrid.msg" 25 | "msg/Odometry.msg" 26 | "msg/Path.msg" 27 | ) 28 | set(srv_files 29 | "srv/GetMap.srv" 30 | "srv/GetPlan.srv" 31 | "srv/LoadMap.srv" 32 | "srv/SetMap.srv" 33 | ) 34 | 35 | rosidl_generate_interfaces(${PROJECT_NAME} 36 | ${msg_files} 37 | ${srv_files} 38 | DEPENDENCIES builtin_interfaces geometry_msgs std_msgs 39 | ADD_LINTER_TESTS 40 | ) 41 | 42 | ament_export_dependencies(rosidl_default_runtime) 43 | 44 | ament_package() 45 | -------------------------------------------------------------------------------- /nav_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /nav_msgs/README.md: -------------------------------------------------------------------------------- 1 | # nav_msgs 2 | 3 | This package provides several messages and services for robotic navigation. 4 | 5 | For more information about the navigation2 stack in ROS 2, see https://ros-planning.github.io/navigation2/. 6 | 7 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 8 | 9 | ## Messages (.msg) 10 | * [GridCells](msg/GridCells.msg): An array of cells in a 2D grid. 11 | * [MapMetaData](msg/MapMetaData.msg): Basic information about the characteristics of the OccupancyGrid. 12 | * [OccupancyGrid](msg/OccupancyGrid.msg): Represents a 2-D grid map, in which each cell represents the probability of occupancy. 13 | * [Odometry](msg/Odometry.msg): This represents an estimate of a position and velocity in free space. 14 | * [Path](msg/Path.msg): An array of poses that represents a Path for a robot to follow. 15 | 16 | ## Services (.srv) 17 | * [GetMap](srv/GetMap.srv): Get the map as a nav_msgs/OccupancyGrid. 18 | * [GetPlan](srv/GetPlan.srv): Get a plan from the current position to the goal Pose. 19 | * [SetMap](srv/SetMap.srv): Set a new map together with an initial pose. 20 | 21 | ## Quality Declaration 22 | This package claims to be in the **Quality Level 2** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 23 | -------------------------------------------------------------------------------- /nav_msgs/msg/Goals.msg: -------------------------------------------------------------------------------- 1 | # An array of navigation goals 2 | 3 | 4 | # This header will store the time at which the poses were computed (not to be confused with the stamps of the poses themselves) 5 | # In the case that individual poses do not have their frame_id set or their timetamp set they will use the default value here. 6 | std_msgs/Header header 7 | 8 | # An array of goals to for navigation to achieve. 9 | # The goals should be executed in the order of the array. 10 | # The header and stamp are intended to be used for computing the position of the goals. 11 | # They may vary to support cases of goals that are moving with respect to the robot. 12 | geometry_msgs/PoseStamped[] goals 13 | -------------------------------------------------------------------------------- /nav_msgs/msg/GridCells.msg: -------------------------------------------------------------------------------- 1 | # An array of cells in a 2D grid 2 | 3 | std_msgs/Header header 4 | 5 | # Width of each cell 6 | float32 cell_width 7 | 8 | # Height of each cell 9 | float32 cell_height 10 | 11 | # Each cell is represented by the Point at the center of the cell 12 | geometry_msgs/Point[] cells 13 | -------------------------------------------------------------------------------- /nav_msgs/msg/MapMetaData.msg: -------------------------------------------------------------------------------- 1 | # This hold basic information about the characteristics of the OccupancyGrid 2 | 3 | # The time at which the map was loaded 4 | builtin_interfaces/Time map_load_time 5 | 6 | # The map resolution [m/cell] 7 | float32 resolution 8 | 9 | # Map width [cells] 10 | uint32 width 11 | 12 | # Map height [cells] 13 | uint32 height 14 | 15 | # The origin of the map [m, m, rad]. This is the real-world pose of the 16 | # bottom left corner of cell (0,0) in the map. 17 | geometry_msgs/Pose origin 18 | -------------------------------------------------------------------------------- /nav_msgs/msg/OccupancyGrid.msg: -------------------------------------------------------------------------------- 1 | # This represents a 2-D grid map 2 | std_msgs/Header header 3 | 4 | # MetaData for the map 5 | MapMetaData info 6 | 7 | # The map data, in row-major order, starting with (0,0). 8 | # Cell (1, 0) will be listed second, representing the next cell in the x direction. 9 | # Cell (0, 1) will be at the index equal to info.width, followed by (1, 1). 10 | # The values inside are application dependent, but frequently, 11 | # 0 represents unoccupied, 1 represents definitely occupied, and 12 | # -1 represents unknown. 13 | int8[] data 14 | -------------------------------------------------------------------------------- /nav_msgs/msg/Odometry.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimate of a position and velocity in free space. 2 | # The pose in this message should be specified in the coordinate frame given by header.frame_id 3 | # The twist in this message should be specified in the coordinate frame given by the child_frame_id 4 | 5 | # Includes the frame id of the pose parent. 6 | std_msgs/Header header 7 | 8 | # Frame id the pose points to. The twist is in this coordinate frame. 9 | string child_frame_id 10 | 11 | # Estimated pose that is typically relative to a fixed world frame. 12 | geometry_msgs/PoseWithCovariance pose 13 | 14 | # Estimated linear and angular velocity relative to child_frame_id. 15 | geometry_msgs/TwistWithCovariance twist 16 | -------------------------------------------------------------------------------- /nav_msgs/msg/Path.msg: -------------------------------------------------------------------------------- 1 | # An array of poses that represents a Path for a robot to follow. 2 | 3 | # Indicates the frame_id of the path. 4 | std_msgs/Header header 5 | 6 | # Array of poses to follow. 7 | geometry_msgs/PoseStamped[] poses 8 | -------------------------------------------------------------------------------- /nav_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | nav_msgs 5 | 5.7.0 6 | A package containing some navigation related message and service definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | builtin_interfaces 22 | geometry_msgs 23 | std_msgs 24 | 25 | rosidl_default_runtime 26 | 27 | ament_lint_common 28 | 29 | rosidl_interface_packages 30 | 31 | 32 | ament_cmake 33 | 34 | 35 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetMap.srv: -------------------------------------------------------------------------------- 1 | # Get the map as a nav_msgs/OccupancyGrid 2 | --- 3 | # The current map hosted by this map service. 4 | OccupancyGrid map 5 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetPlan.srv: -------------------------------------------------------------------------------- 1 | # Get a plan from the current position to the goal Pose 2 | 3 | # The start pose for the plan 4 | geometry_msgs/PoseStamped start 5 | 6 | # The final pose of the goal position 7 | geometry_msgs/PoseStamped goal 8 | 9 | # If the goal is obstructed, how many meters the planner can 10 | # relax the constraint in x and y before failing. 11 | float32 tolerance 12 | --- 13 | # Array of poses from start to goal if one was successfully found. 14 | Path plan 15 | -------------------------------------------------------------------------------- /nav_msgs/srv/LoadMap.srv: -------------------------------------------------------------------------------- 1 | # URL of map resource 2 | # Can be an absolute path to a file: file:///path/to/maps/floor1.yaml 3 | # Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml 4 | string map_url 5 | --- 6 | # Result code definitions 7 | uint8 RESULT_SUCCESS=0 8 | uint8 RESULT_MAP_DOES_NOT_EXIST=1 9 | uint8 RESULT_INVALID_MAP_DATA=2 10 | uint8 RESULT_INVALID_MAP_METADATA=3 11 | uint8 RESULT_UNDEFINED_FAILURE=255 12 | 13 | # Returned map is only valid if result equals RESULT_SUCCESS 14 | nav_msgs/OccupancyGrid map 15 | uint8 result 16 | -------------------------------------------------------------------------------- /nav_msgs/srv/SetMap.srv: -------------------------------------------------------------------------------- 1 | # Set a new map together with an initial pose 2 | 3 | # Requested 2D map to be set. 4 | nav_msgs/OccupancyGrid map 5 | 6 | # Estimated initial pose when setting new map. 7 | geometry_msgs/PoseWithCovarianceStamped initial_pose 8 | --- 9 | 10 | # True if the map was successfully set, false otherwise. 11 | bool success 12 | -------------------------------------------------------------------------------- /sensor_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(sensor_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(builtin_interfaces REQUIRED) 16 | find_package(geometry_msgs REQUIRED) 17 | find_package(rosidl_default_generators REQUIRED) 18 | find_package(std_msgs REQUIRED) 19 | 20 | set(msg_files 21 | "msg/BatteryState.msg" 22 | "msg/CameraInfo.msg" 23 | "msg/ChannelFloat32.msg" 24 | "msg/CompressedImage.msg" 25 | "msg/FluidPressure.msg" 26 | "msg/Illuminance.msg" 27 | "msg/Image.msg" 28 | "msg/Imu.msg" 29 | "msg/JointState.msg" 30 | "msg/Joy.msg" 31 | "msg/JoyFeedback.msg" 32 | "msg/JoyFeedbackArray.msg" 33 | "msg/LaserEcho.msg" 34 | "msg/LaserScan.msg" 35 | "msg/MagneticField.msg" 36 | "msg/MultiDOFJointState.msg" 37 | "msg/MultiEchoLaserScan.msg" 38 | "msg/NavSatFix.msg" 39 | "msg/NavSatStatus.msg" 40 | "msg/PointCloud.msg" 41 | "msg/PointCloud2.msg" 42 | "msg/PointField.msg" 43 | "msg/Range.msg" 44 | "msg/RegionOfInterest.msg" 45 | "msg/RelativeHumidity.msg" 46 | "msg/Temperature.msg" 47 | "msg/TimeReference.msg" 48 | ) 49 | set(srv_files 50 | "srv/SetCameraInfo.srv" 51 | ) 52 | rosidl_generate_interfaces(${PROJECT_NAME} 53 | ${msg_files} 54 | ${srv_files} 55 | DEPENDENCIES builtin_interfaces geometry_msgs std_msgs 56 | ADD_LINTER_TESTS 57 | ) 58 | 59 | rosidl_get_typesupport_target(cpp_typesupport_target "${PROJECT_NAME}" "rosidl_typesupport_cpp") 60 | 61 | if(BUILD_TESTING) 62 | find_package(ament_cmake_gtest REQUIRED) 63 | find_package(ament_lint_auto REQUIRED) 64 | ament_lint_auto_find_test_dependencies() 65 | endif() 66 | 67 | if(TARGET "${cpp_typesupport_target}") 68 | add_library(${PROJECT_NAME}_library INTERFACE) 69 | target_include_directories(${PROJECT_NAME}_library INTERFACE 70 | "$" 71 | "$") 72 | target_link_libraries(${PROJECT_NAME}_library INTERFACE 73 | "${cpp_typesupport_target}") 74 | 75 | install(DIRECTORY include/ 76 | DESTINATION include/${PROJECT_NAME} 77 | ) 78 | install( 79 | TARGETS ${PROJECT_NAME}_library EXPORT export_${PROJECT_NAME} 80 | ) 81 | 82 | # Export old-style CMake variables 83 | ament_export_include_directories("include/${PROJECT_NAME}") 84 | 85 | # Export modern CMake targets 86 | ament_export_targets(export_${PROJECT_NAME}) 87 | 88 | if(BUILD_TESTING) 89 | ament_add_gtest(test_sensor_msgs 90 | test/test_image_encodings.cpp 91 | test/test_pointcloud_conversion.cpp 92 | test/test_pointcloud_iterator.cpp) 93 | target_link_libraries(test_sensor_msgs ${PROJECT_NAME}_library) 94 | endif() 95 | endif() 96 | 97 | ament_export_dependencies(rosidl_default_runtime) 98 | 99 | ament_package() 100 | -------------------------------------------------------------------------------- /sensor_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /sensor_msgs/README.md: -------------------------------------------------------------------------------- 1 | # sensor_msgs 2 | 3 | This package provides many messages and services relating to sensor devices. 4 | 5 | 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). 6 | 7 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 8 | 9 | ## sensor_msgs c++ API 10 | This package provides some common C++ functionality relating to manipulating a couple of particular sensor_msgs messages. 11 | 12 | * [fill_image.hpp](include/sensor_msgs/fill_image.hpp): Fill a Image message from type-erased data pointer. 13 | * [image_encodings.hpp](include/sensor_msgs/image_encodings.hpp): Definitions and functionality relating to image encodings. 14 | * [point_cloud_conversion.hpp](include/sensor_msgs/point_cloud_conversion.hpp): Functionality for converting between the deprecated PointCloud and PointCloud2 messages. 15 | * [point_cloud2_iterator.hpp](include/sensor_msgs/point_cloud2_iterator.hpp): Tools for modifying and parsing PointCloud2 messages. 16 | * [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. 17 | 18 | ## Messages (.msg) 19 | * [BatteryState](msg/BatteryState.msg): Describes the power state of the battery. 20 | * [CameraInfo](msg/CameraInfo.msg): Meta information for a camera. 21 | * [ChannelFloat32](msg/ChannelFloat32.msg): Holds optional data associated with each point in a PointCloud message. 22 | * [CompressedImage](msg/CompressedImage.msg): A compressed image. 23 | * [FluidPressure](msg/FluidPressure.msg): Single pressure reading for fluids (air, water, etc) like atmospheric and barometric pressures. 24 | * [Illuminance](msg/Illuminance.msg): Single photometric illuminance measurement. 25 | * [Image](msg/Image.msg): An uncompressed image. 26 | * [Imu](msg/Imu.msg): Holds data from an IMU (Inertial Measurement Unit). 27 | * [JointState](msg/JointState.msg): Holds data to describe the state of a set of torque controlled joints. 28 | * [JoyFeedbackArray](msg/JoyFeedbackArray.msg): An array of JoyFeedback messages. 29 | * [JoyFeedback](msg/JoyFeedback.msg): Describes user feedback in a joystick, like an LED, rumble pad, or buzzer. 30 | * [Joy](msg/Joy.msg): Reports the state of a joystick's axes and buttons. 31 | * [LaserEcho](msg/LaserEcho.msg): A submessage of MultiEchoLaserScan and is not intended to be used separately. 32 | * [LaserScan](msg/LaserScan.msg): Single scan from a planar laser range-finder. 33 | * [MagneticField](msg/MagneticField.msg): Measurement of the Magnetic Field vector at a specific location. 34 | * [MultiDOFJointState](msg/MultiDOFJointState.msg): Representation of state for joints with multiple degrees of freedom, following the structure of JointState. 35 | * [MultiEchoLaserScan](msg/MultiEchoLaserScan.msg): Single scan from a multi-echo planar laser range-finder. 36 | * [NavSatFix](msg/NavSatFix.msg): Navigation Satellite fix for any Global Navigation Satellite System. 37 | * [NavSatStatus](msg/NavSatStatus.msg): Navigation Satellite fix status for any Global Navigation Satellite System. 38 | * [PointCloud2](msg/PointCloud2.msg): Holds a collection of N-dimensional points, which may contain additional information such as normals, intensity, etc. 39 | * [PointCloud](msg/PointCloud.msg): **THIS MESSAGE IS DEPRECATED AS OF FOXY, use PointCloud2 instead** 40 | * [PointField](msg/PointField.msg): Holds the description of one point entry in the PointCloud2 message format. 41 | * [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. 42 | * [RegionOfInterest](msg/RegionOfInterest.msg): Used to specify a region of interest within an image. 43 | * [RelativeHumidity](msg/RelativeHumidity.msg): A single reading from a relative humidity sensor. 44 | * [Temperature](msg/Temperature.msg): A single temperature reading. 45 | * [TimeReference](msg/TimeReference.msg): Measurement from an external time source not actively synchronized with the system clock. 46 | 47 | ## Services (.srv) 48 | * [SetCameraInfo](srv/SetCameraInfo.srv): Request that a camera stores the given CameraInfo as that camera's calibration information. 49 | 50 | ## Quality Declaration 51 | This package claims to be in the **Quality Level 1** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 52 | -------------------------------------------------------------------------------- /sensor_msgs/include/sensor_msgs/distortion_models.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2010, Willow Garage, Inc. 2 | // Copyright (c) 2017, Open Source Robotics Foundation, Inc. 3 | // 4 | // Redistribution and use in source and binary forms, with or without 5 | // modification, are permitted provided that the following conditions are met: 6 | // 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // 10 | // * Redistributions in binary form must reproduce the above copyright 11 | // notice, this list of conditions and the following disclaimer in the 12 | // documentation and/or other materials provided with the distribution. 13 | // 14 | // * Neither the name of the copyright holder nor the names of its 15 | // contributors may be used to endorse or promote products derived from 16 | // this software without specific prior written permission. 17 | // 18 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 19 | // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 20 | // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 21 | // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 22 | // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 23 | // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 24 | // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 25 | // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 26 | // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 27 | // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 28 | // POSSIBILITY OF SUCH DAMAGE. 29 | 30 | // This file is originally from: 31 | // https://github.com/ros/common_msgs/blob/7dea912/sensor_msgs/include/sensor_msgs/distortion_models.h 32 | 33 | #ifndef SENSOR_MSGS__DISTORTION_MODELS_HPP_ 34 | #define SENSOR_MSGS__DISTORTION_MODELS_HPP_ 35 | 36 | namespace sensor_msgs 37 | { 38 | namespace distortion_models 39 | { 40 | const char PLUMB_BOB[] = "plumb_bob"; 41 | const char RATIONAL_POLYNOMIAL[] = "rational_polynomial"; 42 | const char EQUIDISTANT[] = "equidistant"; 43 | } 44 | } 45 | 46 | #endif // SENSOR_MSGS__DISTORTION_MODELS_HPP_ 47 | -------------------------------------------------------------------------------- /sensor_msgs/include/sensor_msgs/fill_image.hpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2008, Willow Garage, Inc. 2 | // 3 | // Redistribution and use in source and binary forms, with or without 4 | // modification, are permitted provided that the following conditions are met: 5 | // 6 | // * Redistributions of source code must retain the above copyright 7 | // notice, this list of conditions and the following disclaimer. 8 | // 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // 13 | // * Neither the name of the copyright holder nor the names of its 14 | // contributors may be used to endorse or promote products derived from 15 | // this software without specific prior written permission. 16 | // 17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 21 | // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | // POSSIBILITY OF SUCH DAMAGE. 28 | 29 | // This file is originally ported from ROS1: 30 | // https://github.com/ros/common_msgs/blob/89069bc/sensor_msgs/include/sensor_msgs/fill_image.h 31 | 32 | #ifndef SENSOR_MSGS__FILL_IMAGE_HPP_ 33 | #define SENSOR_MSGS__FILL_IMAGE_HPP_ 34 | 35 | #include 36 | #include 37 | 38 | #include "sensor_msgs/msg/image.hpp" 39 | #include "sensor_msgs/image_encodings.hpp" 40 | 41 | namespace sensor_msgs 42 | { 43 | /// Fill an image message. 44 | /** 45 | * \param[out] image Image to be filled. 46 | * \param[in] encoding_arg Encoding type, such as sensor_msgs::image_encodings::RGB8. 47 | * \param[in] rows_arg Number of rows. 48 | * \param[in] cols_arg Number of columns. 49 | * \param[in] step_arg Step size. 50 | * \param[in] data_arg Data to fill image with. 51 | * \return True if successful. 52 | */ 53 | static inline bool fillImage( 54 | msg::Image & image, 55 | const std::string & encoding_arg, 56 | uint32_t rows_arg, 57 | uint32_t cols_arg, 58 | uint32_t step_arg, 59 | const void * data_arg) 60 | { 61 | image.encoding = encoding_arg; 62 | image.height = rows_arg; 63 | image.width = cols_arg; 64 | image.step = step_arg; 65 | size_t st0 = (step_arg * rows_arg); 66 | image.data.resize(st0); 67 | std::memcpy(&image.data[0], data_arg, st0); 68 | 69 | image.is_bigendian = 0; 70 | return true; 71 | } 72 | 73 | /// Clear the data of an image message. 74 | /** 75 | * \details All fields but `data` are kept the same. 76 | * \param[out] image Image to be cleared. 77 | */ 78 | static inline void clearImage(msg::Image & image) 79 | { 80 | image.data.resize(0); 81 | } 82 | } // namespace sensor_msgs 83 | 84 | #endif // SENSOR_MSGS__FILL_IMAGE_HPP_ 85 | -------------------------------------------------------------------------------- /sensor_msgs/msg/BatteryState.msg: -------------------------------------------------------------------------------- 1 | 2 | # Constants are chosen to match the enums in the linux kernel 3 | # defined in include/linux/power_supply.h as of version 3.7 4 | # The one difference is for style reasons the constants are 5 | # all uppercase not mixed case. 6 | 7 | # Power supply status constants 8 | uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0 9 | uint8 POWER_SUPPLY_STATUS_CHARGING = 1 10 | uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2 11 | uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3 12 | uint8 POWER_SUPPLY_STATUS_FULL = 4 13 | 14 | # Power supply health constants 15 | uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0 16 | uint8 POWER_SUPPLY_HEALTH_GOOD = 1 17 | uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2 18 | uint8 POWER_SUPPLY_HEALTH_DEAD = 3 19 | uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 20 | uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 21 | uint8 POWER_SUPPLY_HEALTH_COLD = 6 22 | uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 23 | uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 24 | 25 | # Power supply technology (chemistry) constants 26 | uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 # Unknown battery technology 27 | uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1 # Nickel-Metal Hydride battery 28 | uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2 # Lithium-ion battery 29 | uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3 # Lithium Polymer battery 30 | uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4 # Lithium Iron Phosphate battery 31 | uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5 # Nickel-Cadmium battery 32 | uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6 # Lithium Manganese Dioxide battery 33 | uint8 POWER_SUPPLY_TECHNOLOGY_TERNARY = 7 # Ternary Lithium battery 34 | uint8 POWER_SUPPLY_TECHNOLOGY_VRLA = 8 # Valve Regulated Lead-Acid battery 35 | 36 | std_msgs/Header header 37 | float32 voltage # Voltage in Volts (Mandatory) 38 | float32 temperature # Temperature in Degrees Celsius (If unmeasured NaN) 39 | float32 current # Negative when discharging (A) (If unmeasured NaN) 40 | float32 charge # Current charge in Ah (If unmeasured NaN) 41 | float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN) 42 | float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN) 43 | float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN) 44 | uint8 power_supply_status # The charging status as reported. Values defined above 45 | uint8 power_supply_health # The battery health metric. Values defined above 46 | uint8 power_supply_technology # The battery chemistry. Values defined above 47 | bool present # True if the battery is present 48 | 49 | float32[] cell_voltage # An array of individual cell voltages for each cell in the pack 50 | # If individual voltages unknown but number of cells known set each to NaN 51 | float32[] cell_temperature # An array of individual cell temperatures for each cell in the pack 52 | # If individual temperatures unknown but number of cells known set each to NaN 53 | string location # The location into which the battery is inserted. (slot number or plug) 54 | string serial_number # The best approximation of the battery serial number 55 | -------------------------------------------------------------------------------- /sensor_msgs/msg/ChannelFloat32.msg: -------------------------------------------------------------------------------- 1 | # This message is used by the PointCloud message to hold optional data 2 | # associated with each point in the cloud. The length of the values 3 | # array should be the same as the length of the points array in the 4 | # PointCloud, and each value should be associated with the corresponding 5 | # point. 6 | # 7 | # Channel names in existing practice include: 8 | # "u", "v" - row and column (respectively) in the left stereo image. 9 | # This is opposite to usual conventions but remains for 10 | # historical reasons. The newer PointCloud2 message has no 11 | # such problem. 12 | # "rgb" - For point clouds produced by color stereo cameras. uint8 13 | # (R,G,B) values packed into the least significant 24 bits, 14 | # in order. 15 | # "intensity" - laser or pixel intensity. 16 | # "distance" 17 | 18 | # The channel name should give semantics of the channel (e.g. 19 | # "intensity" instead of "value"). 20 | string name 21 | 22 | # The values array should be 1-1 with the elements of the associated 23 | # PointCloud. 24 | float32[] values 25 | -------------------------------------------------------------------------------- /sensor_msgs/msg/CompressedImage.msg: -------------------------------------------------------------------------------- 1 | # This message contains a compressed image. 2 | 3 | std_msgs/Header header # Header timestamp should be acquisition time of image 4 | # Header frame_id should be optical frame of camera 5 | # origin of frame should be optical center of cameara 6 | # +x should point to the right in the image 7 | # +y should point down in the image 8 | # +z should point into to plane of the image 9 | 10 | string format # Specifies the format of the data 11 | # Acceptable values differ by the image transport used: 12 | # - compressed_image_transport: 13 | # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] 14 | # where: 15 | # - ORIG_PIXFMT is pixel format of the raw image, i.e. 16 | # the content of sensor_msgs/Image/encoding with 17 | # values from include/sensor_msgs/image_encodings.h 18 | # - CODEC is one of [jpeg, png, tiff] 19 | # - COMPRESSED_PIXFMT is only appended for color images 20 | # and is the pixel format used by the compression 21 | # algorithm. Valid values for jpeg encoding are: 22 | # [bgr8, rgb8]. Valid values for png encoding are: 23 | # [bgr8, rgb8, bgr16, rgb16]. 24 | # If the field is empty or does not correspond to the 25 | # above pattern, the image is treated as bgr8 or mono8 26 | # jpeg image (depending on the number of channels). 27 | # - compressed_depth_image_transport: 28 | # ORIG_PIXFMT; compressedDepth CODEC 29 | # where: 30 | # - ORIG_PIXFMT is pixel format of the raw image, i.e. 31 | # the content of sensor_msgs/Image/encoding with 32 | # values from include/sensor_msgs/image_encodings.h 33 | # It is usually one of [16UC1, 32FC1]. 34 | # - CODEC is one of [png, rvl] 35 | # If the field is empty or does not correspond to the 36 | # above pattern, the image is treated as png image. 37 | # - Other image transports can store whatever values they 38 | # need for successful decoding of the image. Refer to 39 | # documentation of the other transports for details. 40 | 41 | uint8[] data # Compressed image buffer 42 | -------------------------------------------------------------------------------- /sensor_msgs/msg/FluidPressure.msg: -------------------------------------------------------------------------------- 1 | # Single pressure reading. This message is appropriate for measuring the 2 | # pressure inside of a fluid (air, water, etc). This also includes 3 | # atmospheric or barometric pressure. 4 | # 5 | # This message is not appropriate for force/pressure contact sensors. 6 | 7 | std_msgs/Header header # timestamp of the measurement 8 | # frame_id is the location of the pressure sensor 9 | 10 | float64 fluid_pressure # Absolute pressure reading in Pascals. 11 | 12 | float64 variance # 0 is interpreted as variance unknown 13 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Illuminance.msg: -------------------------------------------------------------------------------- 1 | # Single photometric illuminance measurement. Light should be assumed to be 2 | # measured along the sensor's x-axis (the area of detection is the y-z plane). 3 | # The illuminance should have a 0 or positive value and be received with 4 | # the sensor's +X axis pointing toward the light source. 5 | # 6 | # Photometric illuminance is the measure of the human eye's sensitivity of the 7 | # intensity of light encountering or passing through a surface. 8 | # 9 | # All other Photometric and Radiometric measurements should not use this message. 10 | # This message cannot represent: 11 | # - Luminous intensity (candela/light source output) 12 | # - Luminance (nits/light output per area) 13 | # - Irradiance (watt/area), etc. 14 | 15 | std_msgs/Header header # timestamp is the time the illuminance was measured 16 | # frame_id is the location and direction of the reading 17 | 18 | float64 illuminance # Measurement of the Photometric Illuminance in Lux. 19 | 20 | float64 variance # 0 is interpreted as variance unknown 21 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Image.msg: -------------------------------------------------------------------------------- 1 | # This message contains an uncompressed image 2 | # (0, 0) is at top-left corner of image 3 | 4 | std_msgs/Header header # Header timestamp should be acquisition time of image 5 | # Header frame_id should be optical frame of camera 6 | # origin of frame should be optical center of cameara 7 | # +x should point to the right in the image 8 | # +y should point down in the image 9 | # +z should point into to plane of the image 10 | # If the frame_id here and the frame_id of the CameraInfo 11 | # message associated with the image conflict 12 | # the behavior is undefined 13 | 14 | uint32 height # image height, that is, number of rows 15 | uint32 width # image width, that is, number of columns 16 | 17 | # The legal values for encoding are in file include/sensor_msgs/image_encodings.hpp 18 | # If you want to standardize a new string format, join 19 | # ros-users@lists.ros.org and send an email proposing a new encoding. 20 | 21 | string encoding # Encoding of pixels -- channel meaning, ordering, size 22 | # taken from the list of strings in include/sensor_msgs/image_encodings.hpp 23 | 24 | uint8 is_bigendian # is this data bigendian? 25 | uint32 step # Full row length in bytes 26 | uint8[] data # actual matrix data, size is (step * rows) 27 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Imu.msg: -------------------------------------------------------------------------------- 1 | # This is a message to hold data from an IMU (Inertial Measurement Unit) 2 | # 3 | # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec 4 | # 5 | # If the covariance of the measurement is known, it should be filled in (if all you know is the 6 | # variance of each measurement, e.g. from the datasheet, just put those along the diagonal) 7 | # A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the 8 | # data a covariance will have to be assumed or gotten from some other source 9 | # 10 | # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an 11 | # orientation estimate), please set element 0 of the associated covariance matrix to -1 12 | # If you are interpreting this message, please check for a value of -1 in the first element of each 13 | # covariance matrix, and disregard the associated estimate. 14 | 15 | std_msgs/Header header 16 | 17 | geometry_msgs/Quaternion orientation 18 | float64[9] orientation_covariance # Row major about x, y, z axes 19 | 20 | geometry_msgs/Vector3 angular_velocity 21 | float64[9] angular_velocity_covariance # Row major about x, y, z axes 22 | 23 | geometry_msgs/Vector3 linear_acceleration 24 | float64[9] linear_acceleration_covariance # Row major x, y z 25 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JointState.msg: -------------------------------------------------------------------------------- 1 | # This is a message that holds data to describe the state of a set of torque controlled joints. 2 | # 3 | # The state of each joint (revolute or prismatic) is defined by: 4 | # * the position of the joint (rad or m), 5 | # * the velocity of the joint (rad/s or m/s) and 6 | # * the effort that is applied in the joint (Nm or N). 7 | # 8 | # Each joint is uniquely identified by its name 9 | # The header specifies the time at which the joint states were recorded. All the joint states 10 | # in one message have to be recorded at the same time. 11 | # 12 | # This message consists of a multiple arrays, one for each part of the joint state. 13 | # The goal is to make each of the fields optional. When e.g. your joints have no 14 | # effort associated with them, you can leave the effort array empty. 15 | # 16 | # All arrays in this message should have the same size, or be empty. 17 | # This is the only way to uniquely associate the joint name with the correct 18 | # states. 19 | 20 | std_msgs/Header header 21 | 22 | string[] name 23 | float64[] position 24 | float64[] velocity 25 | float64[] effort 26 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Joy.msg: -------------------------------------------------------------------------------- 1 | # Reports the state of a joystick's axes and buttons. 2 | 3 | # The timestamp is the time at which data is received from the joystick. 4 | std_msgs/Header header 5 | 6 | # The axes measurements from a joystick. 7 | float32[] axes 8 | 9 | # The buttons measurements from a joystick. 10 | int32[] buttons 11 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JoyFeedback.msg: -------------------------------------------------------------------------------- 1 | # Declare of the type of feedback 2 | uint8 TYPE_LED = 0 3 | uint8 TYPE_RUMBLE = 1 4 | uint8 TYPE_BUZZER = 2 5 | 6 | uint8 type 7 | 8 | # This will hold an id number for each type of each feedback. 9 | # Example, the first led would be id=0, the second would be id=1 10 | uint8 id 11 | 12 | # Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is 13 | # actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. 14 | float32 intensity 15 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JoyFeedbackArray.msg: -------------------------------------------------------------------------------- 1 | # This message publishes values for multiple feedback at once. 2 | JoyFeedback[] array 3 | -------------------------------------------------------------------------------- /sensor_msgs/msg/LaserEcho.msg: -------------------------------------------------------------------------------- 1 | # This message is a submessage of MultiEchoLaserScan and is not intended 2 | # to be used separately. 3 | 4 | float32[] echoes # Multiple values of ranges or intensities. 5 | # Each array represents data from the same angle increment. 6 | -------------------------------------------------------------------------------- /sensor_msgs/msg/LaserScan.msg: -------------------------------------------------------------------------------- 1 | # Single scan from a planar laser range-finder 2 | # 3 | # If you have another ranging device with different behavior (e.g. a sonar 4 | # array), please find or create a different message, since applications 5 | # will make fairly laser-specific assumptions about this data 6 | 7 | std_msgs/Header header # timestamp in the header is the acquisition time of 8 | # the first ray in the scan. 9 | # 10 | # in frame frame_id, angles are measured around 11 | # the positive Z axis (counterclockwise, if Z is up) 12 | # with zero angle being forward along the x axis 13 | 14 | float32 angle_min # start angle of the scan [rad] 15 | float32 angle_max # end angle of the scan [rad] 16 | float32 angle_increment # angular distance between measurements [rad] 17 | 18 | float32 time_increment # time between measurements [seconds] - if your scanner 19 | # is moving, this will be used in interpolating position 20 | # of 3d points 21 | float32 scan_time # time between scans [seconds] 22 | 23 | float32 range_min # minimum range value [m] 24 | float32 range_max # maximum range value [m] 25 | 26 | float32[] ranges # range data [m] 27 | # (Note: values < range_min or > range_max should be discarded) 28 | float32[] intensities # intensity data [device-specific units]. If your 29 | # device does not provide intensities, please leave 30 | # the array empty. 31 | -------------------------------------------------------------------------------- /sensor_msgs/msg/MagneticField.msg: -------------------------------------------------------------------------------- 1 | # Measurement of the Magnetic Field vector at a specific location. 2 | # 3 | # If the covariance of the measurement is known, it should be filled in. 4 | # If all you know is the variance of each measurement, e.g. from the datasheet, 5 | # just put those along the diagonal. 6 | # A covariance matrix of all zeros will be interpreted as "covariance unknown", 7 | # and to use the data a covariance will have to be assumed or gotten from some 8 | # other source. 9 | 10 | std_msgs/Header header # timestamp is the time the 11 | # field was measured 12 | # frame_id is the location and orientation 13 | # of the field measurement 14 | 15 | geometry_msgs/Vector3 magnetic_field # x, y, and z components of the 16 | # field vector in Tesla 17 | # If your sensor does not output 3 axes, 18 | # put NaNs in the components not reported. 19 | 20 | float64[9] magnetic_field_covariance # Row major about x, y, z axes 21 | # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /sensor_msgs/msg/MultiDOFJointState.msg: -------------------------------------------------------------------------------- 1 | # Representation of state for joints with multiple degrees of freedom, 2 | # following the structure of JointState which can only represent a single degree of freedom. 3 | # 4 | # It is assumed that a joint in a system corresponds to a transform that gets applied 5 | # along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) 6 | # and those 3DOF can be expressed as a transformation matrix, and that transformation 7 | # matrix can be converted back to (x, y, yaw) 8 | # 9 | # Each joint is uniquely identified by its name 10 | # The header specifies the time at which the joint states were recorded. All the joint states 11 | # in one message have to be recorded at the same time. 12 | # 13 | # This message consists of a multiple arrays, one for each part of the joint state. 14 | # The goal is to make each of the fields optional. When e.g. your joints have no 15 | # wrench associated with them, you can leave the wrench array empty. 16 | # 17 | # All arrays in this message should have the same size, or be empty. 18 | # This is the only way to uniquely associate the joint name with the correct 19 | # states. 20 | 21 | std_msgs/Header header 22 | 23 | string[] joint_names 24 | geometry_msgs/Transform[] transforms 25 | geometry_msgs/Twist[] twist 26 | geometry_msgs/Wrench[] wrench 27 | -------------------------------------------------------------------------------- /sensor_msgs/msg/MultiEchoLaserScan.msg: -------------------------------------------------------------------------------- 1 | # Single scan from a multi-echo planar laser range-finder 2 | # 3 | # If you have another ranging device with different behavior (e.g. a sonar 4 | # array), please find or create a different message, since applications 5 | # will make fairly laser-specific assumptions about this data 6 | 7 | std_msgs/Header header # timestamp in the header is the acquisition time of 8 | # the first ray in the scan. 9 | # 10 | # in frame frame_id, angles are measured around 11 | # the positive Z axis (counterclockwise, if Z is up) 12 | # with zero angle being forward along the x axis 13 | 14 | float32 angle_min # start angle of the scan [rad] 15 | float32 angle_max # end angle of the scan [rad] 16 | float32 angle_increment # angular distance between measurements [rad] 17 | 18 | float32 time_increment # time between measurements [seconds] - if your scanner 19 | # is moving, this will be used in interpolating position 20 | # of 3d points 21 | float32 scan_time # time between scans [seconds] 22 | 23 | float32 range_min # minimum range value [m] 24 | float32 range_max # maximum range value [m] 25 | 26 | LaserEcho[] ranges # range data [m] 27 | # (Note: NaNs, values < range_min or > range_max should be discarded) 28 | # +Inf measurements are out of range 29 | # -Inf measurements are too close to determine exact distance. 30 | LaserEcho[] intensities # intensity data [device-specific units]. If your 31 | # device does not provide intensities, please leave 32 | # the array empty. 33 | -------------------------------------------------------------------------------- /sensor_msgs/msg/NavSatFix.msg: -------------------------------------------------------------------------------- 1 | # Navigation Satellite fix for any Global Navigation Satellite System 2 | # 3 | # Specified using the WGS 84 reference ellipsoid 4 | 5 | # header.stamp specifies the ROS time for this measurement (the 6 | # corresponding satellite time may be reported using the 7 | # sensor_msgs/TimeReference message). 8 | # 9 | # header.frame_id is the frame of reference reported by the satellite 10 | # receiver, usually the location of the antenna. This is a 11 | # Euclidean frame relative to the vehicle, not a reference 12 | # ellipsoid. 13 | std_msgs/Header header 14 | 15 | # Satellite fix status information. 16 | NavSatStatus status 17 | 18 | # Latitude [degrees]. Positive is north of equator; negative is south. 19 | float64 latitude 20 | 21 | # Longitude [degrees]. Positive is east of prime meridian; negative is west. 22 | float64 longitude 23 | 24 | # Altitude [m]. Positive is above the WGS 84 ellipsoid 25 | # (quiet NaN if no altitude is available). 26 | float64 altitude 27 | 28 | # Position covariance [m^2] defined relative to a tangential plane 29 | # through the reported position. The components are East, North, and 30 | # Up (ENU), in row-major order. 31 | # 32 | # Beware: this coordinate system exhibits singularities at the poles. 33 | float64[9] position_covariance 34 | 35 | # If the covariance of the fix is known, fill it in completely. If the 36 | # GPS receiver provides the variance of each measurement, put them 37 | # along the diagonal. If only Dilution of Precision is available, 38 | # estimate an approximate covariance from that. 39 | 40 | uint8 COVARIANCE_TYPE_UNKNOWN = 0 41 | uint8 COVARIANCE_TYPE_APPROXIMATED = 1 42 | uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 43 | uint8 COVARIANCE_TYPE_KNOWN = 3 44 | 45 | uint8 position_covariance_type 46 | -------------------------------------------------------------------------------- /sensor_msgs/msg/NavSatStatus.msg: -------------------------------------------------------------------------------- 1 | # Navigation Satellite fix status for any Global Navigation Satellite System. 2 | # 3 | # Whether to output an augmented fix is determined by both the fix 4 | # type and the last time differential corrections were received. A 5 | # fix is valid when status >= STATUS_FIX. 6 | 7 | int8 STATUS_UNKNOWN = -2 # status is not yet set 8 | int8 STATUS_NO_FIX = -1 # unable to fix position 9 | int8 STATUS_FIX = 0 # unaugmented fix 10 | int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation 11 | int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation 12 | 13 | int8 status -2 # STATUS_UNKNOWN 14 | 15 | # Bits defining which Global Navigation Satellite System signals were 16 | # used by the receiver. 17 | 18 | uint16 SERVICE_UNKNOWN = 0 # Remember service is a bitfield, so checking (service & SERVICE_UNKNOWN) will not work. Use == instead. 19 | uint16 SERVICE_GPS = 1 20 | uint16 SERVICE_GLONASS = 2 21 | uint16 SERVICE_COMPASS = 4 # includes BeiDou. 22 | uint16 SERVICE_GALILEO = 8 23 | 24 | uint16 service 25 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointCloud.msg: -------------------------------------------------------------------------------- 1 | ## THIS MESSAGE IS DEPRECATED AS OF FOXY 2 | ## Please use sensor_msgs/PointCloud2 3 | 4 | # This message holds a collection of 3d points, plus optional additional 5 | # information about each point. 6 | 7 | # Time of sensor data acquisition, coordinate frame ID. 8 | std_msgs/Header header 9 | 10 | # Array of 3d points. Each Point32 should be interpreted as a 3d point 11 | # in the frame given in the header. 12 | geometry_msgs/Point32[] points 13 | 14 | # Each channel should have the same number of elements as points array, 15 | # and the data in each channel should correspond 1:1 with each point. 16 | # Channel names in common practice are listed in ChannelFloat32.msg. 17 | ChannelFloat32[] channels 18 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointCloud2.msg: -------------------------------------------------------------------------------- 1 | # This message holds a collection of N-dimensional points, which may 2 | # contain additional information such as normals, intensity, etc. The 3 | # point data is stored as a binary blob, its layout described by the 4 | # contents of the "fields" array. 5 | # 6 | # The point cloud data may be organized 2d (image-like) or 1d (unordered). 7 | # Point clouds organized as 2d images may be produced by camera depth sensors 8 | # such as stereo or time-of-flight. 9 | 10 | # Time of sensor data acquisition, and the coordinate frame ID (for 3d points). 11 | std_msgs/Header header 12 | 13 | # 2D structure of the point cloud. If the cloud is unordered, height is 14 | # 1 and width is the length of the point cloud. 15 | uint32 height 16 | uint32 width 17 | 18 | # Describes the channels and their layout in the binary data blob. 19 | PointField[] fields 20 | 21 | bool is_bigendian # Is this data bigendian? 22 | uint32 point_step # Length of a point in bytes 23 | uint32 row_step # Length of a row in bytes 24 | uint8[] data # Actual point data, size is (row_step*height) 25 | 26 | bool is_dense # True if there are no invalid points 27 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointField.msg: -------------------------------------------------------------------------------- 1 | # This message holds the description of one point entry in the 2 | # PointCloud2 message format. 3 | uint8 INT8 = 1 4 | uint8 UINT8 = 2 5 | uint8 INT16 = 3 6 | uint8 UINT16 = 4 7 | uint8 INT32 = 5 8 | uint8 UINT32 = 6 9 | uint8 FLOAT32 = 7 10 | uint8 FLOAT64 = 8 11 | 12 | # Common PointField names are x, y, z, intensity, rgb, rgba 13 | string name # Name of field 14 | uint32 offset # Offset from start of point struct 15 | uint8 datatype # Datatype enumeration, see above 16 | uint32 count # How many elements in the field 17 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Range.msg: -------------------------------------------------------------------------------- 1 | # Single range reading from an active ranger that emits energy and reports 2 | # one range reading that is valid along an arc at the distance measured. 3 | # This message is not appropriate for laser scanners. See the LaserScan 4 | # message if you are working with a laser scanner. 5 | # 6 | # This message also can represent a fixed-distance (binary) ranger. This 7 | # sensor will have min_range===max_range===distance of detection. 8 | # These sensors follow REP 117 and will output -Inf if the object is detected 9 | # and +Inf if the object is outside of the detection range. 10 | 11 | std_msgs/Header header # timestamp in the header is the time the ranger 12 | # returned the distance reading 13 | 14 | # Radiation type enums 15 | # If you want a value added to this list, send an email to the ros-users list 16 | uint8 ULTRASOUND=0 17 | uint8 INFRARED=1 18 | 19 | uint8 radiation_type # the type of radiation used by the sensor 20 | # (sound, IR, etc) [enum] 21 | 22 | float32 field_of_view # the size of the arc that the distance reading is 23 | # valid for [rad] 24 | # the object causing the range reading may have 25 | # been anywhere within -field_of_view/2 and 26 | # field_of_view/2 at the measured range. 27 | # 0 angle corresponds to the x-axis of the sensor. 28 | 29 | float32 min_range # minimum range value [m] 30 | float32 max_range # maximum range value [m] 31 | # Fixed distance rangers require min_range==max_range 32 | 33 | float32 range # range data [m] 34 | # (Note: values < range_min or > range_max should be discarded) 35 | # Fixed distance rangers only output -Inf or +Inf. 36 | # -Inf represents a detection within fixed distance. 37 | # (Detection too close to the sensor to quantify) 38 | # +Inf represents no detection within the fixed distance. 39 | # (Object out of range) 40 | 41 | float32 variance # variance of the range sensor 42 | # 0 is interpreted as variance unknown 43 | -------------------------------------------------------------------------------- /sensor_msgs/msg/RegionOfInterest.msg: -------------------------------------------------------------------------------- 1 | # This message is used to specify a region of interest within an image. 2 | # 3 | # When used to specify the ROI setting of the camera when the image was 4 | # taken, the height and width fields should either match the height and 5 | # width fields for the associated image; or height = width = 0 6 | # indicates that the full resolution image was captured. 7 | 8 | uint32 x_offset # Leftmost pixel of the ROI 9 | # (0 if the ROI includes the left edge of the image) 10 | uint32 y_offset # Topmost pixel of the ROI 11 | # (0 if the ROI includes the top edge of the image) 12 | uint32 height # Height of ROI 13 | uint32 width # Width of ROI 14 | 15 | # True if a distinct rectified ROI should be calculated from the "raw" 16 | # ROI in this message. Typically this should be False if the full image 17 | # is captured (ROI not used), and True if a subwindow is captured (ROI 18 | # used). 19 | bool do_rectify 20 | -------------------------------------------------------------------------------- /sensor_msgs/msg/RelativeHumidity.msg: -------------------------------------------------------------------------------- 1 | # Single reading from a relative humidity sensor. 2 | # Defines the ratio of partial pressure of water vapor to the saturated vapor 3 | # pressure at a temperature. 4 | 5 | std_msgs/Header header # timestamp of the measurement 6 | # frame_id is the location of the humidity sensor 7 | 8 | float64 relative_humidity # Expression of the relative humidity 9 | # from 0.0 to 1.0. 10 | # 0.0 is no partial pressure of water vapor 11 | # 1.0 represents partial pressure of saturation 12 | 13 | float64 variance # 0 is interpreted as variance unknown 14 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Temperature.msg: -------------------------------------------------------------------------------- 1 | # Single temperature reading. 2 | 3 | std_msgs/Header header # timestamp is the time the temperature was measured 4 | # frame_id is the location of the temperature reading 5 | 6 | float64 temperature # Measurement of the Temperature in Degrees Celsius. 7 | 8 | float64 variance # 0 is interpreted as variance unknown. 9 | -------------------------------------------------------------------------------- /sensor_msgs/msg/TimeReference.msg: -------------------------------------------------------------------------------- 1 | # Measurement from an external time source not actively synchronized with the system clock. 2 | 3 | std_msgs/Header header # stamp is system time for which measurement was valid 4 | # frame_id is not used 5 | 6 | builtin_interfaces/Time time_ref # corresponding time from this external source 7 | string source # (optional) name of time source 8 | -------------------------------------------------------------------------------- /sensor_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | sensor_msgs 5 | 5.7.0 6 | A package containing some sensor data related message and service definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | builtin_interfaces 22 | geometry_msgs 23 | std_msgs 24 | 25 | rosidl_default_runtime 26 | 27 | ament_cmake_gtest 28 | ament_lint_auto 29 | ament_lint_common 30 | rosidl_cmake 31 | 32 | rosidl_interface_packages 33 | 34 | 35 | ament_cmake 36 | 37 | 38 | -------------------------------------------------------------------------------- /sensor_msgs/srv/SetCameraInfo.srv: -------------------------------------------------------------------------------- 1 | # This service requests that a camera stores the given CameraInfo as that 2 | # camera's calibration information. 3 | # 4 | # The width and height in the camera_info field should match what the 5 | # camera is currently outputting on its camera_info topic, and the camera 6 | # will assume that the region of the imager that is being referred to is 7 | # the region that the camera is currently capturing. 8 | 9 | sensor_msgs/CameraInfo camera_info # The camera_info to store 10 | --- 11 | bool success # True if the call succeeded 12 | string status_message # Used to give details about success 13 | -------------------------------------------------------------------------------- /sensor_msgs/test/test_pointcloud_conversion.cpp: -------------------------------------------------------------------------------- 1 | // Copyright 2019 Open Source Robotics Foundation, Inc. 2 | // 3 | // Licensed under the Apache License, Version 2.0 (the "License"); 4 | // you may not use this file except in compliance with the License. 5 | // You may obtain a copy of the License at 6 | // 7 | // http://www.apache.org/licenses/LICENSE-2.0 8 | // 9 | // Unless required by applicable law or agreed to in writing, software 10 | // distributed under the License is distributed on an "AS IS" BASIS, 11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | // See the License for the specific language governing permissions and 13 | // limitations under the License. 14 | 15 | #include 16 | 17 | #include "geometry_msgs/msg/point32.hpp" 18 | #include "sensor_msgs/msg/point_cloud.hpp" 19 | #include "sensor_msgs/msg/point_cloud2.hpp" 20 | 21 | #define SENSOR_MSGS_SKIP_WARNING 22 | 23 | // #warning suppression 24 | // Not working due to preprocessor ignoring pragmas in g++ 25 | // https://gcc.gnu.org/bugzilla/show_bug.cgi?id=53431 26 | // Clang doesn't support suppressing -Wcpp probably like above. 27 | // And I can't find any windows way to suppress it either. 28 | 29 | #include "sensor_msgs/point_cloud_conversion.hpp" 30 | #undef SENSOR_MSGS_SKIP_WARNING 31 | 32 | #include "sensor_msgs/point_field_conversion.hpp" 33 | 34 | TEST(sensor_msgs, PointCloudConversion) 35 | { 36 | // Build a PointCloud 37 | sensor_msgs::msg::PointCloud cloud; 38 | 39 | cloud.header.stamp.sec = 100; 40 | cloud.header.stamp.nanosec = 500; 41 | cloud.header.frame_id = "cloud_frame"; 42 | 43 | sensor_msgs::msg::ChannelFloat32 intensity, range; 44 | intensity.name = "intensity"; 45 | range.name = "range"; 46 | 47 | for (size_t ii = 0; ii < 100; ++ii) { 48 | auto pt = geometry_msgs::msg::Point32(); 49 | pt.x = static_cast(1 * ii); 50 | pt.y = static_cast(2 * ii); 51 | pt.z = static_cast(3 * ii); 52 | cloud.points.push_back(pt); 53 | 54 | intensity.values.push_back(static_cast(4 * ii)); 55 | range.values.push_back(static_cast(5 * ii)); 56 | } 57 | cloud.channels.push_back(intensity); 58 | cloud.channels.push_back(range); 59 | 60 | // Convert to PointCloud2 61 | sensor_msgs::msg::PointCloud2 cloud2; 62 | 63 | #ifdef _MSC_VER 64 | #pragma warning(push) 65 | #pragma warning(disable : 4996) 66 | #else 67 | #pragma GCC diagnostic push 68 | #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 69 | #endif 70 | auto ret_cc2 = sensor_msgs::convertPointCloudToPointCloud2(cloud, cloud2); 71 | #ifdef _MSC_VER 72 | #pragma warning(pop) 73 | #else 74 | #pragma GCC diagnostic pop 75 | #endif 76 | ASSERT_TRUE(ret_cc2); 77 | 78 | EXPECT_EQ(1u, cloud2.height); 79 | EXPECT_EQ(100u, cloud2.width); 80 | 81 | EXPECT_EQ(cloud2.fields[0].name, "x"); 82 | EXPECT_EQ(cloud2.fields[1].name, "y"); 83 | EXPECT_EQ(cloud2.fields[2].name, "z"); 84 | EXPECT_EQ(cloud2.fields[3].name, "intensity"); 85 | EXPECT_EQ(cloud2.fields[4].name, "range"); 86 | 87 | EXPECT_EQ(cloud2.fields.size(), 5u); 88 | EXPECT_EQ(cloud2.header.frame_id, "cloud_frame"); 89 | EXPECT_EQ(cloud2.header.stamp.sec, 100); 90 | EXPECT_EQ(cloud2.header.stamp.nanosec, 500u); 91 | 92 | // Convert back to PointCloud 93 | sensor_msgs::msg::PointCloud cloud3; 94 | #ifdef _MSC_VER 95 | #pragma warning(push) 96 | #pragma warning(disable : 4996) 97 | #else 98 | #pragma GCC diagnostic push 99 | #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 100 | #endif 101 | auto ret_c2c = sensor_msgs::convertPointCloud2ToPointCloud(cloud2, cloud3); 102 | #ifdef _MSC_VER 103 | #pragma warning(pop) 104 | #else 105 | #pragma GCC diagnostic pop 106 | #endif 107 | ASSERT_TRUE(ret_c2c); 108 | EXPECT_EQ(cloud3.points.size(), 100u); 109 | EXPECT_EQ(cloud3.channels.size(), 2u); 110 | 111 | EXPECT_EQ(cloud3.channels[0].name, "intensity"); 112 | EXPECT_EQ(cloud3.channels[0].values.size(), 100u); 113 | EXPECT_FLOAT_EQ(cloud3.channels[0].values[0], 0.0); 114 | EXPECT_FLOAT_EQ(cloud3.channels[0].values[10], 40.0); 115 | 116 | EXPECT_EQ(cloud3.channels[1].name, "range"); 117 | EXPECT_EQ(cloud3.channels[1].values.size(), 100u); 118 | EXPECT_FLOAT_EQ(cloud3.channels[1].values[0], 0.0); 119 | EXPECT_FLOAT_EQ(cloud3.channels[1].values[10], 50.0); 120 | } 121 | -------------------------------------------------------------------------------- /sensor_msgs_py/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package sensor_msgs_py 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | 8 | 5.6.0 (2025-04-25) 9 | ------------------ 10 | 11 | 5.5.0 (2025-03-20) 12 | ------------------ 13 | 14 | 5.4.2 (2024-11-20) 15 | ------------------ 16 | * Add ament_xmllint to sensor_msgs_py. (`#259 `_) 17 | * Contributors: Chris Lalancette 18 | 19 | 5.4.1 (2024-06-17) 20 | ------------------ 21 | * Fix formatting in sensor_msgs_py (`#248 `_) 22 | * Contributors: Christophe Bedard 23 | 24 | 5.4.0 (2024-04-26) 25 | ------------------ 26 | 27 | 5.3.4 (2024-04-16) 28 | ------------------ 29 | 30 | 5.3.3 (2024-04-10) 31 | ------------------ 32 | 33 | 5.3.2 (2024-04-10) 34 | ------------------ 35 | * Clarify the license. (`#241 `_) 36 | In particular, every package in this repository is Apache 2.0 37 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 38 | and LICENSE files down into the individual packages, and 39 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 40 | file (it already had the correct LICENSE file). 41 | * Contributors: Chris Lalancette 42 | 43 | 5.3.1 (2024-03-28) 44 | ------------------ 45 | 46 | 5.3.0 (2024-01-24) 47 | ------------------ 48 | 49 | 5.2.2 (2023-12-26) 50 | ------------------ 51 | 52 | 5.2.1 (2023-11-06) 53 | ------------------ 54 | 55 | 5.2.0 (2023-06-07) 56 | ------------------ 57 | * Allow pointcloud create_cloud function to set specific point_step (`#223 `_) 58 | * Fix read_points_numpy field_names parameter 59 | * Contributors: George Broughton 60 | 61 | 5.1.0 (2023-04-27) 62 | ------------------ 63 | 64 | 5.0.0 (2023-04-11) 65 | ------------------ 66 | * Add missing dep for sensor_msgs_py (`#217 `_) 67 | * Contributors: Yadu 68 | 69 | 4.7.0 (2023-02-13) 70 | ------------------ 71 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 72 | * Contributors: Audrow Nash 73 | 74 | 4.6.1 (2022-11-02) 75 | ------------------ 76 | 77 | 4.6.0 (2022-09-13) 78 | ------------------ 79 | * Add support for non standard point step sizes (`#199 `_) 80 | * Remove reference to old implementation (`#198 `_) 81 | * Contributors: Florian Vahl 82 | 83 | 4.5.0 (2022-05-19) 84 | ------------------ 85 | 86 | 4.4.0 (2022-04-29) 87 | ------------------ 88 | 89 | 4.3.0 (2022-04-29) 90 | ------------------ 91 | 92 | 4.2.1 (2022-03-31) 93 | ------------------ 94 | 95 | 4.2.0 (2022-03-30) 96 | ------------------ 97 | * Add in a compatibility layer for older versions of numpy. (`#185 `_) 98 | * Port pointcloud creation to numpy. (`#175 `_) 99 | * Contributors: Chris Lalancette, Florian Vahl 100 | 101 | 4.1.1 (2022-03-26) 102 | ------------------ 103 | 104 | 4.1.0 (2022-03-01) 105 | ------------------ 106 | 107 | 4.0.0 (2021-12-14) 108 | ------------------ 109 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 110 | * Contributors: Audrow Nash 111 | 112 | 3.0.0 (2021-08-24) 113 | ------------------ 114 | 115 | 2.3.0 (2021-08-11) 116 | ------------------ 117 | 118 | 2.2.3 (2021-04-27) 119 | ------------------ 120 | * Use underscores instead of dashes in setup.cfg (`#150 `_) 121 | * Contributors: Ivan Santiago Paunovic 122 | 123 | 2.2.2 (2021-04-06) 124 | ------------------ 125 | 126 | 2.2.1 (2021-01-25) 127 | ------------------ 128 | 129 | 2.2.0 (2020-12-10) 130 | ------------------ 131 | * Port of point_cloud2.py from ROS1 to ROS2. As seperate pkg. (`#128 `_) 132 | * Contributors: Sebastian Grans 133 | 134 | 2.1.0 (2020-07-21 18:27) 135 | ------------------------ 136 | 137 | 2.0.2 (2020-07-21 18:21) 138 | ------------------------ 139 | 140 | 2.0.1 (2020-05-26) 141 | ------------------ 142 | 143 | 2.0.0 (2020-05-21 11:53) 144 | ------------------------ 145 | 146 | 1.0.0 (2020-05-21 01:49) 147 | ------------------------ 148 | 149 | 0.9.0 (2020-04-25) 150 | ------------------ 151 | 152 | 0.8.1 (2019-10-23) 153 | ------------------ 154 | 155 | 0.8.0 (2019-09-26) 156 | ------------------ 157 | 158 | 0.7.0 (2019-04-14) 159 | ------------------ 160 | 161 | 0.6.1 (2018-12-06) 162 | ------------------ 163 | 164 | 0.6.0 (2018-11-16) 165 | ------------------ 166 | 167 | 0.5.1 (2018-08-20) 168 | ------------------ 169 | 170 | 0.5.0 (2018-06-25) 171 | ------------------ 172 | 173 | 0.4.0 (2017-12-08) 174 | ------------------ 175 | -------------------------------------------------------------------------------- /sensor_msgs_py/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the 3-Clause BSD License, as dictated by that 3 | [license](https://opensource.org/licenses/BSD-3-Clause). 4 | -------------------------------------------------------------------------------- /sensor_msgs_py/LICENSE: -------------------------------------------------------------------------------- 1 | Redistribution and use in source and binary forms, with or without 2 | modification, are permitted provided that the following conditions are met: 3 | 4 | * Redistributions of source code must retain the above copyright 5 | notice, this list of conditions and the following disclaimer. 6 | 7 | * Redistributions in binary form must reproduce the above copyright 8 | notice, this list of conditions and the following disclaimer in the 9 | documentation and/or other materials provided with the distribution. 10 | 11 | * Neither the name of the {copyright_holder} nor the names of its 12 | contributors may be used to endorse or promote products derived from 13 | this software without specific prior written permission. 14 | 15 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 16 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 17 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 18 | ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 19 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 20 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 21 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 22 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 23 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 24 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 25 | POSSIBILITY OF SUCH DAMAGE. 26 | -------------------------------------------------------------------------------- /sensor_msgs_py/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | sensor_msgs_py 5 | 5.7.0 6 | A package for easy creation and reading of PointCloud2 messages in Python. 7 | 8 | Tully Foote 9 | 10 | BSD 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | Sebastian Grans 16 | 17 | python3-numpy 18 | sensor_msgs 19 | std_msgs 20 | 21 | ament_copyright 22 | ament_flake8 23 | ament_pep257 24 | ament_xmllint 25 | python3-pytest 26 | 27 | 28 | ament_python 29 | 30 | 31 | -------------------------------------------------------------------------------- /sensor_msgs_py/pytest.ini: -------------------------------------------------------------------------------- 1 | [pytest] 2 | junit_family=xunit2 3 | -------------------------------------------------------------------------------- /sensor_msgs_py/resource/sensor_msgs_py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/common_interfaces/fa74e954260279e97182f82776dc086328502b67/sensor_msgs_py/resource/sensor_msgs_py -------------------------------------------------------------------------------- /sensor_msgs_py/sensor_msgs_py/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/common_interfaces/fa74e954260279e97182f82776dc086328502b67/sensor_msgs_py/sensor_msgs_py/__init__.py -------------------------------------------------------------------------------- /sensor_msgs_py/setup.cfg: -------------------------------------------------------------------------------- 1 | [develop] 2 | script_dir=$base/lib/sensor_msgs_py 3 | [install] 4 | install_scripts=$base/lib/sensor_msgs_py 5 | -------------------------------------------------------------------------------- /sensor_msgs_py/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import setup 2 | 3 | package_name = 'sensor_msgs_py' 4 | 5 | setup( 6 | name=package_name, 7 | version='5.7.0', 8 | packages=[package_name], 9 | data_files=[ 10 | ('share/ament_index/resource_index/packages', 11 | ['resource/' + package_name]), 12 | ('share/' + package_name, ['package.xml']), 13 | ], 14 | install_requires=['setuptools'], 15 | zip_safe=True, 16 | maintainer='Tully Foote', 17 | maintainer_email='tfoote@openrobotics.org', 18 | author='Sebastian Grans', 19 | author_email='sebastian.grans@gmail.com', 20 | description='A package for easy creation and reading of PointCloud2 messages in Python.', 21 | license='BSD', 22 | tests_require=['pytest'], 23 | ) 24 | -------------------------------------------------------------------------------- /sensor_msgs_py/test/test_copyright.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_copyright.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.copyright 20 | @pytest.mark.linter 21 | def test_copyright(): 22 | rc = main(argv=['.', 'test']) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /sensor_msgs_py/test/test_flake8.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Redistribution and use in source and binary forms, with or without 4 | # modification, are permitted provided that the following conditions are met: 5 | # 6 | # * Redistributions of source code must retain the above copyright 7 | # notice, this list of conditions and the following disclaimer. 8 | # 9 | # * Redistributions in binary form must reproduce the above copyright 10 | # notice, this list of conditions and the following disclaimer in the 11 | # documentation and/or other materials provided with the distribution. 12 | # 13 | # * Neither the name of the copyright holder nor the names of its 14 | # contributors may be used to endorse or promote products derived from 15 | # this software without specific prior written permission. 16 | # 17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | # POSSIBILITY OF SUCH DAMAGE. 28 | 29 | 30 | from ament_flake8.main import main_with_errors 31 | import pytest 32 | 33 | 34 | @pytest.mark.flake8 35 | @pytest.mark.linter 36 | def test_flake8(): 37 | rc, errors = main_with_errors(argv=[]) 38 | assert rc == 0, \ 39 | 'Found %d code style errors / warnings:\n' % len(errors) + \ 40 | '\n'.join(errors) 41 | -------------------------------------------------------------------------------- /sensor_msgs_py/test/test_pep257.py: -------------------------------------------------------------------------------- 1 | # Copyright 2020 Open Source Robotics Foundation, Inc. 2 | # 3 | # Redistribution and use in source and binary forms, with or without 4 | # modification, are permitted provided that the following conditions are met: 5 | # 6 | # * Redistributions of source code must retain the above copyright 7 | # notice, this list of conditions and the following disclaimer. 8 | # 9 | # * Redistributions in binary form must reproduce the above copyright 10 | # notice, this list of conditions and the following disclaimer in the 11 | # documentation and/or other materials provided with the distribution. 12 | # 13 | # * Neither the name of the copyright holder nor the names of its 14 | # contributors may be used to endorse or promote products derived from 15 | # this software without specific prior written permission. 16 | # 17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE 21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | # POSSIBILITY OF SUCH DAMAGE. 28 | 29 | 30 | from ament_pep257.main import main 31 | import pytest 32 | 33 | 34 | @pytest.mark.linter 35 | @pytest.mark.pep257 36 | def test_pep257(): 37 | rc = main(argv=['.', 'test']) 38 | assert rc == 0, 'Found code style errors / warnings' 39 | -------------------------------------------------------------------------------- /sensor_msgs_py/test/test_xmllint.py: -------------------------------------------------------------------------------- 1 | # Copyright 2019 Open Source Robotics Foundation, Inc. 2 | # 3 | # Licensed under the Apache License, Version 2.0 (the "License"); 4 | # you may not use this file except in compliance with the License. 5 | # You may obtain a copy of the License at 6 | # 7 | # http://www.apache.org/licenses/LICENSE-2.0 8 | # 9 | # Unless required by applicable law or agreed to in writing, software 10 | # distributed under the License is distributed on an "AS IS" BASIS, 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12 | # See the License for the specific language governing permissions and 13 | # limitations under the License. 14 | 15 | from ament_xmllint.main import main 16 | import pytest 17 | 18 | 19 | @pytest.mark.linter 20 | @pytest.mark.xmllint 21 | def test_xmllint(): 22 | rc = main(argv=[]) 23 | assert rc == 0, 'Found errors' 24 | -------------------------------------------------------------------------------- /shape_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package shape_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | 8 | 5.6.0 (2025-04-25) 9 | ------------------ 10 | 11 | 5.5.0 (2025-03-20) 12 | ------------------ 13 | 14 | 5.4.2 (2024-11-20) 15 | ------------------ 16 | 17 | 5.4.1 (2024-06-17) 18 | ------------------ 19 | 20 | 5.4.0 (2024-04-26) 21 | ------------------ 22 | * Update quality declaration documents (`#245 `_) 23 | * Contributors: Christophe Bedard 24 | 25 | 5.3.4 (2024-04-16) 26 | ------------------ 27 | 28 | 5.3.3 (2024-04-10) 29 | ------------------ 30 | 31 | 5.3.2 (2024-04-10) 32 | ------------------ 33 | * Clarify the license. (`#241 `_) 34 | In particular, every package in this repository is Apache 2.0 35 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 36 | and LICENSE files down into the individual packages, and 37 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 38 | file (it already had the correct LICENSE file). 39 | * Contributors: Chris Lalancette 40 | 41 | 5.3.1 (2024-03-28) 42 | ------------------ 43 | 44 | 5.3.0 (2024-01-24) 45 | ------------------ 46 | 47 | 5.2.2 (2023-12-26) 48 | ------------------ 49 | 50 | 5.2.1 (2023-11-06) 51 | ------------------ 52 | 53 | 5.2.0 (2023-06-07) 54 | ------------------ 55 | 56 | 5.1.0 (2023-04-27) 57 | ------------------ 58 | 59 | 5.0.0 (2023-04-11) 60 | ------------------ 61 | 62 | 4.7.0 (2023-02-13) 63 | ------------------ 64 | * Update common_interfaces to C++17. (`#215 `_) 65 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 66 | * Contributors: Audrow Nash, Chris Lalancette 67 | 68 | 4.6.1 (2022-11-02) 69 | ------------------ 70 | 71 | 4.6.0 (2022-09-13) 72 | ------------------ 73 | 74 | 4.5.0 (2022-05-19) 75 | ------------------ 76 | * Fix SolidPrimitive.msg to contain a single Polygon (`#189 `_) 77 | * Contributors: M. Fatih Cırıt 78 | 79 | 4.4.0 (2022-04-29) 80 | ------------------ 81 | 82 | 4.3.0 (2022-04-29) 83 | ------------------ 84 | 85 | 4.2.1 (2022-03-31) 86 | ------------------ 87 | 88 | 4.2.0 (2022-03-30) 89 | ------------------ 90 | 91 | 4.1.1 (2022-03-26) 92 | ------------------ 93 | 94 | 4.1.0 (2022-03-01) 95 | ------------------ 96 | * Interface packages should fully on the interface packages that they depend on (`#173 `_) 97 | * Contributors: Grey 98 | 99 | 4.0.0 (2021-12-14) 100 | ------------------ 101 | * Add prism type to the SolidPrimitive.msg (`#166 `_) (`#167 `_) 102 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 103 | * Contributors: Audrow Nash, M. Fatih Cırıt 104 | 105 | 3.0.0 (2021-08-24) 106 | ------------------ 107 | 108 | 2.3.0 (2021-08-11) 109 | ------------------ 110 | 111 | 2.2.3 (2021-04-27) 112 | ------------------ 113 | 114 | 2.2.2 (2021-04-06) 115 | ------------------ 116 | * Change index.ros.org -> docs.ros.org. (`#149 `_) 117 | * updating quality declaration links (re: `ros2/docs.ros2.org#52 `_) (`#145 `_) 118 | * Contributors: Chris Lalancette, shonigmann 119 | 120 | 2.2.1 (2021-01-25) 121 | ------------------ 122 | 123 | 2.2.0 (2020-12-10) 124 | ------------------ 125 | * Update QDs to QL 1 (`#135 `_) 126 | * Update package maintainers. (`#132 `_) 127 | * Updated Quality Level to 2 (`#131 `_) 128 | * Contributors: Alejandro Hernández Cordero, Michel Hidalgo, Stephen Brawner 129 | 130 | 2.1.0 (2020-07-21) 131 | ------------------ 132 | 133 | 2.0.2 (2020-07-21) 134 | ------------------ 135 | * Update Quality levels to level 3 (`#124 `_) 136 | * Add Security Vulnerability Policy pointing to REP-2006. (`#120 `_) 137 | * Contributors: Chris Lalancette, brawner 138 | 139 | 2.0.1 (2020-05-26) 140 | ------------------ 141 | * QD Update Version Stability to stable version (`#121 `_) 142 | * Contributors: Alejandro Hernández Cordero 143 | 144 | 1.0.0 (2020-05-20) 145 | ------------------ 146 | * Add current-level quality declarations (`#109 `_) 147 | * Contributors: brawner 148 | -------------------------------------------------------------------------------- /shape_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(shape_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(geometry_msgs REQUIRED) 16 | find_package(rosidl_default_generators REQUIRED) 17 | 18 | set(msg_files 19 | "msg/Mesh.msg" 20 | "msg/MeshTriangle.msg" 21 | "msg/Plane.msg" 22 | "msg/SolidPrimitive.msg" 23 | ) 24 | rosidl_generate_interfaces(${PROJECT_NAME} 25 | ${msg_files} 26 | DEPENDENCIES geometry_msgs 27 | ADD_LINTER_TESTS 28 | ) 29 | 30 | ament_export_dependencies(rosidl_default_runtime) 31 | 32 | ament_package() 33 | -------------------------------------------------------------------------------- /shape_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /shape_msgs/README.md: -------------------------------------------------------------------------------- 1 | # shape_msgs 2 | 3 | This package provides several messages and services for describing 3-dimensional shapes. 4 | 5 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 6 | 7 | ## Messages (.msg) 8 | * [Mesh](msg/Mesh.msg): Holds information describing a mesh for visualization and collision detections. 9 | * [MeshTriangle](msg/MeshTriangle.msg): A single triangle of a mesh. 10 | * [Plane](msg/Plane.msg): Representation of a plane, using the plane equation ax + by + cz + d = 0. 11 | * [SolidPrimitive](msg/SolidPrimitive.msg): Describe a simple shape primitive like a box, a sphere, a cylinder, and a cone. 12 | 13 | ## Quality Declaration 14 | This package claims to be in the **Quality Level 1** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 15 | -------------------------------------------------------------------------------- /shape_msgs/msg/Mesh.msg: -------------------------------------------------------------------------------- 1 | # Definition of a mesh. 2 | 3 | # List of triangles; the index values refer to positions in vertices[]. 4 | MeshTriangle[] triangles 5 | 6 | # The actual vertices that make up the mesh. 7 | geometry_msgs/Point[] vertices 8 | -------------------------------------------------------------------------------- /shape_msgs/msg/MeshTriangle.msg: -------------------------------------------------------------------------------- 1 | # Definition of a triangle's vertices. 2 | 3 | uint32[3] vertex_indices 4 | -------------------------------------------------------------------------------- /shape_msgs/msg/Plane.msg: -------------------------------------------------------------------------------- 1 | # Representation of a plane, using the plane equation ax + by + cz + d = 0. 2 | # 3 | # a := coef[0] 4 | # b := coef[1] 5 | # c := coef[2] 6 | # d := coef[3] 7 | float64[4] coef 8 | -------------------------------------------------------------------------------- /shape_msgs/msg/SolidPrimitive.msg: -------------------------------------------------------------------------------- 1 | # Defines box, sphere, cylinder, cone and prism. 2 | # All shapes are defined to have their bounding boxes centered around 0,0,0. 3 | 4 | uint8 BOX=1 5 | uint8 SPHERE=2 6 | uint8 CYLINDER=3 7 | uint8 CONE=4 8 | uint8 PRISM=5 9 | 10 | # The type of the shape 11 | uint8 type 12 | 13 | # The dimensions of the shape 14 | float64[<=3] dimensions # At no point will dimensions have a length > 3. 15 | 16 | # The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array. 17 | 18 | # For type BOX, the X, Y, and Z dimensions are the length of the corresponding sides of the box. 19 | uint8 BOX_X=0 20 | uint8 BOX_Y=1 21 | uint8 BOX_Z=2 22 | 23 | # For the SPHERE type, only one component is used, and it gives the radius of the sphere. 24 | uint8 SPHERE_RADIUS=0 25 | 26 | # For the CYLINDER and CONE types, the center line is oriented along the Z axis. 27 | # Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component of dimensions gives the 28 | # height of the cylinder (cone). 29 | # The CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the radius of 30 | # the base of the cylinder (cone). 31 | # Cone and cylinder primitives are defined to be circular. The tip of the cone 32 | # is pointing up, along +Z axis. 33 | 34 | uint8 CYLINDER_HEIGHT=0 35 | uint8 CYLINDER_RADIUS=1 36 | 37 | uint8 CONE_HEIGHT=0 38 | uint8 CONE_RADIUS=1 39 | 40 | # For the type PRISM, the center line is oriented along Z axis. 41 | # The PRISM_HEIGHT component of dimensions gives the 42 | # height of the prism. 43 | # The polygon defines the Z axis centered base of the prism. 44 | # The prism is constructed by extruding the base in +Z and -Z 45 | # directions by half of the PRISM_HEIGHT 46 | # Only x and y fields of the points are used in the polygon. 47 | # Points of the polygon are ordered counter-clockwise. 48 | 49 | uint8 PRISM_HEIGHT=0 50 | geometry_msgs/Polygon polygon 51 | -------------------------------------------------------------------------------- /shape_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | shape_msgs 5 | 5.7.0 6 | A package containing some message definitions which describe geometric shapes. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | geometry_msgs 22 | rosidl_default_runtime 23 | 24 | ament_lint_common 25 | 26 | rosidl_interface_packages 27 | 28 | 29 | ament_cmake 30 | 31 | 32 | -------------------------------------------------------------------------------- /std_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package std_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | 8 | 5.6.0 (2025-04-25) 9 | ------------------ 10 | 11 | 5.5.0 (2025-03-20) 12 | ------------------ 13 | 14 | 5.4.2 (2024-11-20) 15 | ------------------ 16 | 17 | 5.4.1 (2024-06-17) 18 | ------------------ 19 | 20 | 5.4.0 (2024-04-26) 21 | ------------------ 22 | * Update quality declaration documents (`#245 `_) 23 | * Contributors: Christophe Bedard 24 | 25 | 5.3.4 (2024-04-16) 26 | ------------------ 27 | 28 | 5.3.3 (2024-04-10) 29 | ------------------ 30 | 31 | 5.3.2 (2024-04-10) 32 | ------------------ 33 | * Clarify the license. (`#241 `_) 34 | In particular, every package in this repository is Apache 2.0 35 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 36 | and LICENSE files down into the individual packages, and 37 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 38 | file (it already had the correct LICENSE file). 39 | * Contributors: Chris Lalancette 40 | 41 | 5.3.1 (2024-03-28) 42 | ------------------ 43 | 44 | 5.3.0 (2024-01-24) 45 | ------------------ 46 | 47 | 5.2.2 (2023-12-26) 48 | ------------------ 49 | 50 | 5.2.1 (2023-11-06) 51 | ------------------ 52 | 53 | 5.2.0 (2023-06-07) 54 | ------------------ 55 | 56 | 5.1.0 (2023-04-27) 57 | ------------------ 58 | 59 | 5.0.0 (2023-04-11) 60 | ------------------ 61 | 62 | 4.7.0 (2023-02-13) 63 | ------------------ 64 | * Update common_interfaces to C++17. (`#215 `_) 65 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 66 | * Contributors: Audrow Nash, Chris Lalancette 67 | 68 | 4.6.1 (2022-11-02) 69 | ------------------ 70 | 71 | 4.6.0 (2022-09-13) 72 | ------------------ 73 | 74 | 4.5.0 (2022-05-19) 75 | ------------------ 76 | 77 | 4.4.0 (2022-04-29) 78 | ------------------ 79 | 80 | 4.3.0 (2022-04-29) 81 | ------------------ 82 | 83 | 4.2.1 (2022-03-31) 84 | ------------------ 85 | 86 | 4.2.0 (2022-03-30) 87 | ------------------ 88 | 89 | 4.1.1 (2022-03-26) 90 | ------------------ 91 | 92 | 4.1.0 (2022-03-01) 93 | ------------------ 94 | * Interface packages should fully on the interface packages that they depend on (`#173 `_) 95 | * Contributors: Grey 96 | 97 | 4.0.0 (2021-12-14) 98 | ------------------ 99 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 100 | * Contributors: Audrow Nash 101 | 102 | 3.0.0 (2021-08-24) 103 | ------------------ 104 | 105 | 2.3.0 (2021-08-11) 106 | ------------------ 107 | 108 | 2.2.3 (2021-04-27) 109 | ------------------ 110 | 111 | 2.2.2 (2021-04-06) 112 | ------------------ 113 | * Change index.ros.org -> docs.ros.org. (`#149 `_) 114 | * updating quality declaration links (re: `ros2/docs.ros2.org#52 `_) (`#145 `_) 115 | Co-authored-by: Simon Honigmann 116 | * Contributors: Chris Lalancette, shonigmann 117 | 118 | 2.2.1 (2021-01-25) 119 | ------------------ 120 | 121 | 2.2.0 (2020-12-10) 122 | ------------------ 123 | * Update QDs to QL 1 (`#135 `_) 124 | * Update package maintainers. (`#132 `_) 125 | * Updated Quality Level to 2 (`#131 `_) 126 | * Contributors: Alejandro Hernández Cordero, Michel Hidalgo, Stephen Brawner 127 | 128 | 2.1.0 (2020-07-21) 129 | ------------------ 130 | 131 | 2.0.2 (2020-07-21) 132 | ------------------ 133 | * Update Quality levels to level 3 (`#124 `_) 134 | * Add Security Vulnerability Policy pointing to REP-2006. (`#120 `_) 135 | * Contributors: Chris Lalancette, brawner 136 | 137 | 2.0.1 (2020-05-26) 138 | ------------------ 139 | * QD Update Version Stability to stable version (`#121 `_) 140 | * Contributors: Alejandro Hernández Cordero 141 | 142 | 1.0.0 (2020-05-20) 143 | ------------------ 144 | * Add deprecation messages to all messages now in example_interfaces (`#116 `_) 145 | * Add current-level quality declarations (`#109 `_) 146 | * Contributors: Tully Foote, brawner 147 | -------------------------------------------------------------------------------- /std_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(std_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(builtin_interfaces REQUIRED) 16 | find_package(rosidl_default_generators REQUIRED) 17 | 18 | set(msg_files 19 | "msg/Bool.msg" 20 | "msg/Byte.msg" 21 | "msg/ByteMultiArray.msg" 22 | "msg/Char.msg" 23 | "msg/ColorRGBA.msg" 24 | "msg/Empty.msg" 25 | "msg/Float32.msg" 26 | "msg/Float32MultiArray.msg" 27 | "msg/Float64.msg" 28 | "msg/Float64MultiArray.msg" 29 | "msg/Header.msg" 30 | "msg/Int16.msg" 31 | "msg/Int16MultiArray.msg" 32 | "msg/Int32.msg" 33 | "msg/Int32MultiArray.msg" 34 | "msg/Int64.msg" 35 | "msg/Int64MultiArray.msg" 36 | "msg/Int8.msg" 37 | "msg/Int8MultiArray.msg" 38 | "msg/MultiArrayDimension.msg" 39 | "msg/MultiArrayLayout.msg" 40 | "msg/String.msg" 41 | "msg/UInt16.msg" 42 | "msg/UInt16MultiArray.msg" 43 | "msg/UInt32.msg" 44 | "msg/UInt32MultiArray.msg" 45 | "msg/UInt64.msg" 46 | "msg/UInt64MultiArray.msg" 47 | "msg/UInt8.msg" 48 | "msg/UInt8MultiArray.msg" 49 | ) 50 | rosidl_generate_interfaces(${PROJECT_NAME} 51 | ${msg_files} 52 | DEPENDENCIES builtin_interfaces 53 | ADD_LINTER_TESTS 54 | ) 55 | 56 | ament_export_dependencies(rosidl_default_runtime) 57 | 58 | ament_package() 59 | -------------------------------------------------------------------------------- /std_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /std_msgs/README.md: -------------------------------------------------------------------------------- 1 | # std_msgs 2 | 3 | `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. 4 | 5 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 6 | 7 | ## Messages (.msg) 8 | * [ColorRGBA](msg/ColorRGBA.msg): A single RGBA value for representing colors. 9 | * [Empty](msg/Empty.msg): Does not hold any information, useful when the sending of a message would provide sufficient information. 10 | * [Header](msg/Header.msg): Standard metadata for higher-level stamped data types used to communicate timestamped data in a particular coordinate frame. 11 | 12 | ### Primitive Types 13 | `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). 14 | 15 | * [Bool](msg/Bool.msg) 16 | * [Byte](msg/Byte.msg) 17 | * [Char](msg/Char.msg) 18 | * [Float32](msg/Float32.msg) 19 | * [Float64](msg/Float64.msg) 20 | * [Int8](msg/Int8.msg) 21 | * [Int16](msg/Int16.msg) 22 | * [Int32](msg/Int32.msg) 23 | * [Int64](msg/Int64.msg) 24 | * [String](msg/String.msg) 25 | * [UInt8](msg/UInt8.msg) 26 | * [UInt16](msg/UInt16.msg) 27 | * [UInt32](msg/UInt32.msg) 28 | * [UInt64](msg/UInt64.msg) 29 | 30 | ### Array Types 31 | `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). 32 | 33 | * [ByteMultiArray](msg/ByteMultiArray.msg) 34 | * [Float32MultiArray](msg/Float32MultiArray.msg) 35 | * [Float64MultiArray](msg/Float64MultiArray.msg) 36 | * [Int8MultiArray](msg/Int8MultiArray.msg) 37 | * [Int16MultiArray](msg/Int16MultiArray.msg) 38 | * [Int32MultiArray](msg/Int32MultiArray.msg) 39 | * [Int64MultiArray](msg/Int64MultiArray.msg) 40 | * [MultiArrayDimension](msg/MultiArrayDimension.msg) 41 | * [MultiArrayLayout](msg/MultiArrayLayout.msg) 42 | * [UInt16MultiArray](msg/UInt16MultiArray.msg) 43 | * [UInt32MultiArray](msg/UInt32MultiArray.msg) 44 | * [UInt64MultiArray](msg/UInt64MultiArray.msg) 45 | * [UInt8MultiArray](msg/UInt8MultiArray.msg) 46 | 47 | ## Quality Declaration 48 | This package claims to be in the **Quality Level 1** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 49 | -------------------------------------------------------------------------------- /std_msgs/msg/Bool.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | bool data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/Byte.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | byte data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/ByteMultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | byte[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/Char.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | char data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/ColorRGBA.msg: -------------------------------------------------------------------------------- 1 | float32 r 2 | float32 g 3 | float32 b 4 | float32 a 5 | -------------------------------------------------------------------------------- /std_msgs/msg/Empty.msg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros2/common_interfaces/fa74e954260279e97182f82776dc086328502b67/std_msgs/msg/Empty.msg -------------------------------------------------------------------------------- /std_msgs/msg/Float32.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | float32 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/Float32MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | float32[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/Float64.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | float64 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/Float64MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | float64[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/Header.msg: -------------------------------------------------------------------------------- 1 | # Standard metadata for higher-level stamped data types. 2 | # This is generally used to communicate timestamped data 3 | # in a particular coordinate frame. 4 | 5 | # Two-integer timestamp that is expressed as seconds and nanoseconds. 6 | builtin_interfaces/Time stamp 7 | 8 | # Transform frame with which this data is associated. 9 | string frame_id 10 | -------------------------------------------------------------------------------- /std_msgs/msg/Int16.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | int16 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/Int16MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | int16[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/Int32.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | int32 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/Int32MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | int32[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/Int64.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | int64 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/Int64MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | int64[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/Int8.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | int8 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/Int8MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | int8[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/MultiArrayDimension.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | string label # label of given dimension 7 | uint32 size # size of given dimension (in type units) 8 | uint32 stride # stride of given dimension 9 | -------------------------------------------------------------------------------- /std_msgs/msg/MultiArrayLayout.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # The multiarray declares a generic multi-dimensional array of a 7 | # particular data type. Dimensions are ordered from outer most 8 | # to inner most. 9 | # 10 | # Accessors should ALWAYS be written in terms of dimension stride 11 | # and specified outer-most dimension first. 12 | # 13 | # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] 14 | # 15 | # A standard, 3-channel 640x480 image with interleaved color channels 16 | # would be specified as: 17 | # 18 | # dim[0].label = "height" 19 | # dim[0].size = 480 20 | # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) 21 | # dim[1].label = "width" 22 | # dim[1].size = 640 23 | # dim[1].stride = 3*640 = 1920 24 | # dim[2].label = "channel" 25 | # dim[2].size = 3 26 | # dim[2].stride = 3 27 | # 28 | # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. 29 | 30 | MultiArrayDimension[] dim # Array of dimension properties 31 | uint32 data_offset # padding bytes at front of data 32 | -------------------------------------------------------------------------------- /std_msgs/msg/String.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | string data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt16.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | uint16 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt16MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | uint16[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt32.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | uint32 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt32MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | uint32[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt64.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | uint64 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt64MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | uint64[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt8.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | uint8 data 7 | -------------------------------------------------------------------------------- /std_msgs/msg/UInt8MultiArray.msg: -------------------------------------------------------------------------------- 1 | # This was originally provided as an example message. 2 | # It is deprecated as of Foxy 3 | # It is recommended to create your own semantically meaningful message. 4 | # However if you would like to continue using this please use the equivalent in example_msgs. 5 | 6 | # Please look at the MultiArrayLayout message definition for 7 | # documentation on all multiarrays. 8 | 9 | MultiArrayLayout layout # specification of data layout 10 | uint8[] data # array of data 11 | -------------------------------------------------------------------------------- /std_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | std_msgs 5 | 5.7.0 6 | A package containing some standard message definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Dirk Thomas 13 | Geoffrey Biggs 14 | Michael Carroll 15 | Michel Hidalgo 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | builtin_interfaces 22 | rosidl_default_runtime 23 | 24 | ament_lint_common 25 | 26 | rosidl_interface_packages 27 | 28 | 29 | ament_cmake 30 | 31 | 32 | -------------------------------------------------------------------------------- /std_srvs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package std_srvs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | 8 | 5.6.0 (2025-04-25) 9 | ------------------ 10 | 11 | 5.5.0 (2025-03-20) 12 | ------------------ 13 | 14 | 5.4.2 (2024-11-20) 15 | ------------------ 16 | 17 | 5.4.1 (2024-06-17) 18 | ------------------ 19 | 20 | 5.4.0 (2024-04-26) 21 | ------------------ 22 | * Update quality declaration documents (`#245 `_) 23 | * Contributors: Christophe Bedard 24 | 25 | 5.3.4 (2024-04-16) 26 | ------------------ 27 | 28 | 5.3.3 (2024-04-10) 29 | ------------------ 30 | 31 | 5.3.2 (2024-04-10) 32 | ------------------ 33 | * Clarify the license. (`#241 `_) 34 | In particular, every package in this repository is Apache 2.0 35 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 36 | and LICENSE files down into the individual packages, and 37 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 38 | file (it already had the correct LICENSE file). 39 | * Contributors: Chris Lalancette 40 | 41 | 5.3.1 (2024-03-28) 42 | ------------------ 43 | 44 | 5.3.0 (2024-01-24) 45 | ------------------ 46 | 47 | 5.2.2 (2023-12-26) 48 | ------------------ 49 | 50 | 5.2.1 (2023-11-06) 51 | ------------------ 52 | 53 | 5.2.0 (2023-06-07) 54 | ------------------ 55 | 56 | 5.1.0 (2023-04-27) 57 | ------------------ 58 | 59 | 5.0.0 (2023-04-11) 60 | ------------------ 61 | 62 | 4.7.0 (2023-02-13) 63 | ------------------ 64 | * Update common_interfaces to C++17. (`#215 `_) 65 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 66 | * Contributors: Audrow Nash, Chris Lalancette 67 | 68 | 4.6.1 (2022-11-02) 69 | ------------------ 70 | 71 | 4.6.0 (2022-09-13) 72 | ------------------ 73 | 74 | 4.5.0 (2022-05-19) 75 | ------------------ 76 | 77 | 4.4.0 (2022-04-29) 78 | ------------------ 79 | 80 | 4.3.0 (2022-04-29) 81 | ------------------ 82 | 83 | 4.2.1 (2022-03-31) 84 | ------------------ 85 | 86 | 4.2.0 (2022-03-30) 87 | ------------------ 88 | 89 | 4.1.1 (2022-03-26) 90 | ------------------ 91 | 92 | 4.1.0 (2022-03-01) 93 | ------------------ 94 | 95 | 4.0.0 (2021-12-14) 96 | ------------------ 97 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 98 | * Contributors: Audrow Nash 99 | 100 | 3.0.0 (2021-08-24) 101 | ------------------ 102 | 103 | 2.3.0 (2021-08-11) 104 | ------------------ 105 | 106 | 2.2.3 (2021-04-27) 107 | ------------------ 108 | 109 | 2.2.2 (2021-04-06) 110 | ------------------ 111 | * Change index.ros.org -> docs.ros.org. (`#149 `_) 112 | * updating quality declaration links (re: `ros2/docs.ros2.org#52 `_) (`#145 `_) 113 | * Contributors: Chris Lalancette, shonigmann 114 | 115 | 2.2.1 (2021-01-25) 116 | ------------------ 117 | 118 | 2.2.0 (2020-12-10) 119 | ------------------ 120 | * Update QDs to QL 1 (`#135 `_) 121 | * Update package maintainers. (`#132 `_) 122 | * Updated Quality Level to 2 (`#131 `_) 123 | * Contributors: Alejandro Hernández Cordero, Michel Hidalgo, Stephen Brawner 124 | 125 | 2.1.0 (2020-07-21) 126 | ------------------ 127 | 128 | 2.0.2 (2020-07-21) 129 | ------------------ 130 | * Update Quality levels to level 3 (`#124 `_) 131 | * Add Security Vulnerability Policy pointing to REP-2006. (`#120 `_) 132 | * Contributors: Chris Lalancette, brawner 133 | 134 | 2.0.1 (2020-05-26) 135 | ------------------ 136 | * QD Update Version Stability to stable version (`#121 `_) 137 | * Contributors: Alejandro Hernández Cordero 138 | 139 | 1.0.0 (2020-05-20) 140 | ------------------ 141 | * Add current-level quality declarations (`#109 `_) 142 | * Contributors: brawner 143 | -------------------------------------------------------------------------------- /std_srvs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(std_srvs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(rosidl_default_generators REQUIRED) 16 | 17 | set(srv_files 18 | "srv/Empty.srv" 19 | "srv/SetBool.srv" 20 | "srv/Trigger.srv" 21 | ) 22 | rosidl_generate_interfaces(${PROJECT_NAME} 23 | ${srv_files} 24 | ADD_LINTER_TESTS 25 | ) 26 | 27 | ament_export_dependencies(rosidl_default_runtime) 28 | 29 | ament_package() 30 | -------------------------------------------------------------------------------- /std_srvs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /std_srvs/README.md: -------------------------------------------------------------------------------- 1 | # std_srvs 2 | 3 | This package provides several service definitions for standard but simple ROS services. 4 | 5 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 6 | 7 | ## Services (.srv) 8 | * [Empty.srv](srv/Empty.srv): A service containing an empty request and response. 9 | * [SetBool.srv](srv/SetBool.srv): Service to set a boolean state to true or false, for enabling or disabling hardware for example. 10 | * [Trigger.srv](srv/Trigger.srv): Service with an empty request header used for triggering the activation or start of a service. 11 | 12 | 13 | ## Quality Declaration 14 | This package claims to be in the **Quality Level 1** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 15 | -------------------------------------------------------------------------------- /std_srvs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | std_srvs 5 | 5.7.0 6 | A package containing some standard service definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Dirk Thomas 13 | Geoffrey Biggs 14 | Michael Carroll 15 | Michel Hidalgo 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | rosidl_default_runtime 22 | 23 | ament_lint_common 24 | 25 | rosidl_interface_packages 26 | 27 | 28 | ament_cmake 29 | 30 | 31 | -------------------------------------------------------------------------------- /std_srvs/srv/Empty.srv: -------------------------------------------------------------------------------- 1 | --- 2 | -------------------------------------------------------------------------------- /std_srvs/srv/SetBool.srv: -------------------------------------------------------------------------------- 1 | bool data # e.g. for hardware enabling / disabling 2 | --- 3 | bool success # indicate successful run of triggered service 4 | string message # informational, e.g. for error messages 5 | -------------------------------------------------------------------------------- /std_srvs/srv/Trigger.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool success # indicate successful run of triggered service 3 | string message # informational, e.g. for error messages 4 | -------------------------------------------------------------------------------- /stereo_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package stereo_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | 8 | 5.6.0 (2025-04-25) 9 | ------------------ 10 | 11 | 5.5.0 (2025-03-20) 12 | ------------------ 13 | 14 | 5.4.2 (2024-11-20) 15 | ------------------ 16 | 17 | 5.4.1 (2024-06-17) 18 | ------------------ 19 | 20 | 5.4.0 (2024-04-26) 21 | ------------------ 22 | * Update quality declaration documents (`#245 `_) 23 | * Contributors: Christophe Bedard 24 | 25 | 5.3.4 (2024-04-16) 26 | ------------------ 27 | 28 | 5.3.3 (2024-04-10) 29 | ------------------ 30 | 31 | 5.3.2 (2024-04-10) 32 | ------------------ 33 | * Clarify the license. (`#241 `_) 34 | In particular, every package in this repository is Apache 2.0 35 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 36 | and LICENSE files down into the individual packages, and 37 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 38 | file (it already had the correct LICENSE file). 39 | * Contributors: Chris Lalancette 40 | 41 | 5.3.1 (2024-03-28) 42 | ------------------ 43 | 44 | 5.3.0 (2024-01-24) 45 | ------------------ 46 | 47 | 5.2.2 (2023-12-26) 48 | ------------------ 49 | 50 | 5.2.1 (2023-11-06) 51 | ------------------ 52 | 53 | 5.2.0 (2023-06-07) 54 | ------------------ 55 | 56 | 5.1.0 (2023-04-27) 57 | ------------------ 58 | 59 | 5.0.0 (2023-04-11) 60 | ------------------ 61 | 62 | 4.7.0 (2023-02-13) 63 | ------------------ 64 | * Update common_interfaces to C++17. (`#215 `_) 65 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 66 | * Contributors: Audrow Nash, Chris Lalancette 67 | 68 | 4.6.1 (2022-11-02) 69 | ------------------ 70 | 71 | 4.6.0 (2022-09-13) 72 | ------------------ 73 | 74 | 4.5.0 (2022-05-19) 75 | ------------------ 76 | 77 | 4.4.0 (2022-04-29) 78 | ------------------ 79 | 80 | 4.3.0 (2022-04-29) 81 | ------------------ 82 | 83 | 4.2.1 (2022-03-31) 84 | ------------------ 85 | 86 | 4.2.0 (2022-03-30) 87 | ------------------ 88 | 89 | 4.1.1 (2022-03-26) 90 | ------------------ 91 | 92 | 4.1.0 (2022-03-01) 93 | ------------------ 94 | * Interface packages should fully on the interface packages that they depend on (`#173 `_) 95 | * Contributors: Grey 96 | 97 | 4.0.0 (2021-12-14) 98 | ------------------ 99 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 100 | * Contributors: Audrow Nash 101 | 102 | 3.0.0 (2021-08-24) 103 | ------------------ 104 | 105 | 2.3.0 (2021-08-11) 106 | ------------------ 107 | 108 | 2.2.3 (2021-04-27) 109 | ------------------ 110 | 111 | 2.2.2 (2021-04-06) 112 | ------------------ 113 | * Change index.ros.org -> docs.ros.org. (`#149 `_) 114 | * updating quality declaration links (re: `ros2/docs.ros2.org#52 `_) (`#145 `_) 115 | * Contributors: Chris Lalancette, shonigmann 116 | 117 | 2.2.1 (2021-01-25) 118 | ------------------ 119 | 120 | 2.2.0 (2020-12-10) 121 | ------------------ 122 | * Update QDs to QL 1 (`#135 `_) 123 | * Update package maintainers. (`#132 `_) 124 | * Updated Quality Level to 2 (`#131 `_) 125 | * Contributors: Alejandro Hernández Cordero, Michel Hidalgo, Stephen Brawner 126 | 127 | 2.1.0 (2020-07-21) 128 | ------------------ 129 | 130 | 2.0.2 (2020-07-21) 131 | ------------------ 132 | * Update Quality levels to level 3 (`#124 `_) 133 | * Add Security Vulnerability Policy pointing to REP-2006. (`#120 `_) 134 | * Contributors: Chris Lalancette, brawner 135 | 136 | 2.0.1 (2020-05-26) 137 | ------------------ 138 | * QD Update Version Stability to stable version (`#121 `_) 139 | * Contributors: Alejandro Hernández Cordero 140 | 141 | 1.0.0 (2020-05-20) 142 | ------------------ 143 | * Add current-level quality declarations (`#109 `_) 144 | * Contributors: brawner 145 | -------------------------------------------------------------------------------- /stereo_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(stereo_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(rosidl_default_generators REQUIRED) 16 | find_package(sensor_msgs REQUIRED) 17 | find_package(std_msgs REQUIRED) 18 | 19 | set(msg_files 20 | "msg/DisparityImage.msg" 21 | ) 22 | rosidl_generate_interfaces(${PROJECT_NAME} 23 | ${msg_files} 24 | DEPENDENCIES sensor_msgs std_msgs 25 | ADD_LINTER_TESTS 26 | ) 27 | 28 | ament_export_dependencies(rosidl_default_runtime) 29 | 30 | ament_package() 31 | -------------------------------------------------------------------------------- /stereo_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /stereo_msgs/README.md: -------------------------------------------------------------------------------- 1 | # stereo_msgs 2 | 3 | This package provides a message for describing a disparity image. 4 | 5 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 6 | 7 | ## Messages (.msg) 8 | * [DisparityImage](msg/DisparityImage.msg): A floating point disparity image with metadata. 9 | 10 | ## Quality Declaration 11 | This package claims to be in the **Quality Level 1** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 12 | -------------------------------------------------------------------------------- /stereo_msgs/msg/DisparityImage.msg: -------------------------------------------------------------------------------- 1 | # Separate header for compatibility with current TimeSynchronizer. 2 | # Likely to be removed in a later release, use image.header instead. 3 | std_msgs/Header header 4 | 5 | # Floating point disparity image. The disparities are pre-adjusted for any 6 | # x-offset between the principal points of the two cameras (in the case 7 | # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) 8 | sensor_msgs/Image image 9 | 10 | # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. 11 | float32 f # Focal length, pixels 12 | float32 t # Baseline, world units 13 | 14 | # Subwindow of (potentially) valid disparity values. 15 | sensor_msgs/RegionOfInterest valid_window 16 | 17 | # The range of disparities searched. 18 | # In the disparity image, any disparity less than min_disparity is invalid. 19 | # The disparity search range defines the horopter, or 3D volume that the 20 | # stereo algorithm can "see". Points with Z outside of: 21 | # Z_min = fT / max_disparity 22 | # Z_max = fT / min_disparity 23 | # could not be found. 24 | float32 min_disparity 25 | float32 max_disparity 26 | 27 | # Smallest allowed disparity increment. The smallest achievable depth range 28 | # resolution is delta_Z = (Z^2/fT)*delta_d. 29 | float32 delta_d 30 | -------------------------------------------------------------------------------- /stereo_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | stereo_msgs 5 | 5.7.0 6 | A package containing some stereo camera related message definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | sensor_msgs 22 | std_msgs 23 | 24 | rosidl_default_runtime 25 | 26 | ament_lint_common 27 | 28 | rosidl_interface_packages 29 | 30 | 31 | ament_cmake 32 | 33 | 34 | -------------------------------------------------------------------------------- /trajectory_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package trajectory_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 5.7.0 (2025-05-19) 6 | ------------------ 7 | 8 | 5.6.0 (2025-04-25) 9 | ------------------ 10 | 11 | 5.5.0 (2025-03-20) 12 | ------------------ 13 | 14 | 5.4.2 (2024-11-20) 15 | ------------------ 16 | 17 | 5.4.1 (2024-06-17) 18 | ------------------ 19 | 20 | 5.4.0 (2024-04-26) 21 | ------------------ 22 | * Update quality declaration documents (`#245 `_) 23 | * Contributors: Christophe Bedard 24 | 25 | 5.3.4 (2024-04-16) 26 | ------------------ 27 | 28 | 5.3.3 (2024-04-10) 29 | ------------------ 30 | 31 | 5.3.2 (2024-04-10) 32 | ------------------ 33 | * Clarify the license. (`#241 `_) 34 | In particular, every package in this repository is Apache 2.0 35 | licensed except for sensor_msgs_py. So move the CONTRIBUTING.md 36 | and LICENSE files down into the individual packages, and 37 | make sure that sensor_msgs_py has the correct CONTRIBUTING.md 38 | file (it already had the correct LICENSE file). 39 | * Contributors: Chris Lalancette 40 | 41 | 5.3.1 (2024-03-28) 42 | ------------------ 43 | 44 | 5.3.0 (2024-01-24) 45 | ------------------ 46 | 47 | 5.2.2 (2023-12-26) 48 | ------------------ 49 | 50 | 5.2.1 (2023-11-06) 51 | ------------------ 52 | 53 | 5.2.0 (2023-06-07) 54 | ------------------ 55 | 56 | 5.1.0 (2023-04-27) 57 | ------------------ 58 | 59 | 5.0.0 (2023-04-11) 60 | ------------------ 61 | 62 | 4.7.0 (2023-02-13) 63 | ------------------ 64 | * Update common_interfaces to C++17. (`#215 `_) 65 | * [rolling] Update maintainers - 2022-11-07 (`#210 `_) 66 | * Contributors: Audrow Nash, Chris Lalancette 67 | 68 | 4.6.1 (2022-11-02) 69 | ------------------ 70 | 71 | 4.6.0 (2022-09-13) 72 | ------------------ 73 | 74 | 4.5.0 (2022-05-19) 75 | ------------------ 76 | 77 | 4.4.0 (2022-04-29) 78 | ------------------ 79 | 80 | 4.3.0 (2022-04-29) 81 | ------------------ 82 | 83 | 4.2.1 (2022-03-31) 84 | ------------------ 85 | 86 | 4.2.0 (2022-03-30) 87 | ------------------ 88 | 89 | 4.1.1 (2022-03-26) 90 | ------------------ 91 | 92 | 4.1.0 (2022-03-01) 93 | ------------------ 94 | * Interface packages should fully on the interface packages that they depend on (`#173 `_) 95 | * Contributors: Grey 96 | 97 | 4.0.0 (2021-12-14) 98 | ------------------ 99 | * Update maintainers to Geoffrey Biggs and Tully Foote (`#163 `_) 100 | * Contributors: Audrow Nash 101 | 102 | 3.0.0 (2021-08-24) 103 | ------------------ 104 | 105 | 2.3.0 (2021-08-11) 106 | ------------------ 107 | 108 | 2.2.3 (2021-04-27) 109 | ------------------ 110 | 111 | 2.2.2 (2021-04-06) 112 | ------------------ 113 | * Change index.ros.org -> docs.ros.org. (`#149 `_) 114 | * updating quality declaration links (re: `ros2/docs.ros2.org#52 `_) (`#145 `_) 115 | * Contributors: Chris Lalancette, shonigmann 116 | 117 | 2.2.1 (2021-01-25) 118 | ------------------ 119 | 120 | 2.2.0 (2020-12-10) 121 | ------------------ 122 | * Update QDs to QL 1 (`#135 `_) 123 | * Update package maintainers. (`#132 `_) 124 | * Updated Quality Level to 2 (`#131 `_) 125 | * Contributors: Alejandro Hernández Cordero, Michel Hidalgo, Stephen Brawner 126 | 127 | 2.1.0 (2020-07-21) 128 | ------------------ 129 | 130 | 2.0.2 (2020-07-21) 131 | ------------------ 132 | * Update Quality levels to level 3 (`#124 `_) 133 | * Finish up API documentation (`#123 `_) 134 | * Add Security Vulnerability Policy pointing to REP-2006. (`#120 `_) 135 | * Contributors: Chris Lalancette, brawner 136 | 137 | 2.0.1 (2020-05-26) 138 | ------------------ 139 | * QD Update Version Stability to stable version (`#121 `_) 140 | * Contributors: Alejandro Hernández Cordero 141 | 142 | 1.0.0 (2020-05-20) 143 | ------------------ 144 | * Add current-level quality declarations (`#109 `_) 145 | * Contributors: brawner 146 | -------------------------------------------------------------------------------- /trajectory_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(trajectory_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(builtin_interfaces REQUIRED) 16 | find_package(geometry_msgs REQUIRED) 17 | find_package(rosidl_default_generators REQUIRED) 18 | find_package(std_msgs REQUIRED) 19 | 20 | set(msg_files 21 | "msg/JointTrajectory.msg" 22 | "msg/JointTrajectoryPoint.msg" 23 | "msg/MultiDOFJointTrajectory.msg" 24 | "msg/MultiDOFJointTrajectoryPoint.msg" 25 | ) 26 | rosidl_generate_interfaces(${PROJECT_NAME} 27 | ${msg_files} 28 | DEPENDENCIES builtin_interfaces geometry_msgs std_msgs 29 | ADD_LINTER_TESTS 30 | ) 31 | 32 | ament_export_dependencies(rosidl_default_runtime) 33 | 34 | ament_package() 35 | -------------------------------------------------------------------------------- /trajectory_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /trajectory_msgs/README.md: -------------------------------------------------------------------------------- 1 | # trajectory_msgs 2 | 3 | This package provides several messages for defining robotic joint trajectories. 4 | 5 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 6 | 7 | ## Messages (.msg) 8 | * [JointTrajectory](msg/JointTrajectory.msg): A coordinated sequence of joint configurations to be reached at prescribed time points. 9 | * [JointTrajectoryPoint](msg/JointTrajectoryPoint.msg): A single configuration for multiple joints in a JointTrajectory. 10 | * [MultiDOFJointTrajectory](msg/MultiDOFJointTrajectory.msg): A representation of a multi-dof joint trajectory (each point is a transformation). 11 | * [MultiDOFJointTrajectoryPoint](msg/MultiDOFJointTrajectoryPoint.msg): A single configuration for multiple joints in a MultiDOFJointTrajectory. 12 | 13 | ## Quality Declaration 14 | This package claims to be in the **Quality Level 2** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 15 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/JointTrajectory.msg: -------------------------------------------------------------------------------- 1 | # The header is used to specify the coordinate frame and the reference time for 2 | # the trajectory durations 3 | std_msgs/Header header 4 | 5 | # The names of the active joints in each trajectory point. These names are 6 | # ordered and must correspond to the values in each trajectory point. 7 | string[] joint_names 8 | 9 | # Array of trajectory points, which describe the positions, velocities, 10 | # accelerations and/or efforts of the joints at each time point. 11 | JointTrajectoryPoint[] points 12 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/JointTrajectoryPoint.msg: -------------------------------------------------------------------------------- 1 | # Each trajectory point specifies either positions[, velocities[, accelerations]] 2 | # or positions[, effort] for the trajectory to be executed. 3 | # All specified values are in the same order as the joint names in JointTrajectory.msg. 4 | 5 | # Single DOF joint positions for each joint relative to their "0" position. 6 | # The units depend on the specific joint type: radians for revolute or 7 | # continuous joints, and meters for prismatic joints. 8 | float64[] positions 9 | 10 | # The rate of change in position of each joint. Units are joint type dependent. 11 | # Radians/second for revolute or continuous joints, and meters/second for 12 | # prismatic joints. 13 | float64[] velocities 14 | 15 | # Rate of change in velocity of each joint. Units are joint type dependent. 16 | # Radians/second^2 for revolute or continuous joints, and meters/second^2 for 17 | # prismatic joints. 18 | float64[] accelerations 19 | 20 | # The torque or the force to be applied at each joint. For revolute/continuous 21 | # joints effort denotes a torque in newton-meters. For prismatic joints, effort 22 | # denotes a force in newtons. 23 | float64[] effort 24 | 25 | # Desired time from the trajectory start to arrive at this trajectory point. 26 | builtin_interfaces/Duration time_from_start 27 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/MultiDOFJointTrajectory.msg: -------------------------------------------------------------------------------- 1 | # The header is used to specify the coordinate frame and the reference time for the trajectory durations 2 | std_msgs/Header header 3 | 4 | # A representation of a multi-dof joint trajectory (each point is a transformation) 5 | # Each point along the trajectory will include an array of positions/velocities/accelerations 6 | # that has the same length as the array of joint names, and has the same order of joints as 7 | # the joint names array. 8 | 9 | string[] joint_names 10 | MultiDOFJointTrajectoryPoint[] points 11 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.msg: -------------------------------------------------------------------------------- 1 | # Each multi-dof joint can specify a transform (up to 6 DOF). 2 | geometry_msgs/Transform[] transforms 3 | 4 | # There can be a velocity specified for the origin of the joint. 5 | geometry_msgs/Twist[] velocities 6 | 7 | # There can be an acceleration specified for the origin of the joint. 8 | geometry_msgs/Twist[] accelerations 9 | 10 | # Desired time from the trajectory start to arrive at this trajectory point. 11 | builtin_interfaces/Duration time_from_start 12 | -------------------------------------------------------------------------------- /trajectory_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | trajectory_msgs 5 | 5.7.0 6 | A package containing some robot trajectory message definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | builtin_interfaces 22 | geometry_msgs 23 | std_msgs 24 | 25 | rosidl_default_runtime 26 | 27 | ament_lint_common 28 | 29 | rosidl_interface_packages 30 | 31 | 32 | ament_cmake 33 | 34 | 35 | -------------------------------------------------------------------------------- /visualization_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.5) 2 | 3 | project(visualization_msgs) 4 | 5 | # Default to C++17 6 | if(NOT CMAKE_CXX_STANDARD) 7 | set(CMAKE_CXX_STANDARD 17) 8 | set(CMAKE_CXX_STANDARD_REQUIRED ON) 9 | endif() 10 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") 11 | add_compile_options(-Wall -Wextra -Wpedantic) 12 | endif() 13 | 14 | find_package(ament_cmake REQUIRED) 15 | find_package(builtin_interfaces REQUIRED) 16 | find_package(geometry_msgs REQUIRED) 17 | find_package(rosidl_default_generators REQUIRED) 18 | find_package(sensor_msgs REQUIRED) 19 | find_package(std_msgs REQUIRED) 20 | 21 | set(msg_files 22 | "msg/ImageMarker.msg" 23 | "msg/InteractiveMarker.msg" 24 | "msg/InteractiveMarkerControl.msg" 25 | "msg/InteractiveMarkerFeedback.msg" 26 | "msg/InteractiveMarkerInit.msg" 27 | "msg/InteractiveMarkerPose.msg" 28 | "msg/InteractiveMarkerUpdate.msg" 29 | "msg/Marker.msg" 30 | "msg/MarkerArray.msg" 31 | "msg/MenuEntry.msg" 32 | "msg/MeshFile.msg" 33 | "msg/UVCoordinate.msg" 34 | ) 35 | set(srv_files 36 | "srv/GetInteractiveMarkers.srv" 37 | ) 38 | 39 | rosidl_generate_interfaces(${PROJECT_NAME} 40 | ${msg_files} 41 | ${srv_files} 42 | DEPENDENCIES builtin_interfaces geometry_msgs sensor_msgs std_msgs 43 | ADD_LINTER_TESTS 44 | ) 45 | 46 | ament_export_dependencies(rosidl_default_runtime) 47 | 48 | ament_package() 49 | -------------------------------------------------------------------------------- /visualization_msgs/CONTRIBUTING.md: -------------------------------------------------------------------------------- 1 | Any contribution that you make to this repository will 2 | be under the Apache 2 License, as dictated by that 3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html): 4 | 5 | ~~~ 6 | 5. Submission of Contributions. Unless You explicitly state otherwise, 7 | any Contribution intentionally submitted for inclusion in the Work 8 | by You to the Licensor shall be under the terms and conditions of 9 | this License, without any additional terms or conditions. 10 | Notwithstanding the above, nothing herein shall supersede or modify 11 | the terms of any separate license agreement you may have executed 12 | with Licensor regarding such Contributions. 13 | ~~~ 14 | 15 | Contributors must sign-off each commit by adding a `Signed-off-by: ...` 16 | line to commit messages to certify that they have the right to submit 17 | the code they are contributing to the project according to the 18 | [Developer Certificate of Origin (DCO)](https://developercertificate.org/). 19 | 20 | 21 | ## Contributing new messages and or packages 22 | 23 | To be accepted into `common_interfaces` a package needs to have been API reviewed and be in active use in a non trivial portion of the ROS ecosystem. 24 | It's really supposed to represent messages which are commonly used. 25 | 26 | On the way to becoming a member of `common_interfaces` please release a message-only package and make it available to the community. 27 | Once it has matured, been reviewed, tested, and possibly iterated upon by early adopters, then it can be promoted to be a member of the `common_interfaces` metapackage. 28 | -------------------------------------------------------------------------------- /visualization_msgs/README.md: -------------------------------------------------------------------------------- 1 | # visualization_msgs 2 | 3 | This package provides messages for visualizing 3D information in ROS GUI programs, particularly RViz. 4 | 5 | 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. 6 | 7 | For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros.org/en/rolling/Concepts/About-ROS-Interfaces.html). 8 | 9 | ## Messages (.msg) 10 | * [ImageMarker](msg/ImageMarker.msg): A marker to overlay on displayed images. 11 | * [InteractiveMarker](msg/InteractiveMarker.msg): A user interaction marker for manipulating objects in 3-dimensional space in GUI programs, like RViz. 12 | * [InteractiveMarkerControl](msg/InteractiveMarkerControl.msg): Represents a control that is to be displayed together with an interactive marker. 13 | * [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. 14 | * [InteractiveMarkerInit](msg/InteractiveMarkerInit.msg): Used for sending initial interactive marker descriptions. 15 | * [InteractiveMarkerPose](msg/InteractiveMarkerPose.msg): The pose of the interactive marker. 16 | * [InteractiveMarkerUpdate](msg/InteractiveMarkerUpdate.msg): The top-level message for sending data from the interactive marker server to the client (i.e. rviz). 17 | * [Marker](msg/Marker.msg): A non-interactive marker for displaying annotations in 3-dimensional space. 18 | * [MarkerArray](msg/MarkerArray.msg): An array of markers. 19 | * [MenuEntry](msg/MenuEntry.msg): Used to describe the menu/submenu/subsubmenu/etc tree. 20 | 21 | ## Services (.srv) 22 | * [GetInteractiveMarkers.srv](srv/GetInteractiveMarkers.srv): Get the currently available interactive markers. 23 | 24 | ## Quality Declaration 25 | This package claims to be in the **Quality Level 2** category, see the [Quality Declaration](QUALITY_DECLARATION.md) for more details. 26 | -------------------------------------------------------------------------------- /visualization_msgs/msg/ImageMarker.msg: -------------------------------------------------------------------------------- 1 | int32 CIRCLE=0 2 | int32 LINE_STRIP=1 3 | int32 LINE_LIST=2 4 | int32 POLYGON=3 5 | int32 POINTS=4 6 | 7 | int32 ADD=0 8 | int32 REMOVE=1 9 | 10 | std_msgs/Header header 11 | # Namespace which is used with the id to form a unique id. 12 | string ns 13 | # Unique id within the namespace. 14 | int32 id 15 | # One of the above types, e.g. CIRCLE, LINE_STRIP, etc. 16 | int32 type 17 | # Either ADD or REMOVE. 18 | int32 action 19 | # Two-dimensional coordinate position, in pixel-coordinates. 20 | geometry_msgs/Point position 21 | # The scale of the object, e.g. the diameter for a CIRCLE. 22 | float32 scale 23 | # The outline color of the marker. 24 | std_msgs/ColorRGBA outline_color 25 | # Whether or not to fill in the shape with color. 26 | uint8 filled 27 | # Fill color; in the range: [0.0-1.0] 28 | std_msgs/ColorRGBA fill_color 29 | # How long the object should last before being automatically deleted. 30 | # 0 indicates forever. 31 | builtin_interfaces/Duration lifetime 32 | 33 | # Coordinates in 2D in pixel coords. Used for LINE_STRIP, LINE_LIST, POINTS, etc. 34 | geometry_msgs/Point[] points 35 | # The color for each line, point, etc. in the points field. 36 | std_msgs/ColorRGBA[] outline_colors 37 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarker.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | # If header.time is set to 0, the marker will be retransformed into 3 | # its frame on each timestep. You will receive the pose feedback 4 | # in the same frame. 5 | # Otherwise, you might receive feedback in a different frame. 6 | # For rviz, this will be the current 'fixed frame' set by the user. 7 | std_msgs/Header header 8 | 9 | # Initial pose. Also, defines the pivot point for rotations. 10 | geometry_msgs/Pose pose 11 | 12 | # Identifying string. Must be globally unique in 13 | # the topic that this message is sent through. 14 | string name 15 | 16 | # Short description (< 40 characters). 17 | string description 18 | 19 | # Scale to be used for default controls (default=1). 20 | float32 scale 21 | 22 | # All menu and submenu entries associated with this marker. 23 | MenuEntry[] menu_entries 24 | 25 | # List of controls displayed for this marker. 26 | InteractiveMarkerControl[] controls 27 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerControl.msg: -------------------------------------------------------------------------------- 1 | # Represents a control that is to be displayed together with an interactive marker 2 | 3 | # Identifying string for this control. 4 | # You need to assign a unique value to this to receive feedback from the GUI 5 | # on what actions the user performs on this control (e.g. a button click). 6 | string name 7 | 8 | 9 | # Defines the local coordinate frame (relative to the pose of the parent 10 | # interactive marker) in which is being rotated and translated. 11 | # Default: Identity 12 | geometry_msgs/Quaternion orientation 13 | 14 | 15 | # Orientation mode: controls how orientation changes. 16 | # INHERIT: Follow orientation of interactive marker 17 | # FIXED: Keep orientation fixed at initial state 18 | # VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). 19 | uint8 INHERIT = 0 20 | uint8 FIXED = 1 21 | uint8 VIEW_FACING = 2 22 | 23 | uint8 orientation_mode 24 | 25 | # Interaction mode for this control 26 | # 27 | # NONE: This control is only meant for visualization; no context menu. 28 | # MENU: Like NONE, but right-click menu is active. 29 | # BUTTON: Element can be left-clicked. 30 | # MOVE_AXIS: Translate along local x-axis. 31 | # MOVE_PLANE: Translate in local y-z plane. 32 | # ROTATE_AXIS: Rotate around local x-axis. 33 | # MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. 34 | uint8 NONE = 0 35 | uint8 MENU = 1 36 | uint8 BUTTON = 2 37 | uint8 MOVE_AXIS = 3 38 | uint8 MOVE_PLANE = 4 39 | uint8 ROTATE_AXIS = 5 40 | uint8 MOVE_ROTATE = 6 41 | # "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. 42 | # MOVE_3D: Translate freely in 3D space. 43 | # ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. 44 | # MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. 45 | uint8 MOVE_3D = 7 46 | uint8 ROTATE_3D = 8 47 | uint8 MOVE_ROTATE_3D = 9 48 | 49 | uint8 interaction_mode 50 | 51 | 52 | # If true, the contained markers will also be visible 53 | # when the gui is not in interactive mode. 54 | bool always_visible 55 | 56 | 57 | # Markers to be displayed as custom visual representation. 58 | # Leave this empty to use the default control handles. 59 | # 60 | # Note: 61 | # - The markers can be defined in an arbitrary coordinate frame, 62 | # but will be transformed into the local frame of the interactive marker. 63 | # - If the header of a marker is empty, its pose will be interpreted as 64 | # relative to the pose of the parent interactive marker. 65 | Marker[] markers 66 | 67 | 68 | # In VIEW_FACING mode, set this to true if you don't want the markers 69 | # to be aligned with the camera view point. The markers will show up 70 | # as in INHERIT mode. 71 | bool independent_marker_orientation 72 | 73 | 74 | # Short description (< 40 characters) of what this control does, 75 | # e.g. "Move the robot". 76 | # Default: A generic description based on the interaction mode 77 | string description 78 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerFeedback.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | std_msgs/Header header 3 | 4 | # Identifying string. Must be unique in the topic namespace. 5 | string client_id 6 | 7 | # Feedback message sent back from the GUI, e.g. 8 | # when the status of an interactive marker was modified by the user. 9 | 10 | # Specifies which interactive marker and control this message refers to 11 | string marker_name 12 | string control_name 13 | 14 | # Type of the event 15 | # KEEP_ALIVE: sent while dragging to keep up control of the marker 16 | # MENU_SELECT: a menu entry has been selected 17 | # BUTTON_CLICK: a button control has been clicked 18 | # POSE_UPDATE: the pose has been changed using one of the controls 19 | uint8 KEEP_ALIVE = 0 20 | uint8 POSE_UPDATE = 1 21 | uint8 MENU_SELECT = 2 22 | uint8 BUTTON_CLICK = 3 23 | 24 | uint8 MOUSE_DOWN = 4 25 | uint8 MOUSE_UP = 5 26 | 27 | uint8 event_type 28 | 29 | # Current pose of the marker 30 | # Note: Has to be valid for all feedback types. 31 | geometry_msgs/Pose pose 32 | 33 | # Contains the ID of the selected menu entry 34 | # Only valid for MENU_SELECT events. 35 | uint32 menu_entry_id 36 | 37 | # If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point 38 | # may contain the 3 dimensional position of the event on the 39 | # control. If it does, mouse_point_valid will be true. mouse_point 40 | # will be relative to the frame listed in the header. 41 | geometry_msgs/Point mouse_point 42 | bool mouse_point_valid 43 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerInit.msg: -------------------------------------------------------------------------------- 1 | # Identifying string. Must be unique in the topic namespace 2 | # that this server works on. 3 | string server_id 4 | 5 | # Sequence number. 6 | # The client will use this to detect if it has missed a subsequent 7 | # update. Every update message will have the same sequence number as 8 | # an init message. Clients will likely want to unsubscribe from the 9 | # init topic after a successful initialization to avoid receiving 10 | # duplicate data. 11 | uint64 seq_num 12 | 13 | # All markers. 14 | InteractiveMarker[] markers 15 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerPose.msg: -------------------------------------------------------------------------------- 1 | 2 | # Time/frame info. 3 | std_msgs/Header header 4 | 5 | # Initial pose. Also, defines the pivot point for rotations. 6 | geometry_msgs/Pose pose 7 | 8 | # Identifying string. Must be globally unique in 9 | # the topic that this message is sent through. 10 | string name 11 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerUpdate.msg: -------------------------------------------------------------------------------- 1 | 2 | # Identifying string. Must be unique in the topic namespace 3 | # that this server works on. 4 | string server_id 5 | 6 | # Sequence number. 7 | # The client will use this to detect if it has missed an update. 8 | uint64 seq_num 9 | 10 | # Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE. 11 | # UPDATE: Incremental update to previous state. 12 | # The sequence number must be 1 higher than for 13 | # the previous update. 14 | # KEEP_ALIVE: Indicates the that the server is still living. 15 | # The sequence number does not increase. 16 | # No payload data should be filled out (markers, poses, or erases). 17 | uint8 KEEP_ALIVE = 0 18 | uint8 UPDATE = 1 19 | 20 | uint8 type 21 | 22 | # Note: No guarantees on the order of processing. 23 | # Contents must be kept consistent by sender. 24 | 25 | # Markers to be added or updated 26 | InteractiveMarker[] markers 27 | 28 | # Poses of markers that should be moved 29 | InteractiveMarkerPose[] poses 30 | 31 | # Names of markers to be erased 32 | string[] erases 33 | -------------------------------------------------------------------------------- /visualization_msgs/msg/Marker.msg: -------------------------------------------------------------------------------- 1 | # See: 2 | # - http://www.ros.org/wiki/rviz/DisplayTypes/Marker 3 | # - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes 4 | # 5 | # for more information on using this message with rviz. 6 | 7 | int32 ARROW=0 8 | int32 CUBE=1 9 | int32 SPHERE=2 10 | int32 CYLINDER=3 11 | int32 LINE_STRIP=4 12 | int32 LINE_LIST=5 13 | int32 CUBE_LIST=6 14 | int32 SPHERE_LIST=7 15 | int32 POINTS=8 16 | int32 TEXT_VIEW_FACING=9 17 | int32 MESH_RESOURCE=10 18 | int32 TRIANGLE_LIST=11 19 | int32 ARROW_STRIP=12 20 | 21 | int32 ADD=0 22 | int32 MODIFY=0 23 | int32 DELETE=2 24 | int32 DELETEALL=3 25 | 26 | # Header for timestamp and frame id. 27 | std_msgs/Header header 28 | # Namespace in which to place the object. 29 | # Used in conjunction with id to create a unique name for the object. 30 | string ns 31 | # Object ID used in conjunction with the namespace for manipulating and deleting the object later. 32 | int32 id 33 | # Type of object. 34 | int32 type 35 | # Action to take; one of: 36 | # - 0 add/modify an object 37 | # - 1 (deprecated) 38 | # - 2 deletes an object (with the given ns and id) 39 | # - 3 deletes all objects (or those with the given ns if any) 40 | int32 action 41 | # Pose of the object with respect the frame_id specified in the header. 42 | geometry_msgs/Pose pose 43 | # Scale of the object; 1,1,1 means default (usually 1 meter square). 44 | geometry_msgs/Vector3 scale 45 | # Color of the object; in the range: [0.0-1.0] 46 | std_msgs/ColorRGBA color 47 | # How long the object should last before being automatically deleted. 48 | # 0 indicates forever. 49 | builtin_interfaces/Duration lifetime 50 | # If this marker should be frame-locked, i.e. retransformed into its frame every timestep. 51 | bool frame_locked 52 | 53 | # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ARROW_STRIP, etc.) 54 | geometry_msgs/Point[] points 55 | # Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) 56 | # The number of colors provided must either be 0 or equal to the number of points provided. 57 | # NOTE: alpha is not yet used 58 | std_msgs/ColorRGBA[] colors 59 | 60 | # Texture resource is a special URI that can either reference a texture file in 61 | # a format acceptable to (resource retriever)[https://docs.ros.org/en/rolling/p/resource_retriever/] 62 | # or an embedded texture via a string matching the format: 63 | # "embedded://texture_name" 64 | string texture_resource 65 | # An image to be loaded into the rendering engine as the texture for this marker. 66 | # This will be used iff texture_resource is set to embedded. 67 | sensor_msgs/CompressedImage texture 68 | # Location of each vertex within the texture; in the range: [0.0-1.0] 69 | UVCoordinate[] uv_coordinates 70 | 71 | # Only used for text markers 72 | string text 73 | 74 | # Only used for MESH_RESOURCE markers. 75 | # Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. 76 | # Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, 77 | # use the following format for mesh_resource: 78 | # "embedded://mesh_name" 79 | string mesh_resource 80 | MeshFile mesh_file 81 | bool mesh_use_embedded_materials 82 | -------------------------------------------------------------------------------- /visualization_msgs/msg/MarkerArray.msg: -------------------------------------------------------------------------------- 1 | Marker[] markers 2 | -------------------------------------------------------------------------------- /visualization_msgs/msg/MenuEntry.msg: -------------------------------------------------------------------------------- 1 | # MenuEntry message. 2 | # 3 | # Each InteractiveMarker message has an array of MenuEntry messages. 4 | # A collection of MenuEntries together describe a 5 | # menu/submenu/subsubmenu/etc tree, though they are stored in a flat 6 | # array. The tree structure is represented by giving each menu entry 7 | # an ID number and a "parent_id" field. Top-level entries are the 8 | # ones with parent_id = 0. Menu entries are ordered within their 9 | # level the same way they are ordered in the containing array. Parent 10 | # entries must appear before their children. 11 | # 12 | # Example: 13 | # - id = 3 14 | # parent_id = 0 15 | # title = "fun" 16 | # - id = 2 17 | # parent_id = 0 18 | # title = "robot" 19 | # - id = 4 20 | # parent_id = 2 21 | # title = "pr2" 22 | # - id = 5 23 | # parent_id = 2 24 | # title = "turtle" 25 | # 26 | # Gives a menu tree like this: 27 | # - fun 28 | # - robot 29 | # - pr2 30 | # - turtle 31 | 32 | # ID is a number for each menu entry. Must be unique within the 33 | # control, and should never be 0. 34 | uint32 id 35 | 36 | # ID of the parent of this menu entry, if it is a submenu. If this 37 | # menu entry is a top-level entry, set parent_id to 0. 38 | uint32 parent_id 39 | 40 | # menu / entry title 41 | string title 42 | 43 | # Arguments to command indicated by command_type (below) 44 | string command 45 | 46 | # Command_type stores the type of response desired when this menu 47 | # entry is clicked. 48 | # FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. 49 | # ROSRUN: execute "rosrun" with arguments given in the command field (above). 50 | # ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). 51 | uint8 FEEDBACK=0 52 | uint8 ROSRUN=1 53 | uint8 ROSLAUNCH=2 54 | uint8 command_type 55 | -------------------------------------------------------------------------------- /visualization_msgs/msg/MeshFile.msg: -------------------------------------------------------------------------------- 1 | # Used to send raw mesh files. 2 | 3 | # The filename is used for both debug purposes and to provide a file extension 4 | # for whatever parser is used. 5 | string filename 6 | 7 | # This stores the raw text of the mesh file. 8 | uint8[] data 9 | -------------------------------------------------------------------------------- /visualization_msgs/msg/UVCoordinate.msg: -------------------------------------------------------------------------------- 1 | # Location of the pixel as a ratio of the width of a 2D texture. 2 | # Values should be in range: [0.0-1.0]. 3 | float32 u 4 | float32 v 5 | -------------------------------------------------------------------------------- /visualization_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | visualization_msgs 5 | 5.7.0 6 | A package containing some visualization and interaction related message definitions. 7 | 8 | Tully Foote 9 | 10 | Apache License 2.0 11 | 12 | Geoffrey Biggs 13 | Michael Carroll 14 | Michel Hidalgo 15 | William Woodall 16 | 17 | ament_cmake 18 | 19 | rosidl_default_generators 20 | 21 | builtin_interfaces 22 | geometry_msgs 23 | sensor_msgs 24 | std_msgs 25 | 26 | rosidl_default_runtime 27 | 28 | ament_lint_common 29 | 30 | rosidl_interface_packages 31 | 32 | 33 | ament_cmake 34 | 35 | 36 | -------------------------------------------------------------------------------- /visualization_msgs/srv/GetInteractiveMarkers.srv: -------------------------------------------------------------------------------- 1 | --- 2 | # Sequence number. 3 | # Set to the sequence number of the latest update message 4 | # at the time the server received the request. 5 | # Clients use this to detect if any updates were missed. 6 | uint64 sequence_number 7 | 8 | # All interactive markers provided by the server. 9 | InteractiveMarker[] markers 10 | --------------------------------------------------------------------------------