From da5eb1ad0781279fbeff80ffd0a2ee785bf09662 Mon Sep 17 00:00:00 2001 From: Greek64 Date: Fri, 7 Jan 2022 13:03:20 +0100 Subject: [PATCH] Add IDL definitions for ROS2 MSG and SRV --- src/TODO.txt | 5 +- src/ros2/common_interfaces/REF.txt | 2 + .../diagnostic_msgs/AddDiagnostics.idl | 41 +++++ .../diagnostic_msgs/AddDiagnostics.srv | 27 +++ .../diagnostic_msgs/DiagnosticArray.idl | 22 +++ .../diagnostic_msgs/DiagnosticArray.msg | 3 + .../diagnostic_msgs/DiagnosticStatus.idl | 39 +++++ .../diagnostic_msgs/DiagnosticStatus.msg | 19 +++ .../diagnostic_msgs/KeyValue.idl | 18 ++ .../diagnostic_msgs/KeyValue.msg | 4 + .../diagnostic_msgs/SelfTest.idl | 20 +++ .../diagnostic_msgs/SelfTest.srv | 4 + .../common_interfaces/geometry_msgs/Accel.idl | 17 ++ .../common_interfaces/geometry_msgs/Accel.msg | 3 + .../geometry_msgs/AccelStamped.idl | 18 ++ .../geometry_msgs/AccelStamped.msg | 3 + .../geometry_msgs/AccelWithCovariance.idl | 23 +++ .../geometry_msgs/AccelWithCovariance.msg | 9 + .../AccelWithCovarianceStamped.idl | 18 ++ .../AccelWithCovarianceStamped.msg | 3 + .../geometry_msgs/Inertia.idl | 38 +++++ .../geometry_msgs/Inertia.msg | 16 ++ .../geometry_msgs/InertiaStamped.idl | 18 ++ .../geometry_msgs/InertiaStamped.msg | 4 + .../common_interfaces/geometry_msgs/Point.idl | 18 ++ .../common_interfaces/geometry_msgs/Point.msg | 4 + .../geometry_msgs/Point32.idl | 24 +++ .../geometry_msgs/Point32.msg | 11 ++ .../geometry_msgs/PointStamped.idl | 18 ++ .../geometry_msgs/PointStamped.msg | 4 + .../geometry_msgs/Polygon.idl | 15 ++ .../geometry_msgs/Polygon.msg | 3 + .../geometry_msgs/PolygonStamped.idl | 18 ++ .../geometry_msgs/PolygonStamped.msg | 4 + .../common_interfaces/geometry_msgs/Pose.idl | 18 ++ .../common_interfaces/geometry_msgs/Pose.msg | 4 + .../geometry_msgs/Pose2D.idl | 22 +++ .../geometry_msgs/Pose2D.msg | 10 ++ .../geometry_msgs/PoseArray.idl | 18 ++ .../geometry_msgs/PoseArray.msg | 5 + .../geometry_msgs/PoseStamped.idl | 18 ++ .../geometry_msgs/PoseStamped.msg | 4 + .../geometry_msgs/PoseWithCovariance.idl | 23 +++ .../geometry_msgs/PoseWithCovariance.msg | 9 + .../PoseWithCovarianceStamped.idl | 18 ++ .../PoseWithCovarianceStamped.msg | 4 + .../geometry_msgs/Quaternion.idl | 24 +++ .../geometry_msgs/Quaternion.msg | 6 + .../geometry_msgs/QuaternionStamped.idl | 18 ++ .../geometry_msgs/QuaternionStamped.msg | 4 + .../geometry_msgs/Transform.idl | 18 ++ .../geometry_msgs/Transform.msg | 4 + .../geometry_msgs/TransformStamped.idl | 35 ++++ .../geometry_msgs/TransformStamped.msg | 19 +++ .../common_interfaces/geometry_msgs/Twist.idl | 17 ++ .../common_interfaces/geometry_msgs/Twist.msg | 4 + .../geometry_msgs/TwistStamped.idl | 18 ++ .../geometry_msgs/TwistStamped.msg | 4 + .../geometry_msgs/TwistWithCovariance.idl | 23 +++ .../geometry_msgs/TwistWithCovariance.msg | 9 + .../TwistWithCovarianceStamped.idl | 18 ++ .../TwistWithCovarianceStamped.msg | 4 + .../geometry_msgs/Vector3.idl | 22 +++ .../geometry_msgs/Vector3.msg | 9 + .../geometry_msgs/Vector3Stamped.idl | 21 +++ .../geometry_msgs/Vector3Stamped.msg | 7 + .../geometry_msgs/Wrench.idl | 17 ++ .../geometry_msgs/Wrench.msg | 4 + .../geometry_msgs/WrenchStamped.idl | 18 ++ .../geometry_msgs/WrenchStamped.msg | 4 + .../common_interfaces/nav_msgs/GetMap.idl | 20 +++ .../common_interfaces/nav_msgs/GetMap.srv | 4 + .../common_interfaces/nav_msgs/GetPlan.idl | 32 ++++ .../common_interfaces/nav_msgs/GetPlan.srv | 14 ++ .../common_interfaces/nav_msgs/GridCells.idl | 28 ++++ .../common_interfaces/nav_msgs/GridCells.msg | 12 ++ .../common_interfaces/nav_msgs/LoadMap.idl | 33 ++++ .../common_interfaces/nav_msgs/LoadMap.srv | 15 ++ .../nav_msgs/MapMetaData.idl | 38 +++++ .../nav_msgs/MapMetaData.msg | 17 ++ .../nav_msgs/OccupancyGrid.idl | 29 ++++ .../nav_msgs/OccupancyGrid.msg | 13 ++ .../common_interfaces/nav_msgs/Odometry.idl | 33 ++++ .../common_interfaces/nav_msgs/Odometry.msg | 15 ++ src/ros2/common_interfaces/nav_msgs/Path.idl | 22 +++ src/ros2/common_interfaces/nav_msgs/Path.msg | 7 + .../common_interfaces/nav_msgs/SetMap.idl | 27 +++ .../common_interfaces/nav_msgs/SetMap.srv | 11 ++ .../sensor_msgs/BatteryState.idl | 98 +++++++++++ .../sensor_msgs/BatteryState.msg | 52 ++++++ .../sensor_msgs/CameraInfo.idl | 156 ++++++++++++++++++ .../sensor_msgs/CameraInfo.msg | 131 +++++++++++++++ .../sensor_msgs/ChannelFloat32.idl | 37 +++++ .../sensor_msgs/ChannelFloat32.msg | 24 +++ .../sensor_msgs/CompressedImage.idl | 32 ++++ .../sensor_msgs/CompressedImage.msg | 14 ++ .../sensor_msgs/FluidPressure.idl | 30 ++++ .../sensor_msgs/FluidPressure.msg | 12 ++ .../sensor_msgs/Illuminance.idl | 38 +++++ .../sensor_msgs/Illuminance.msg | 20 +++ .../common_interfaces/sensor_msgs/Image.idl | 54 ++++++ .../common_interfaces/sensor_msgs/Image.msg | 26 +++ .../common_interfaces/sensor_msgs/Imu.idl | 48 ++++++ .../common_interfaces/sensor_msgs/Imu.msg | 24 +++ .../sensor_msgs/JointState.idl | 40 +++++ .../sensor_msgs/JointState.msg | 25 +++ .../common_interfaces/sensor_msgs/Joy.idl | 25 +++ .../common_interfaces/sensor_msgs/Joy.msg | 10 ++ .../sensor_msgs/JoyFeedback.idl | 29 ++++ .../sensor_msgs/JoyFeedback.msg | 14 ++ .../sensor_msgs/JoyFeedbackArray.idl | 15 ++ .../sensor_msgs/JoyFeedbackArray.msg | 2 + .../sensor_msgs/LaserEcho.idl | 18 ++ .../sensor_msgs/LaserEcho.msg | 5 + .../sensor_msgs/LaserScan.idl | 76 +++++++++ .../sensor_msgs/LaserScan.msg | 30 ++++ .../sensor_msgs/MagneticField.idl | 41 +++++ .../sensor_msgs/MagneticField.msg | 21 +++ .../sensor_msgs/MultiDOFJointState.idl | 44 +++++ .../sensor_msgs/MultiDOFJointState.msg | 26 +++ .../sensor_msgs/MultiEchoLaserScan.idl | 79 +++++++++ .../sensor_msgs/MultiEchoLaserScan.msg | 32 ++++ .../sensor_msgs/NavSatFix.idl | 65 ++++++++ .../sensor_msgs/NavSatFix.msg | 45 +++++ .../sensor_msgs/NavSatStatus.idl | 30 ++++ .../sensor_msgs/NavSatStatus.msg | 22 +++ .../sensor_msgs/PointCloud.idl | 33 ++++ .../sensor_msgs/PointCloud.msg | 17 ++ .../sensor_msgs/PointCloud2.idl | 56 +++++++ .../sensor_msgs/PointCloud2.msg | 26 +++ .../sensor_msgs/PointField.idl | 40 +++++ .../sensor_msgs/PointField.msg | 16 ++ .../common_interfaces/sensor_msgs/Range.idl | 68 ++++++++ .../common_interfaces/sensor_msgs/Range.msg | 39 +++++ .../sensor_msgs/RegionOfInterest.idl | 42 +++++ .../sensor_msgs/RegionOfInterest.msg | 19 +++ .../sensor_msgs/RelativeHumidity.idl | 31 ++++ .../sensor_msgs/RelativeHumidity.msg | 13 ++ .../sensor_msgs/SetCameraInfo.idl | 32 ++++ .../sensor_msgs/SetCameraInfo.srv | 12 ++ .../sensor_msgs/Temperature.idl | 26 +++ .../sensor_msgs/Temperature.msg | 8 + .../sensor_msgs/TimeReference.idl | 27 +++ .../sensor_msgs/TimeReference.msg | 7 + .../common_interfaces/shape_msgs/Mesh.idl | 22 +++ .../common_interfaces/shape_msgs/Mesh.msg | 7 + .../shape_msgs/MeshTriangle.idl | 15 ++ .../shape_msgs/MeshTriangle.msg | 3 + .../common_interfaces/shape_msgs/Plane.idl | 20 +++ .../common_interfaces/shape_msgs/Plane.msg | 7 + .../shape_msgs/SolidPrimitive.idl | 41 +++++ .../shape_msgs/SolidPrimitive.msg | 50 ++++++ .../common_interfaces/std_msgs/ColorRGBA.idl | 18 ++ .../common_interfaces/std_msgs/ColorRGBA.msg | 4 + src/ros2/common_interfaces/std_msgs/Empty.idl | 12 ++ src/ros2/common_interfaces/std_msgs/Empty.msg | 0 .../common_interfaces/std_msgs/Header.idl | 23 +++ .../common_interfaces/std_msgs/Header.msg | 9 + src/ros2/common_interfaces/std_srvs/Empty.idl | 15 ++ src/ros2/common_interfaces/std_srvs/Empty.srv | 1 + .../common_interfaces/std_srvs/SetBool.idl | 23 +++ .../common_interfaces/std_srvs/SetBool.srv | 4 + .../common_interfaces/std_srvs/Trigger.idl | 21 +++ .../common_interfaces/std_srvs/Trigger.srv | 3 + .../stereo_msgs/DisparityImage.idl | 54 ++++++ .../stereo_msgs/DisparityImage.msg | 29 ++++ .../trajectory_msgs/JointTrajectory.idl | 27 +++ .../trajectory_msgs/JointTrajectory.msg | 11 ++ .../trajectory_msgs/JointTrajectoryPoint.idl | 43 +++++ .../trajectory_msgs/JointTrajectoryPoint.msg | 26 +++ .../MultiDOFJointTrajectory.idl | 25 +++ .../MultiDOFJointTrajectory.msg | 10 ++ .../MultiDOFJointTrajectoryPoint.idl | 29 ++++ .../MultiDOFJointTrajectoryPoint.msg | 11 ++ .../GetInteractiveMarkers.idl | 25 +++ .../GetInteractiveMarkers.srv | 9 + .../visualization_msgs/ImageMarker.idl | 75 +++++++++ .../visualization_msgs/ImageMarker.msg | 36 ++++ .../visualization_msgs/InteractiveMarker.idl | 48 ++++++ .../visualization_msgs/InteractiveMarker.msg | 26 +++ .../InteractiveMarkerControl.idl | 73 ++++++++ .../InteractiveMarkerControl.msg | 77 +++++++++ .../InteractiveMarkerFeedback.idl | 58 +++++++ .../InteractiveMarkerFeedback.msg | 42 +++++ .../InteractiveMarkerInit.idl | 29 ++++ .../InteractiveMarkerInit.msg | 14 ++ .../InteractiveMarkerPose.idl | 25 +++ .../InteractiveMarkerPose.msg | 10 ++ .../InteractiveMarkerUpdate.idl | 42 +++++ .../InteractiveMarkerUpdate.msg | 32 ++++ .../visualization_msgs/Marker.idl | 134 +++++++++++++++ .../visualization_msgs/Marker.msg | 80 +++++++++ .../visualization_msgs/MarkerArray.idl | 13 ++ .../visualization_msgs/MarkerArray.msg | 1 + .../visualization_msgs/MenuEntry.idl | 66 ++++++++ .../visualization_msgs/MenuEntry.msg | 54 ++++++ .../visualization_msgs/MeshFile.idl | 21 +++ .../visualization_msgs/MeshFile.msg | 8 + .../visualization_msgs/UVCoordinate.idl | 17 ++ .../visualization_msgs/UVCoordinate.msg | 4 + src/ros2/rcl_interfaces/REF.txt | 2 + .../rcl_interfaces/action_msgs/CancelGoal.idl | 44 +++++ .../rcl_interfaces/action_msgs/CancelGoal.srv | 46 ++++++ .../rcl_interfaces/action_msgs/GoalInfo.idl | 20 +++ .../rcl_interfaces/action_msgs/GoalInfo.msg | 5 + .../rcl_interfaces/action_msgs/GoalStatus.idl | 33 ++++ .../rcl_interfaces/action_msgs/GoalStatus.msg | 32 ++++ .../action_msgs/GoalStatusArray.idl | 15 ++ .../action_msgs/GoalStatusArray.msg | 2 + .../builtin_interfaces/Duration.idl | 22 +++ .../builtin_interfaces/Duration.msg | 9 + .../builtin_interfaces/Time.idl | 21 +++ .../builtin_interfaces/Time.msg | 8 + .../composition_interfaces/ListNodes.idl | 21 +++ .../composition_interfaces/ListNodes.srv | 5 + .../composition_interfaces/LoadNode.idl | 67 ++++++++ .../composition_interfaces/LoadNode.srv | 42 +++++ .../composition_interfaces/UnloadNode.idl | 23 +++ .../composition_interfaces/UnloadNode.srv | 8 + .../lifecycle_msgs/ChangeState.idl | 22 +++ .../lifecycle_msgs/ChangeState.srv | 8 + .../lifecycle_msgs/GetAvailableStates.idl | 18 ++ .../lifecycle_msgs/GetAvailableStates.srv | 3 + .../GetAvailableTransitions.idl | 18 ++ .../GetAvailableTransitions.srv | 3 + .../lifecycle_msgs/GetState.idl | 18 ++ .../lifecycle_msgs/GetState.srv | 3 + .../rcl_interfaces/lifecycle_msgs/State.idl | 34 ++++ .../rcl_interfaces/lifecycle_msgs/State.msg | 57 +++++++ .../lifecycle_msgs/Transition.idl | 56 +++++++ .../lifecycle_msgs/Transition.msg | 94 +++++++++++ .../lifecycle_msgs/TransitionDescription.idl | 24 +++ .../lifecycle_msgs/TransitionDescription.msg | 8 + .../lifecycle_msgs/TransitionEvent.idl | 28 ++++ .../lifecycle_msgs/TransitionEvent.msg | 11 ++ .../MetricsMessage.idl | 49 ++++++ .../MetricsMessage.msg | 30 ++++ .../StatisticDataPoint.idl | 36 ++++ .../StatisticDataPoint.msg | 23 +++ .../StatisticDataType.idl | 29 ++++ .../StatisticDataType.msg | 18 ++ .../rcl_interfaces/DescribeParameters.idl | 22 +++ .../rcl_interfaces/DescribeParameters.srv | 8 + .../rcl_interfaces/FloatingPointRange.idl | 42 +++++ .../rcl_interfaces/FloatingPointRange.msg | 28 ++++ .../rcl_interfaces/GetParameterTypes.idl | 23 +++ .../rcl_interfaces/GetParameterTypes.srv | 10 ++ .../rcl_interfaces/GetParameters.idl | 29 ++++ .../rcl_interfaces/GetParameters.srv | 15 ++ .../rcl_interfaces/IntegerRange.idl | 38 +++++ .../rcl_interfaces/IntegerRange.msg | 24 +++ .../rcl_interfaces/ListParameters.idl | 31 ++++ .../rcl_interfaces/ListParameters.srv | 14 ++ .../rcl_interfaces/ListParametersResult.idl | 19 +++ .../rcl_interfaces/ListParametersResult.msg | 6 + .../rcl_interfaces/rcl_interfaces/Log.idl | 62 +++++++ .../rcl_interfaces/rcl_interfaces/Log.msg | 54 ++++++ .../rcl_interfaces/Parameter.idl | 23 +++ .../rcl_interfaces/Parameter.msg | 9 + .../rcl_interfaces/ParameterDescriptor.idl | 57 +++++++ .../rcl_interfaces/ParameterDescriptor.msg | 36 ++++ .../rcl_interfaces/ParameterEvent.idl | 36 ++++ .../rcl_interfaces/ParameterEvent.msg | 18 ++ .../ParameterEventDescriptors.idl | 21 +++ .../ParameterEventDescriptors.msg | 7 + .../rcl_interfaces/ParameterType.idl | 26 +++ .../rcl_interfaces/ParameterType.msg | 14 ++ .../rcl_interfaces/ParameterValue.idl | 58 +++++++ .../rcl_interfaces/ParameterValue.msg | 38 +++++ .../rcl_interfaces/SetParameters.idl | 21 +++ .../rcl_interfaces/SetParameters.srv | 6 + .../SetParametersAtomically.idl | 23 +++ .../SetParametersAtomically.srv | 8 + .../rcl_interfaces/SetParametersResult.idl | 20 +++ .../rcl_interfaces/SetParametersResult.msg | 7 + .../rcl_interfaces/rosgraph_msgs/Clock.idl | 17 ++ .../rcl_interfaces/rosgraph_msgs/Clock.msg | 4 + 277 files changed, 6815 insertions(+), 1 deletion(-) create mode 100644 src/ros2/common_interfaces/REF.txt create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.idl create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.srv create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.idl create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.msg create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.idl create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.msg create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/KeyValue.idl create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/KeyValue.msg create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/SelfTest.idl create mode 100644 src/ros2/common_interfaces/diagnostic_msgs/SelfTest.srv create mode 100644 src/ros2/common_interfaces/geometry_msgs/Accel.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Accel.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/AccelStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/AccelStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Inertia.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Inertia.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/InertiaStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/InertiaStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Point.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Point.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Point32.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Point32.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/PointStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/PointStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Polygon.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Polygon.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/PolygonStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/PolygonStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Pose.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Pose.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Pose2D.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Pose2D.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseArray.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseArray.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Quaternion.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Quaternion.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Transform.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Transform.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/TransformStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/TransformStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Twist.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Twist.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/TwistStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/TwistStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Vector3.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Vector3.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/Wrench.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/Wrench.msg create mode 100644 src/ros2/common_interfaces/geometry_msgs/WrenchStamped.idl create mode 100644 src/ros2/common_interfaces/geometry_msgs/WrenchStamped.msg create mode 100644 src/ros2/common_interfaces/nav_msgs/GetMap.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/GetMap.srv create mode 100644 src/ros2/common_interfaces/nav_msgs/GetPlan.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/GetPlan.srv create mode 100644 src/ros2/common_interfaces/nav_msgs/GridCells.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/GridCells.msg create mode 100644 src/ros2/common_interfaces/nav_msgs/LoadMap.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/LoadMap.srv create mode 100644 src/ros2/common_interfaces/nav_msgs/MapMetaData.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/MapMetaData.msg create mode 100644 src/ros2/common_interfaces/nav_msgs/OccupancyGrid.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/OccupancyGrid.msg create mode 100644 src/ros2/common_interfaces/nav_msgs/Odometry.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/Odometry.msg create mode 100644 src/ros2/common_interfaces/nav_msgs/Path.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/Path.msg create mode 100644 src/ros2/common_interfaces/nav_msgs/SetMap.idl create mode 100644 src/ros2/common_interfaces/nav_msgs/SetMap.srv create mode 100644 src/ros2/common_interfaces/sensor_msgs/BatteryState.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/BatteryState.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/CameraInfo.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/CameraInfo.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/CompressedImage.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/CompressedImage.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/FluidPressure.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/FluidPressure.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/Illuminance.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/Illuminance.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/Image.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/Image.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/Imu.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/Imu.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/JointState.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/JointState.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/Joy.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/Joy.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/JoyFeedback.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/JoyFeedback.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/LaserEcho.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/LaserEcho.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/LaserScan.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/LaserScan.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/MagneticField.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/MagneticField.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/NavSatFix.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/NavSatFix.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/NavSatStatus.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/NavSatStatus.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/PointCloud.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/PointCloud.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/PointCloud2.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/PointCloud2.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/PointField.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/PointField.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/Range.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/Range.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.srv create mode 100644 src/ros2/common_interfaces/sensor_msgs/Temperature.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/Temperature.msg create mode 100644 src/ros2/common_interfaces/sensor_msgs/TimeReference.idl create mode 100644 src/ros2/common_interfaces/sensor_msgs/TimeReference.msg create mode 100644 src/ros2/common_interfaces/shape_msgs/Mesh.idl create mode 100644 src/ros2/common_interfaces/shape_msgs/Mesh.msg create mode 100644 src/ros2/common_interfaces/shape_msgs/MeshTriangle.idl create mode 100644 src/ros2/common_interfaces/shape_msgs/MeshTriangle.msg create mode 100644 src/ros2/common_interfaces/shape_msgs/Plane.idl create mode 100644 src/ros2/common_interfaces/shape_msgs/Plane.msg create mode 100644 src/ros2/common_interfaces/shape_msgs/SolidPrimitive.idl create mode 100644 src/ros2/common_interfaces/shape_msgs/SolidPrimitive.msg create mode 100644 src/ros2/common_interfaces/std_msgs/ColorRGBA.idl create mode 100644 src/ros2/common_interfaces/std_msgs/ColorRGBA.msg create mode 100644 src/ros2/common_interfaces/std_msgs/Empty.idl create mode 100644 src/ros2/common_interfaces/std_msgs/Empty.msg create mode 100644 src/ros2/common_interfaces/std_msgs/Header.idl create mode 100644 src/ros2/common_interfaces/std_msgs/Header.msg create mode 100644 src/ros2/common_interfaces/std_srvs/Empty.idl create mode 100644 src/ros2/common_interfaces/std_srvs/Empty.srv create mode 100644 src/ros2/common_interfaces/std_srvs/SetBool.idl create mode 100644 src/ros2/common_interfaces/std_srvs/SetBool.srv create mode 100644 src/ros2/common_interfaces/std_srvs/Trigger.idl create mode 100644 src/ros2/common_interfaces/std_srvs/Trigger.srv create mode 100644 src/ros2/common_interfaces/stereo_msgs/DisparityImage.idl create mode 100644 src/ros2/common_interfaces/stereo_msgs/DisparityImage.msg create mode 100644 src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.idl create mode 100644 src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.msg create mode 100644 src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.idl create mode 100644 src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.msg create mode 100644 src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.idl create mode 100644 src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.msg create mode 100644 src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.idl create mode 100644 src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.srv create mode 100644 src/ros2/common_interfaces/visualization_msgs/ImageMarker.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/ImageMarker.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/Marker.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/Marker.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/MarkerArray.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/MarkerArray.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/MenuEntry.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/MenuEntry.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/MeshFile.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/MeshFile.msg create mode 100644 src/ros2/common_interfaces/visualization_msgs/UVCoordinate.idl create mode 100644 src/ros2/common_interfaces/visualization_msgs/UVCoordinate.msg create mode 100644 src/ros2/rcl_interfaces/REF.txt create mode 100644 src/ros2/rcl_interfaces/action_msgs/CancelGoal.idl create mode 100644 src/ros2/rcl_interfaces/action_msgs/CancelGoal.srv create mode 100644 src/ros2/rcl_interfaces/action_msgs/GoalInfo.idl create mode 100644 src/ros2/rcl_interfaces/action_msgs/GoalInfo.msg create mode 100644 src/ros2/rcl_interfaces/action_msgs/GoalStatus.idl create mode 100644 src/ros2/rcl_interfaces/action_msgs/GoalStatus.msg create mode 100644 src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.idl create mode 100644 src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.msg create mode 100644 src/ros2/rcl_interfaces/builtin_interfaces/Duration.idl create mode 100644 src/ros2/rcl_interfaces/builtin_interfaces/Duration.msg create mode 100644 src/ros2/rcl_interfaces/builtin_interfaces/Time.idl create mode 100644 src/ros2/rcl_interfaces/builtin_interfaces/Time.msg create mode 100644 src/ros2/rcl_interfaces/composition_interfaces/ListNodes.idl create mode 100644 src/ros2/rcl_interfaces/composition_interfaces/ListNodes.srv create mode 100644 src/ros2/rcl_interfaces/composition_interfaces/LoadNode.idl create mode 100644 src/ros2/rcl_interfaces/composition_interfaces/LoadNode.srv create mode 100644 src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.idl create mode 100644 src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.srv create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.srv create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.srv create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.srv create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/GetState.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/GetState.srv create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/State.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/State.msg create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/Transition.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/Transition.msg create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.msg create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.idl create mode 100644 src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.msg create mode 100644 src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.idl create mode 100644 src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.msg create mode 100644 src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.idl create mode 100644 src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.msg create mode 100644 src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.idl create mode 100644 src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.srv create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.srv create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.srv create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.srv create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/Log.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/Log.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/Parameter.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/Parameter.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.msg create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.srv create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.srv create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.idl create mode 100644 src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.msg create mode 100644 src/ros2/rcl_interfaces/rosgraph_msgs/Clock.idl create mode 100644 src/ros2/rcl_interfaces/rosgraph_msgs/Clock.msg diff --git a/src/TODO.txt b/src/TODO.txt index 22d533b..fd55374 100644 --- a/src/TODO.txt +++ b/src/TODO.txt @@ -95,6 +95,9 @@ Which means that the bound of a bounded string does not count the NUL byte. * Currently we use one rtps_builtin_endpoint per participant. Meaning that if we want to compile 2 seperate participants we have to actually compile 2 different systems (e.g. in seperate Libraries for testing). It would make sense to remove this restriction, rename the rtps_builtin_endpoint to something more generic like "discovery_module", and allow a way to set participant boundaries. +* Convert ROS MSG and SRV files to IDL files + ros2 run rosidl_adapter msg2idl.py *.msg + ros2 run rosidl_adapter srv2idl.py *.srv * Fast-RTPS does not follow DDSI-RTPS Specification - Open Github Issue @@ -430,4 +433,4 @@ RTPS ENDPOINT ============= * 8.2.6 - topicKind Used to indicate whether the Endpoint supports instance lifecycle management operations (see 8.7.4). \ No newline at end of file + topicKind Used to indicate whether the Endpoint supports instance lifecycle management operations (see 8.7.4). diff --git a/src/ros2/common_interfaces/REF.txt b/src/ros2/common_interfaces/REF.txt new file mode 100644 index 0000000..037f156 --- /dev/null +++ b/src/ros2/common_interfaces/REF.txt @@ -0,0 +1,2 @@ +https://github.com/ros2/common_interfaces.git +@ f41462f5dd36f5c3ae28866f18f356423ffb84e4 4.0.0 diff --git a/src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.idl b/src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.idl new file mode 100644 index 0000000..6410dc3 --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.idl @@ -0,0 +1,41 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from diagnostic_msgs/srv/AddDiagnostics.srv +// generated code does not contain a copyright notice + + +module diagnostic_msgs { + module srv { + @verbatim (language="comment", text= + " This service is used as part of the process for loading analyzers at runtime," "\n" + " and should be used by a loader script or program, not as a standalone service." "\n" + " Information about dynamic addition of analyzers can be found at" "\n" + " http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime") + struct AddDiagnostics_Request { + @verbatim (language="comment", text= + " The load_namespace parameter defines the namespace where parameters for the" "\n" + " initialization of analyzers in the diagnostic aggregator have been loaded. The" "\n" + " value should be a global name (i.e. /my/name/space), not a relative" "\n" + " (my/name/space) or private (~my/name/space) name. Analyzers will not be added" "\n" + " if a non-global name is used. The call will also fail if the namespace" "\n" + " contains parameters that follow a namespace structure that does not conform to" "\n" + " that expected by the analyzer definitions. See" "\n" + " http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators" "\n" + " and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer" "\n" + " for examples of the structure of yaml files which are expected to have been" "\n" + " loaded into the namespace.") + string load_namespace; + }; + struct AddDiagnostics_Response { + @verbatim (language="comment", text= + " True if diagnostic aggregator was updated with new diagnostics, False" "\n" + " otherwise. A false return value means that either there is a bond in the" "\n" + " aggregator which already used the requested namespace, or the initialization" "\n" + " of analyzers failed.") + boolean success; + + @verbatim (language="comment", text= + " Message with additional information about the success or failure") + string message; + }; + }; +}; diff --git a/src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.srv b/src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.srv new file mode 100644 index 0000000..413c401 --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/AddDiagnostics.srv @@ -0,0 +1,27 @@ +# This service is used as part of the process for loading analyzers at runtime, +# and should be used by a loader script or program, not as a standalone service. +# Information about dynamic addition of analyzers can be found at +# http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime + +# The load_namespace parameter defines the namespace where parameters for the +# initialization of analyzers in the diagnostic aggregator have been loaded. The +# value should be a global name (i.e. /my/name/space), not a relative +# (my/name/space) or private (~my/name/space) name. Analyzers will not be added +# if a non-global name is used. The call will also fail if the namespace +# contains parameters that follow a namespace structure that does not conform to +# that expected by the analyzer definitions. See +# http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators +# and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer +# for examples of the structure of yaml files which are expected to have been +# loaded into the namespace. +string load_namespace +--- + +# True if diagnostic aggregator was updated with new diagnostics, False +# otherwise. A false return value means that either there is a bond in the +# aggregator which already used the requested namespace, or the initialization +# of analyzers failed. +bool success + +# Message with additional information about the success or failure +string message diff --git a/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.idl b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.idl new file mode 100644 index 0000000..3e0810a --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from diagnostic_msgs/msg/DiagnosticArray.msg +// generated code does not contain a copyright notice + +#include "diagnostic_msgs/msg/DiagnosticStatus.idl" +#include "std_msgs/msg/Header.idl" + +module diagnostic_msgs { + module msg { + @verbatim (language="comment", text= + " This message is used to send diagnostic information about the state of the robot.") + struct DiagnosticArray { + @verbatim (language="comment", text= + " for timestamp") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " an array of components being reported on") + sequence status; + }; + }; +}; diff --git a/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.msg b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.msg new file mode 100644 index 0000000..358a0be --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticArray.msg @@ -0,0 +1,3 @@ +# This message is used to send diagnostic information about the state of the robot. +std_msgs/Header header # for timestamp +DiagnosticStatus[] status # an array of components being reported on diff --git a/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.idl b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.idl new file mode 100644 index 0000000..9ce3c51 --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.idl @@ -0,0 +1,39 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from diagnostic_msgs/msg/DiagnosticStatus.msg +// generated code does not contain a copyright notice + +#include "diagnostic_msgs/msg/KeyValue.idl" + +module diagnostic_msgs { + module msg { + module DiagnosticStatus_Constants { + const octet OK = 0; + const octet WARN = 1; + const octet ERROR = 2; + const octet STALE = 3; + }; + @verbatim (language="comment", text= + " This message holds the status of an individual component of the robot.") + struct DiagnosticStatus { + @verbatim (language="comment", text= + " Level of operation enumerated above.") + octet level; + + @verbatim (language="comment", text= + " A description of the test/component reporting.") + string name; + + @verbatim (language="comment", text= + " A description of the status.") + string message; + + @verbatim (language="comment", text= + " A hardware unique string.") + string hardware_id; + + @verbatim (language="comment", text= + " An array of values associated with the status.") + sequence values; + }; + }; +}; diff --git a/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.msg b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.msg new file mode 100644 index 0000000..b49f5c7 --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/DiagnosticStatus.msg @@ -0,0 +1,19 @@ +# This message holds the status of an individual component of the robot. + +# Possible levels of operations. +byte OK=0 +byte WARN=1 +byte ERROR=2 +byte STALE=3 + +# Level of operation enumerated above. +byte level +# A description of the test/component reporting. +string name +# A description of the status. +string message +# A hardware unique string. +string hardware_id +# An array of values associated with the status. +KeyValue[] values + diff --git a/src/ros2/common_interfaces/diagnostic_msgs/KeyValue.idl b/src/ros2/common_interfaces/diagnostic_msgs/KeyValue.idl new file mode 100644 index 0000000..8234b11 --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/KeyValue.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from diagnostic_msgs/msg/KeyValue.msg +// generated code does not contain a copyright notice + + +module diagnostic_msgs { + module msg { + @verbatim (language="comment", text= + " What to label this value when viewing.") + struct KeyValue { + string key; + + @verbatim (language="comment", text= + " A value to track over time.") + string value; + }; + }; +}; diff --git a/src/ros2/common_interfaces/diagnostic_msgs/KeyValue.msg b/src/ros2/common_interfaces/diagnostic_msgs/KeyValue.msg new file mode 100644 index 0000000..2362c50 --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/KeyValue.msg @@ -0,0 +1,4 @@ +# What to label this value when viewing. +string key +# A value to track over time. +string value diff --git a/src/ros2/common_interfaces/diagnostic_msgs/SelfTest.idl b/src/ros2/common_interfaces/diagnostic_msgs/SelfTest.idl new file mode 100644 index 0000000..55a6a09 --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/SelfTest.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from diagnostic_msgs/srv/SelfTest.srv +// generated code does not contain a copyright notice + +#include "diagnostic_msgs/msg/DiagnosticStatus.idl" + +module diagnostic_msgs { + module srv { + struct SelfTest_Request { + uint8 structure_needs_at_least_one_member; + }; + struct SelfTest_Response { + string id; + + octet passed; + + sequence status; + }; + }; +}; diff --git a/src/ros2/common_interfaces/diagnostic_msgs/SelfTest.srv b/src/ros2/common_interfaces/diagnostic_msgs/SelfTest.srv new file mode 100644 index 0000000..ee2974d --- /dev/null +++ b/src/ros2/common_interfaces/diagnostic_msgs/SelfTest.srv @@ -0,0 +1,4 @@ +--- +string id +byte passed +DiagnosticStatus[] status diff --git a/src/ros2/common_interfaces/geometry_msgs/Accel.idl b/src/ros2/common_interfaces/geometry_msgs/Accel.idl new file mode 100644 index 0000000..04f4b6c --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Accel.idl @@ -0,0 +1,17 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Accel.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Vector3.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This expresses acceleration in free space broken into its linear and angular parts.") + struct Accel { + geometry_msgs::msg::Vector3 linear; + + geometry_msgs::msg::Vector3 angular; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Accel.msg b/src/ros2/common_interfaces/geometry_msgs/Accel.msg new file mode 100644 index 0000000..19fef14 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Accel.msg @@ -0,0 +1,3 @@ +# This expresses acceleration in free space broken into its linear and angular parts. +Vector3 linear +Vector3 angular diff --git a/src/ros2/common_interfaces/geometry_msgs/AccelStamped.idl b/src/ros2/common_interfaces/geometry_msgs/AccelStamped.idl new file mode 100644 index 0000000..43983b5 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/AccelStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/AccelStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Accel.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " An accel with reference coordinate frame and timestamp") + struct AccelStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Accel accel; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/AccelStamped.msg b/src/ros2/common_interfaces/geometry_msgs/AccelStamped.msg new file mode 100644 index 0000000..9283fbb --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/AccelStamped.msg @@ -0,0 +1,3 @@ +# An accel with reference coordinate frame and timestamp +std_msgs/Header header +Accel accel diff --git a/src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.idl b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.idl new file mode 100644 index 0000000..608cf41 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/AccelWithCovariance.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Accel.idl" + +module geometry_msgs { + module msg { + typedef double double__36[36]; + @verbatim (language="comment", text= + " This expresses acceleration in free space with uncertainty.") + struct AccelWithCovariance { + geometry_msgs::msg::Accel accel; + + @verbatim (language="comment", text= + " Row-major representation of the 6x6 covariance matrix" "\n" + " The orientation parameters use a fixed-axis representation." "\n" + " In order, the parameters are:" "\n" + " (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)") + double__36 covariance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.msg b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.msg new file mode 100644 index 0000000..fb9674d --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovariance.msg @@ -0,0 +1,9 @@ +# This expresses acceleration in free space with uncertainty. + +Accel accel + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance diff --git a/src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.idl b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.idl new file mode 100644 index 0000000..d65d39c --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/AccelWithCovarianceStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/AccelWithCovariance.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents an estimated accel with reference coordinate frame and timestamp.") + struct AccelWithCovarianceStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::AccelWithCovariance accel; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.msg b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.msg new file mode 100644 index 0000000..90acd6e --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/AccelWithCovarianceStamped.msg @@ -0,0 +1,3 @@ +# This represents an estimated accel with reference coordinate frame and timestamp. +std_msgs/Header header +AccelWithCovariance accel diff --git a/src/ros2/common_interfaces/geometry_msgs/Inertia.idl b/src/ros2/common_interfaces/geometry_msgs/Inertia.idl new file mode 100644 index 0000000..c8558ec --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Inertia.idl @@ -0,0 +1,38 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Inertia.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Vector3.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " Mass") + struct Inertia { + double m; + + @verbatim (language="comment", text= + " Center of mass") + @unit (value="m") + geometry_msgs::msg::Vector3 com; + + @verbatim (language="comment", text= + " Inertia Tensor" "\n" + " | ixx ixy ixz |" "\n" + " I = | ixy iyy iyz |" "\n" + " | ixz iyz izz |") + @unit (value="kg-m^2") + double ixx; + + double ixy; + + double ixz; + + double iyy; + + double iyz; + + double izz; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Inertia.msg b/src/ros2/common_interfaces/geometry_msgs/Inertia.msg new file mode 100644 index 0000000..8b214df --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Inertia.msg @@ -0,0 +1,16 @@ +# Mass [kg] +float64 m + +# Center of mass [m] +geometry_msgs/Vector3 com + +# Inertia Tensor [kg-m^2] +# | ixx ixy ixz | +# I = | ixy iyy iyz | +# | ixz iyz izz | +float64 ixx +float64 ixy +float64 ixz +float64 iyy +float64 iyz +float64 izz diff --git a/src/ros2/common_interfaces/geometry_msgs/InertiaStamped.idl b/src/ros2/common_interfaces/geometry_msgs/InertiaStamped.idl new file mode 100644 index 0000000..4c46d8f --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/InertiaStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/InertiaStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Inertia.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " An Inertia with a time stamp and reference frame.") + struct InertiaStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Inertia inertia; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/InertiaStamped.msg b/src/ros2/common_interfaces/geometry_msgs/InertiaStamped.msg new file mode 100644 index 0000000..7da2662 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/InertiaStamped.msg @@ -0,0 +1,4 @@ +# An Inertia with a time stamp and reference frame. + +std_msgs/Header header +Inertia inertia diff --git a/src/ros2/common_interfaces/geometry_msgs/Point.idl b/src/ros2/common_interfaces/geometry_msgs/Point.idl new file mode 100644 index 0000000..65ef26f --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Point.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Point.msg +// generated code does not contain a copyright notice + + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This contains the position of a point in free space") + struct Point { + double x; + + double y; + + double z; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Point.msg b/src/ros2/common_interfaces/geometry_msgs/Point.msg new file mode 100644 index 0000000..f1d3a71 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Point.msg @@ -0,0 +1,4 @@ +# This contains the position of a point in free space +float64 x +float64 y +float64 z diff --git a/src/ros2/common_interfaces/geometry_msgs/Point32.idl b/src/ros2/common_interfaces/geometry_msgs/Point32.idl new file mode 100644 index 0000000..899ba55 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Point32.idl @@ -0,0 +1,24 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Point32.msg +// generated code does not contain a copyright notice + + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This contains the position of a point in free space(with 32 bits of precision)." "\n" + " It is recommended to use Point wherever possible instead of Point32." "\n" + "" "\n" + " This recommendation is to promote interoperability." "\n" + "" "\n" + " This message is designed to take up less space when sending" "\n" + " lots of points at once, as in the case of a PointCloud.") + struct Point32 { + float x; + + float y; + + float z; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Point32.msg b/src/ros2/common_interfaces/geometry_msgs/Point32.msg new file mode 100644 index 0000000..a7f5dc4 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Point32.msg @@ -0,0 +1,11 @@ +# This contains the position of a point in free space(with 32 bits of precision). +# It is recommended to use Point wherever possible instead of Point32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending +# lots of points at once, as in the case of a PointCloud. + +float32 x +float32 y +float32 z diff --git a/src/ros2/common_interfaces/geometry_msgs/PointStamped.idl b/src/ros2/common_interfaces/geometry_msgs/PointStamped.idl new file mode 100644 index 0000000..d592cd0 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PointStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/PointStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Point.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents a Point with reference coordinate frame and timestamp") + struct PointStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Point point; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/PointStamped.msg b/src/ros2/common_interfaces/geometry_msgs/PointStamped.msg new file mode 100644 index 0000000..32a734c --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PointStamped.msg @@ -0,0 +1,4 @@ +# This represents a Point with reference coordinate frame and timestamp + +std_msgs/Header header +Point point diff --git a/src/ros2/common_interfaces/geometry_msgs/Polygon.idl b/src/ros2/common_interfaces/geometry_msgs/Polygon.idl new file mode 100644 index 0000000..046e4f6 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Polygon.idl @@ -0,0 +1,15 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Polygon.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Point32.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " A specification of a polygon where the first and last points are assumed to be connected") + struct Polygon { + sequence points; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Polygon.msg b/src/ros2/common_interfaces/geometry_msgs/Polygon.msg new file mode 100644 index 0000000..47aeb74 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Polygon.msg @@ -0,0 +1,3 @@ +# A specification of a polygon where the first and last points are assumed to be connected + +Point32[] points diff --git a/src/ros2/common_interfaces/geometry_msgs/PolygonStamped.idl b/src/ros2/common_interfaces/geometry_msgs/PolygonStamped.idl new file mode 100644 index 0000000..6bee45a --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PolygonStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/PolygonStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Polygon.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents a Polygon with reference coordinate frame and timestamp") + struct PolygonStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Polygon polygon; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/PolygonStamped.msg b/src/ros2/common_interfaces/geometry_msgs/PolygonStamped.msg new file mode 100644 index 0000000..3b87ac1 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PolygonStamped.msg @@ -0,0 +1,4 @@ +# This represents a Polygon with reference coordinate frame and timestamp + +std_msgs/Header header +Polygon polygon diff --git a/src/ros2/common_interfaces/geometry_msgs/Pose.idl b/src/ros2/common_interfaces/geometry_msgs/Pose.idl new file mode 100644 index 0000000..1690053 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Pose.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Pose.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Point.idl" +#include "geometry_msgs/msg/Quaternion.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " A representation of pose in free space, composed of position and orientation.") + struct Pose { + geometry_msgs::msg::Point position; + + geometry_msgs::msg::Quaternion orientation; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Pose.msg b/src/ros2/common_interfaces/geometry_msgs/Pose.msg new file mode 100644 index 0000000..277e2f0 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Pose.msg @@ -0,0 +1,4 @@ +# A representation of pose in free space, composed of position and orientation. + +Point position +Quaternion orientation diff --git a/src/ros2/common_interfaces/geometry_msgs/Pose2D.idl b/src/ros2/common_interfaces/geometry_msgs/Pose2D.idl new file mode 100644 index 0000000..09df6a5 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Pose2D.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Pose2D.msg +// generated code does not contain a copyright notice + + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " Deprecated as of Foxy and will potentially be removed in any following release." "\n" + " Please use the full 3D pose.") + struct Pose2D { + @verbatim (language="comment", text= + " 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." "\n" + " 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.") + double x; + + double y; + + double theta; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Pose2D.msg b/src/ros2/common_interfaces/geometry_msgs/Pose2D.msg new file mode 100644 index 0000000..e9cf016 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Pose2D.msg @@ -0,0 +1,10 @@ +# Deprecated as of Foxy and will potentially be removed in any following release. +# Please use the full 3D pose. + +# 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. + +# 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. + +float64 x +float64 y +float64 theta diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseArray.idl b/src/ros2/common_interfaces/geometry_msgs/PoseArray.idl new file mode 100644 index 0000000..bf54823 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseArray.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/PoseArray.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Pose.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " An array of poses with a header for global reference.") + struct PoseArray { + std_msgs::msg::Header header; + + sequence poses; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseArray.msg b/src/ros2/common_interfaces/geometry_msgs/PoseArray.msg new file mode 100644 index 0000000..80386e0 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseArray.msg @@ -0,0 +1,5 @@ +# An array of poses with a header for global reference. + +std_msgs/Header header + +Pose[] poses diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseStamped.idl b/src/ros2/common_interfaces/geometry_msgs/PoseStamped.idl new file mode 100644 index 0000000..7f4d7e4 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/PoseStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Pose.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " A Pose with reference coordinate frame and timestamp") + struct PoseStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Pose pose; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseStamped.msg b/src/ros2/common_interfaces/geometry_msgs/PoseStamped.msg new file mode 100644 index 0000000..2b43935 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseStamped.msg @@ -0,0 +1,4 @@ +# A Pose with reference coordinate frame and timestamp + +std_msgs/Header header +Pose pose diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.idl b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.idl new file mode 100644 index 0000000..635593c --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/PoseWithCovariance.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Pose.idl" + +module geometry_msgs { + module msg { + typedef double double__36[36]; + @verbatim (language="comment", text= + " This represents a pose in free space with uncertainty.") + struct PoseWithCovariance { + geometry_msgs::msg::Pose pose; + + @verbatim (language="comment", text= + " Row-major representation of the 6x6 covariance matrix" "\n" + " The orientation parameters use a fixed-axis representation." "\n" + " In order, the parameters are:" "\n" + " (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)") + double__36 covariance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.msg b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.msg new file mode 100644 index 0000000..86bc45a --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovariance.msg @@ -0,0 +1,9 @@ +# This represents a pose in free space with uncertainty. + +Pose pose + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.idl b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.idl new file mode 100644 index 0000000..4aee318 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/PoseWithCovarianceStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/PoseWithCovariance.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This expresses an estimated pose with a reference coordinate frame and timestamp") + struct PoseWithCovarianceStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::PoseWithCovariance pose; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.msg b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.msg new file mode 100644 index 0000000..d439cdf --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/PoseWithCovarianceStamped.msg @@ -0,0 +1,4 @@ +# This expresses an estimated pose with a reference coordinate frame and timestamp + +std_msgs/Header header +PoseWithCovariance pose diff --git a/src/ros2/common_interfaces/geometry_msgs/Quaternion.idl b/src/ros2/common_interfaces/geometry_msgs/Quaternion.idl new file mode 100644 index 0000000..cf06ae5 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Quaternion.idl @@ -0,0 +1,24 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Quaternion.msg +// generated code does not contain a copyright notice + + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents an orientation in free space in quaternion form.") + struct Quaternion { + @default (value=0.0) + double x; + + @default (value=0.0) + double y; + + @default (value=0.0) + double z; + + @default (value=1.0) + double w; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Quaternion.msg b/src/ros2/common_interfaces/geometry_msgs/Quaternion.msg new file mode 100644 index 0000000..96d3927 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Quaternion.msg @@ -0,0 +1,6 @@ +# This represents an orientation in free space in quaternion form. + +float64 x 0 +float64 y 0 +float64 z 0 +float64 w 1 diff --git a/src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.idl b/src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.idl new file mode 100644 index 0000000..2bc5175 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/QuaternionStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Quaternion.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents an orientation with reference coordinate frame and timestamp.") + struct QuaternionStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Quaternion quaternion; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.msg b/src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.msg new file mode 100644 index 0000000..f192883 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/QuaternionStamped.msg @@ -0,0 +1,4 @@ +# This represents an orientation with reference coordinate frame and timestamp. + +std_msgs/Header header +Quaternion quaternion diff --git a/src/ros2/common_interfaces/geometry_msgs/Transform.idl b/src/ros2/common_interfaces/geometry_msgs/Transform.idl new file mode 100644 index 0000000..92da301 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Transform.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Transform.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Quaternion.idl" +#include "geometry_msgs/msg/Vector3.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents the transform between two coordinate frames in free space.") + struct Transform { + geometry_msgs::msg::Vector3 translation; + + geometry_msgs::msg::Quaternion rotation; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Transform.msg b/src/ros2/common_interfaces/geometry_msgs/Transform.msg new file mode 100644 index 0000000..f605c85 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Transform.msg @@ -0,0 +1,4 @@ +# This represents the transform between two coordinate frames in free space. + +Vector3 translation +Quaternion rotation diff --git a/src/ros2/common_interfaces/geometry_msgs/TransformStamped.idl b/src/ros2/common_interfaces/geometry_msgs/TransformStamped.idl new file mode 100644 index 0000000..a700642 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TransformStamped.idl @@ -0,0 +1,35 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/TransformStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Transform.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This expresses a transform from coordinate frame header.frame_id" "\n" + " to the coordinate frame child_frame_id at the time of header.stamp" "\n" + "" "\n" + " This message is mostly used by the" "\n" + " tf2 package." "\n" + " See its documentation for more information." "\n" + "" "\n" + " The child_frame_id is necessary in addition to the frame_id" "\n" + " in the Header to communicate the full reference for the transform" "\n" + " in a self contained message.") + struct TransformStamped { + @verbatim (language="comment", text= + " The frame id in the header is used as the reference frame of this transform.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " The frame id of the child frame to which this transform points.") + string child_frame_id; + + @verbatim (language="comment", text= + " Translation and rotation in 3-dimensions of child_frame_id from header.frame_id.") + geometry_msgs::msg::Transform transform; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/TransformStamped.msg b/src/ros2/common_interfaces/geometry_msgs/TransformStamped.msg new file mode 100644 index 0000000..ac6be59 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TransformStamped.msg @@ -0,0 +1,19 @@ +# This expresses a transform from coordinate frame header.frame_id +# to the coordinate frame child_frame_id at the time of header.stamp +# +# This message is mostly used by the +# tf2 package. +# See its documentation for more information. +# +# The child_frame_id is necessary in addition to the frame_id +# in the Header to communicate the full reference for the transform +# in a self contained message. + +# The frame id in the header is used as the reference frame of this transform. +std_msgs/Header header + +# The frame id of the child frame to which this transform points. +string child_frame_id + +# Translation and rotation in 3-dimensions of child_frame_id from header.frame_id. +Transform transform diff --git a/src/ros2/common_interfaces/geometry_msgs/Twist.idl b/src/ros2/common_interfaces/geometry_msgs/Twist.idl new file mode 100644 index 0000000..84b0fbe --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Twist.idl @@ -0,0 +1,17 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Twist.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Vector3.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This expresses velocity in free space broken into its linear and angular parts.") + struct Twist { + geometry_msgs::msg::Vector3 linear; + + geometry_msgs::msg::Vector3 angular; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Twist.msg b/src/ros2/common_interfaces/geometry_msgs/Twist.msg new file mode 100644 index 0000000..ede7359 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Twist.msg @@ -0,0 +1,4 @@ +# This expresses velocity in free space broken into its linear and angular parts. + +Vector3 linear +Vector3 angular diff --git a/src/ros2/common_interfaces/geometry_msgs/TwistStamped.idl b/src/ros2/common_interfaces/geometry_msgs/TwistStamped.idl new file mode 100644 index 0000000..be61baf --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TwistStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/TwistStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Twist.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " A twist with reference coordinate frame and timestamp") + struct TwistStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Twist twist; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/TwistStamped.msg b/src/ros2/common_interfaces/geometry_msgs/TwistStamped.msg new file mode 100644 index 0000000..2dcbeac --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TwistStamped.msg @@ -0,0 +1,4 @@ +# A twist with reference coordinate frame and timestamp + +std_msgs/Header header +Twist twist diff --git a/src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.idl b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.idl new file mode 100644 index 0000000..ebe0a47 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/TwistWithCovariance.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Twist.idl" + +module geometry_msgs { + module msg { + typedef double double__36[36]; + @verbatim (language="comment", text= + " This expresses velocity in free space with uncertainty.") + struct TwistWithCovariance { + geometry_msgs::msg::Twist twist; + + @verbatim (language="comment", text= + " Row-major representation of the 6x6 covariance matrix" "\n" + " The orientation parameters use a fixed-axis representation." "\n" + " In order, the parameters are:" "\n" + " (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)") + double__36 covariance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.msg b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.msg new file mode 100644 index 0000000..111a19c --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovariance.msg @@ -0,0 +1,9 @@ +# This expresses velocity in free space with uncertainty. + +Twist twist + +# Row-major representation of the 6x6 covariance matrix +# The orientation parameters use a fixed-axis representation. +# In order, the parameters are: +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) +float64[36] covariance diff --git a/src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.idl b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.idl new file mode 100644 index 0000000..2c6ccbe --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/TwistWithCovarianceStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/TwistWithCovariance.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents an estimated twist with reference coordinate frame and timestamp.") + struct TwistWithCovarianceStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::TwistWithCovariance twist; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.msg b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.msg new file mode 100644 index 0000000..90b65b1 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/TwistWithCovarianceStamped.msg @@ -0,0 +1,4 @@ +# This represents an estimated twist with reference coordinate frame and timestamp. + +std_msgs/Header header +TwistWithCovariance twist diff --git a/src/ros2/common_interfaces/geometry_msgs/Vector3.idl b/src/ros2/common_interfaces/geometry_msgs/Vector3.idl new file mode 100644 index 0000000..e580bb0 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Vector3.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Vector3.msg +// generated code does not contain a copyright notice + + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents a vector in free space.") + struct Vector3 { + @verbatim (language="comment", text= + " This is semantically different than a point." "\n" + " A vector is always anchored at the origin." "\n" + " When a transform is applied to a vector, only the rotational component is applied.") + double x; + + double y; + + double z; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Vector3.msg b/src/ros2/common_interfaces/geometry_msgs/Vector3.msg new file mode 100644 index 0000000..b54588e --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Vector3.msg @@ -0,0 +1,9 @@ +# This represents a vector in free space. + +# This is semantically different than a point. +# A vector is always anchored at the origin. +# When a transform is applied to a vector, only the rotational component is applied. + +float64 x +float64 y +float64 z diff --git a/src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.idl b/src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.idl new file mode 100644 index 0000000..1f38088 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Vector3Stamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Vector3.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents a Vector3 with reference coordinate frame and timestamp") + struct Vector3Stamped { + @verbatim (language="comment", text= + " Note that this follows vector semantics with it always anchored at the origin," "\n" + " so the rotational elements of a transform are the only parts applied when transforming.") + std_msgs::msg::Header header; + + geometry_msgs::msg::Vector3 vector; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.msg b/src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.msg new file mode 100644 index 0000000..aab1e0a --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Vector3Stamped.msg @@ -0,0 +1,7 @@ +# This represents a Vector3 with reference coordinate frame and timestamp + +# Note that this follows vector semantics with it always anchored at the origin, +# so the rotational elements of a transform are the only parts applied when transforming. + +std_msgs/Header header +Vector3 vector diff --git a/src/ros2/common_interfaces/geometry_msgs/Wrench.idl b/src/ros2/common_interfaces/geometry_msgs/Wrench.idl new file mode 100644 index 0000000..c351cbd --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Wrench.idl @@ -0,0 +1,17 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/Wrench.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Vector3.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " This represents force in free space, separated into its linear and angular parts.") + struct Wrench { + geometry_msgs::msg::Vector3 force; + + geometry_msgs::msg::Vector3 torque; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/Wrench.msg b/src/ros2/common_interfaces/geometry_msgs/Wrench.msg new file mode 100644 index 0000000..0b8efcc --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/Wrench.msg @@ -0,0 +1,4 @@ +# This represents force in free space, separated into its linear and angular parts. + +Vector3 force +Vector3 torque diff --git a/src/ros2/common_interfaces/geometry_msgs/WrenchStamped.idl b/src/ros2/common_interfaces/geometry_msgs/WrenchStamped.idl new file mode 100644 index 0000000..cb05e33 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/WrenchStamped.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from geometry_msgs/msg/WrenchStamped.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Wrench.idl" +#include "std_msgs/msg/Header.idl" + +module geometry_msgs { + module msg { + @verbatim (language="comment", text= + " A wrench with reference coordinate frame and timestamp") + struct WrenchStamped { + std_msgs::msg::Header header; + + geometry_msgs::msg::Wrench wrench; + }; + }; +}; diff --git a/src/ros2/common_interfaces/geometry_msgs/WrenchStamped.msg b/src/ros2/common_interfaces/geometry_msgs/WrenchStamped.msg new file mode 100644 index 0000000..0d5ebd9 --- /dev/null +++ b/src/ros2/common_interfaces/geometry_msgs/WrenchStamped.msg @@ -0,0 +1,4 @@ +# A wrench with reference coordinate frame and timestamp + +std_msgs/Header header +Wrench wrench diff --git a/src/ros2/common_interfaces/nav_msgs/GetMap.idl b/src/ros2/common_interfaces/nav_msgs/GetMap.idl new file mode 100644 index 0000000..a400daf --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/GetMap.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from nav_msgs/srv/GetMap.srv +// generated code does not contain a copyright notice + +#include "nav_msgs/msg/OccupancyGrid.idl" + +module nav_msgs { + module srv { + @verbatim (language="comment", text= + " Get the map as a nav_msgs/OccupancyGrid") + struct GetMap_Request { + uint8 structure_needs_at_least_one_member; + }; + @verbatim (language="comment", text= + " The current map hosted by this map service.") + struct GetMap_Response { + nav_msgs::msg::OccupancyGrid map; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/GetMap.srv b/src/ros2/common_interfaces/nav_msgs/GetMap.srv new file mode 100644 index 0000000..91be6a7 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/GetMap.srv @@ -0,0 +1,4 @@ +# Get the map as a nav_msgs/OccupancyGrid +--- +# The current map hosted by this map service. +OccupancyGrid map diff --git a/src/ros2/common_interfaces/nav_msgs/GetPlan.idl b/src/ros2/common_interfaces/nav_msgs/GetPlan.idl new file mode 100644 index 0000000..3901c9f --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/GetPlan.idl @@ -0,0 +1,32 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from nav_msgs/srv/GetPlan.srv +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/PoseStamped.idl" +#include "nav_msgs/msg/Path.idl" + +module nav_msgs { + module srv { + @verbatim (language="comment", text= + " Get a plan from the current position to the goal Pose") + struct GetPlan_Request { + @verbatim (language="comment", text= + " The start pose for the plan") + geometry_msgs::msg::PoseStamped start; + + @verbatim (language="comment", text= + " The final pose of the goal position") + geometry_msgs::msg::PoseStamped goal; + + @verbatim (language="comment", text= + " If the goal is obstructed, how many meters the planner can" "\n" + " relax the constraint in x and y before failing.") + float tolerance; + }; + @verbatim (language="comment", text= + " Array of poses from start to goal if one was successfully found.") + struct GetPlan_Response { + nav_msgs::msg::Path plan; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/GetPlan.srv b/src/ros2/common_interfaces/nav_msgs/GetPlan.srv new file mode 100644 index 0000000..689290a --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/GetPlan.srv @@ -0,0 +1,14 @@ +# Get a plan from the current position to the goal Pose + +# The start pose for the plan +geometry_msgs/PoseStamped start + +# The final pose of the goal position +geometry_msgs/PoseStamped goal + +# If the goal is obstructed, how many meters the planner can +# relax the constraint in x and y before failing. +float32 tolerance +--- +# Array of poses from start to goal if one was successfully found. +Path plan diff --git a/src/ros2/common_interfaces/nav_msgs/GridCells.idl b/src/ros2/common_interfaces/nav_msgs/GridCells.idl new file mode 100644 index 0000000..8154dca --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/GridCells.idl @@ -0,0 +1,28 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from nav_msgs/msg/GridCells.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Point.idl" +#include "std_msgs/msg/Header.idl" + +module nav_msgs { + module msg { + @verbatim (language="comment", text= + " An array of cells in a 2D grid") + struct GridCells { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Width of each cell") + float cell_width; + + @verbatim (language="comment", text= + " Height of each cell") + float cell_height; + + @verbatim (language="comment", text= + " Each cell is represented by the Point at the center of the cell") + sequence cells; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/GridCells.msg b/src/ros2/common_interfaces/nav_msgs/GridCells.msg new file mode 100644 index 0000000..7154e6c --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/GridCells.msg @@ -0,0 +1,12 @@ +# An array of cells in a 2D grid + +std_msgs/Header header + +# Width of each cell +float32 cell_width + +# Height of each cell +float32 cell_height + +# Each cell is represented by the Point at the center of the cell +geometry_msgs/Point[] cells diff --git a/src/ros2/common_interfaces/nav_msgs/LoadMap.idl b/src/ros2/common_interfaces/nav_msgs/LoadMap.idl new file mode 100644 index 0000000..33706c7 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/LoadMap.idl @@ -0,0 +1,33 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from nav_msgs/srv/LoadMap.srv +// generated code does not contain a copyright notice + +#include "nav_msgs/msg/OccupancyGrid.idl" + +module nav_msgs { + module srv { + @verbatim (language="comment", text= + " URL of map resource" "\n" + " Can be an absolute path to a file: file:///path/to/maps/floor1.yaml" "\n" + " Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml") + struct LoadMap_Request { + string map_url; + }; + module LoadMap_Response_Constants { + const uint8 RESULT_SUCCESS = 0; + const uint8 RESULT_MAP_DOES_NOT_EXIST = 1; + const uint8 RESULT_INVALID_MAP_DATA = 2; + const uint8 RESULT_INVALID_MAP_METADATA = 3; + const uint8 RESULT_UNDEFINED_FAILURE = 255; + }; + @verbatim (language="comment", text= + " Result code defintions") + struct LoadMap_Response { + @verbatim (language="comment", text= + " Returned map is only valid if result equals RESULT_SUCCESS") + nav_msgs::msg::OccupancyGrid map; + + uint8 result; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/LoadMap.srv b/src/ros2/common_interfaces/nav_msgs/LoadMap.srv new file mode 100644 index 0000000..3b9caaa --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/LoadMap.srv @@ -0,0 +1,15 @@ +# URL of map resource +# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml +# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml +string map_url +--- +# Result code defintions +uint8 RESULT_SUCCESS=0 +uint8 RESULT_MAP_DOES_NOT_EXIST=1 +uint8 RESULT_INVALID_MAP_DATA=2 +uint8 RESULT_INVALID_MAP_METADATA=3 +uint8 RESULT_UNDEFINED_FAILURE=255 + +# Returned map is only valid if result equals RESULT_SUCCESS +nav_msgs/OccupancyGrid map +uint8 result diff --git a/src/ros2/common_interfaces/nav_msgs/MapMetaData.idl b/src/ros2/common_interfaces/nav_msgs/MapMetaData.idl new file mode 100644 index 0000000..6735c85 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/MapMetaData.idl @@ -0,0 +1,38 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from nav_msgs/msg/MapMetaData.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" +#include "geometry_msgs/msg/Pose.idl" + +module nav_msgs { + module msg { + @verbatim (language="comment", text= + " This hold basic information about the characteristics of the OccupancyGrid") + struct MapMetaData { + @verbatim (language="comment", text= + " The time at which the map was loaded") + builtin_interfaces::msg::Time map_load_time; + + @verbatim (language="comment", text= + " The map resolution") + @unit (value="m/cell") + float resolution; + + @verbatim (language="comment", text= + " Map width") + @unit (value="cells") + uint32 width; + + @verbatim (language="comment", text= + " Map height") + @unit (value="cells") + uint32 height; + + @verbatim (language="comment", text= + " The origin of the map [m, m, rad]. This is the real-world pose of the" "\n" + " bottom left corner of cell (0,0) in the map.") + geometry_msgs::msg::Pose origin; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/MapMetaData.msg b/src/ros2/common_interfaces/nav_msgs/MapMetaData.msg new file mode 100644 index 0000000..1c11e29 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/MapMetaData.msg @@ -0,0 +1,17 @@ +# This hold basic information about the characteristics of the OccupancyGrid + +# The time at which the map was loaded +builtin_interfaces/Time map_load_time + +# The map resolution [m/cell] +float32 resolution + +# Map width [cells] +uint32 width + +# Map height [cells] +uint32 height + +# The origin of the map [m, m, rad]. This is the real-world pose of the +# bottom left corner of cell (0,0) in the map. +geometry_msgs/Pose origin diff --git a/src/ros2/common_interfaces/nav_msgs/OccupancyGrid.idl b/src/ros2/common_interfaces/nav_msgs/OccupancyGrid.idl new file mode 100644 index 0000000..5170f21 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/OccupancyGrid.idl @@ -0,0 +1,29 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from nav_msgs/msg/OccupancyGrid.msg +// generated code does not contain a copyright notice + +#include "nav_msgs/msg/MapMetaData.idl" +#include "std_msgs/msg/Header.idl" + +module nav_msgs { + module msg { + @verbatim (language="comment", text= + " This represents a 2-D grid map") + struct OccupancyGrid { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " MetaData for the map") + nav_msgs::msg::MapMetaData info; + + @verbatim (language="comment", text= + " The map data, in row-major order, starting with (0,0)." "\n" + " Cell (1, 0) will be listed second, representing the next cell in the x direction." "\n" + " Cell (0, 1) will be at the index equal to info.width, followed by (1, 1)." "\n" + " The values inside are application dependent, but frequently," "\n" + " 0 represents unoccupied, 1 represents definitely occupied, and" "\n" + " -1 represents unknown.") + sequence data; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/OccupancyGrid.msg b/src/ros2/common_interfaces/nav_msgs/OccupancyGrid.msg new file mode 100644 index 0000000..abbd189 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/OccupancyGrid.msg @@ -0,0 +1,13 @@ +# This represents a 2-D grid map +std_msgs/Header header + +# MetaData for the map +MapMetaData info + +# The map data, in row-major order, starting with (0,0). +# Cell (1, 0) will be listed second, representing the next cell in the x direction. +# Cell (0, 1) will be at the index equal to info.width, followed by (1, 1). +# The values inside are application dependent, but frequently, +# 0 represents unoccupied, 1 represents definitely occupied, and +# -1 represents unknown. +int8[] data diff --git a/src/ros2/common_interfaces/nav_msgs/Odometry.idl b/src/ros2/common_interfaces/nav_msgs/Odometry.idl new file mode 100644 index 0000000..4ab6391 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/Odometry.idl @@ -0,0 +1,33 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from nav_msgs/msg/Odometry.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/PoseWithCovariance.idl" +#include "geometry_msgs/msg/TwistWithCovariance.idl" +#include "std_msgs/msg/Header.idl" + +module nav_msgs { + module msg { + @verbatim (language="comment", text= + " This represents an estimate of a position and velocity in free space." "\n" + " The pose in this message should be specified in the coordinate frame given by header.frame_id" "\n" + " The twist in this message should be specified in the coordinate frame given by the child_frame_id") + struct Odometry { + @verbatim (language="comment", text= + " Includes the frame id of the pose parent.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Frame id the pose points to. The twist is in this coordinate frame.") + string child_frame_id; + + @verbatim (language="comment", text= + " Estimated pose that is typically relative to a fixed world frame.") + geometry_msgs::msg::PoseWithCovariance pose; + + @verbatim (language="comment", text= + " Estimated linear and angular velocity relative to child_frame_id.") + geometry_msgs::msg::TwistWithCovariance twist; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/Odometry.msg b/src/ros2/common_interfaces/nav_msgs/Odometry.msg new file mode 100644 index 0000000..7186f06 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/Odometry.msg @@ -0,0 +1,15 @@ +# This represents an estimate of a position and velocity in free space. +# The pose in this message should be specified in the coordinate frame given by header.frame_id +# The twist in this message should be specified in the coordinate frame given by the child_frame_id + +# Includes the frame id of the pose parent. +std_msgs/Header header + +# Frame id the pose points to. The twist is in this coordinate frame. +string child_frame_id + +# Estimated pose that is typically relative to a fixed world frame. +geometry_msgs/PoseWithCovariance pose + +# Estimated linear and angular velocity relative to child_frame_id. +geometry_msgs/TwistWithCovariance twist diff --git a/src/ros2/common_interfaces/nav_msgs/Path.idl b/src/ros2/common_interfaces/nav_msgs/Path.idl new file mode 100644 index 0000000..8351355 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/Path.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from nav_msgs/msg/Path.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/PoseStamped.idl" +#include "std_msgs/msg/Header.idl" + +module nav_msgs { + module msg { + @verbatim (language="comment", text= + " An array of poses that represents a Path for a robot to follow.") + struct Path { + @verbatim (language="comment", text= + " Indicates the frame_id of the path.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Array of poses to follow.") + sequence poses; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/Path.msg b/src/ros2/common_interfaces/nav_msgs/Path.msg new file mode 100644 index 0000000..8be8de7 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/Path.msg @@ -0,0 +1,7 @@ +# An array of poses that represents a Path for a robot to follow. + +# Indicates the frame_id of the path. +std_msgs/Header header + +# Array of poses to follow. +geometry_msgs/PoseStamped[] poses diff --git a/src/ros2/common_interfaces/nav_msgs/SetMap.idl b/src/ros2/common_interfaces/nav_msgs/SetMap.idl new file mode 100644 index 0000000..65956ff --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/SetMap.idl @@ -0,0 +1,27 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from nav_msgs/srv/SetMap.srv +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/PoseWithCovarianceStamped.idl" +#include "nav_msgs/msg/OccupancyGrid.idl" + +module nav_msgs { + module srv { + @verbatim (language="comment", text= + " Set a new map together with an initial pose") + struct SetMap_Request { + @verbatim (language="comment", text= + " Requested 2D map to be set.") + nav_msgs::msg::OccupancyGrid map; + + @verbatim (language="comment", text= + " Estimated initial pose when setting new map.") + geometry_msgs::msg::PoseWithCovarianceStamped initial_pose; + }; + struct SetMap_Response { + @verbatim (language="comment", text= + " True if the map was successfully set, false otherwise.") + boolean success; + }; + }; +}; diff --git a/src/ros2/common_interfaces/nav_msgs/SetMap.srv b/src/ros2/common_interfaces/nav_msgs/SetMap.srv new file mode 100644 index 0000000..5270d45 --- /dev/null +++ b/src/ros2/common_interfaces/nav_msgs/SetMap.srv @@ -0,0 +1,11 @@ +# Set a new map together with an initial pose + +# Requested 2D map to be set. +nav_msgs/OccupancyGrid map + +# Estimated initial pose when setting new map. +geometry_msgs/PoseWithCovarianceStamped initial_pose +--- + +# True if the map was successfully set, false otherwise. +bool success diff --git a/src/ros2/common_interfaces/sensor_msgs/BatteryState.idl b/src/ros2/common_interfaces/sensor_msgs/BatteryState.idl new file mode 100644 index 0000000..f01cf44 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/BatteryState.idl @@ -0,0 +1,98 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/BatteryState.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + module BatteryState_Constants { + const uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0; + const uint8 POWER_SUPPLY_STATUS_CHARGING = 1; + const uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2; + const uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3; + const uint8 POWER_SUPPLY_STATUS_FULL = 4; + const uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0; + const uint8 POWER_SUPPLY_HEALTH_GOOD = 1; + const uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2; + const uint8 POWER_SUPPLY_HEALTH_DEAD = 3; + const uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4; + const uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5; + const uint8 POWER_SUPPLY_HEALTH_COLD = 6; + const uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7; + const uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8; + const uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0; + const uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1; + const uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2; + const uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3; + const uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4; + const uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5; + const uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6; + }; + struct BatteryState { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Voltage in Volts (Mandatory)") + float voltage; + + @verbatim (language="comment", text= + " Temperature in Degrees Celsius (If unmeasured NaN)") + float temperature; + + @verbatim (language="comment", text= + " Negative when discharging (A) (If unmeasured NaN)") + float current; + + @verbatim (language="comment", text= + " Current charge in Ah (If unmeasured NaN)") + float charge; + + @verbatim (language="comment", text= + " Capacity in Ah (last full capacity) (If unmeasured NaN)") + float capacity; + + @verbatim (language="comment", text= + " Capacity in Ah (design capacity) (If unmeasured NaN)") + float design_capacity; + + @verbatim (language="comment", text= + " Charge percentage on 0 to 1 range (If unmeasured NaN)") + float percentage; + + @verbatim (language="comment", text= + " The charging status as reported. Values defined above") + uint8 power_supply_status; + + @verbatim (language="comment", text= + " The battery health metric. Values defined above") + uint8 power_supply_health; + + @verbatim (language="comment", text= + " The battery chemistry. Values defined above") + uint8 power_supply_technology; + + @verbatim (language="comment", text= + " True if the battery is present") + boolean present; + + @verbatim (language="comment", text= + " An array of individual cell voltages for each cell in the pack" "\n" + " If individual voltages unknown but number of cells known set each to NaN") + sequence cell_voltage; + + @verbatim (language="comment", text= + " An array of individual cell temperatures for each cell in the pack" "\n" + " If individual temperatures unknown but number of cells known set each to NaN") + sequence cell_temperature; + + @verbatim (language="comment", text= + " The location into which the battery is inserted. (slot number or plug)") + string location; + + @verbatim (language="comment", text= + " The best approximation of the battery serial number") + string serial_number; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/BatteryState.msg b/src/ros2/common_interfaces/sensor_msgs/BatteryState.msg new file mode 100644 index 0000000..00bd059 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/BatteryState.msg @@ -0,0 +1,52 @@ + +# Constants are chosen to match the enums in the linux kernel +# defined in include/linux/power_supply.h as of version 3.7 +# The one difference is for style reasons the constants are +# all uppercase not mixed case. + +# Power supply status constants +uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0 +uint8 POWER_SUPPLY_STATUS_CHARGING = 1 +uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2 +uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3 +uint8 POWER_SUPPLY_STATUS_FULL = 4 + +# Power supply health constants +uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0 +uint8 POWER_SUPPLY_HEALTH_GOOD = 1 +uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2 +uint8 POWER_SUPPLY_HEALTH_DEAD = 3 +uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 +uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 +uint8 POWER_SUPPLY_HEALTH_COLD = 6 +uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 +uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 + +# Power supply technology (chemistry) constants +uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 +uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1 +uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2 +uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3 +uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4 +uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5 +uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6 + +std_msgs/Header header +float32 voltage # Voltage in Volts (Mandatory) +float32 temperature # Temperature in Degrees Celsius (If unmeasured NaN) +float32 current # Negative when discharging (A) (If unmeasured NaN) +float32 charge # Current charge in Ah (If unmeasured NaN) +float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN) +float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN) +float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN) +uint8 power_supply_status # The charging status as reported. Values defined above +uint8 power_supply_health # The battery health metric. Values defined above +uint8 power_supply_technology # The battery chemistry. Values defined above +bool present # True if the battery is present + +float32[] cell_voltage # An array of individual cell voltages for each cell in the pack + # If individual voltages unknown but number of cells known set each to NaN +float32[] cell_temperature # An array of individual cell temperatures for each cell in the pack + # If individual temperatures unknown but number of cells known set each to NaN +string location # The location into which the battery is inserted. (slot number or plug) +string serial_number # The best approximation of the battery serial number diff --git a/src/ros2/common_interfaces/sensor_msgs/CameraInfo.idl b/src/ros2/common_interfaces/sensor_msgs/CameraInfo.idl new file mode 100644 index 0000000..ae42d8e --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/CameraInfo.idl @@ -0,0 +1,156 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/CameraInfo.msg +// generated code does not contain a copyright notice + +#include "sensor_msgs/msg/RegionOfInterest.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + typedef double double__9[9]; + typedef double double__12[12]; + @verbatim (language="comment", text= + " This message defines meta information for a camera. It should be in a" "\n" + " camera namespace on topic \"camera_info\" and accompanied by up to five" "\n" + " image topics named:" "\n" + "" "\n" + " image_raw - raw data from the camera driver, possibly Bayer encoded" "\n" + " image - monochrome, distorted" "\n" + " image_color - color, distorted" "\n" + " image_rect - monochrome, rectified" "\n" + " image_rect_color - color, rectified" "\n" + "" "\n" + " The image_pipeline contains packages (image_proc, stereo_image_proc)" "\n" + " for producing the four processed image topics from image_raw and" "\n" + " camera_info. The meaning of the camera parameters are described in" "\n" + " detail at http://www.ros.org/wiki/image_pipeline/CameraInfo." "\n" + "" "\n" + " The image_geometry package provides a user-friendly interface to" "\n" + " common operations using this meta information. If you want to, e.g.," "\n" + " project a 3d point into image coordinates, we strongly recommend" "\n" + " using image_geometry." "\n" + "" "\n" + " If the camera is uncalibrated, the matrices D, K, R, P should be left" "\n" + " zeroed out. In particular, clients may assume that K == 0.0" "\n" + " indicates an uncalibrated camera.") + struct CameraInfo { + @verbatim (language="comment", text= + "######################################################################" "\n" + " Image acquisition info #" "\n" + "######################################################################" "\n" + " Time of image acquisition, camera coordinate frame ID" "\n" + " Header timestamp should be acquisition time of image" "\n" + " Header frame_id should be optical frame of camera" "\n" + " origin of frame should be optical center of camera" "\n" + " +x should point to the right in the image" "\n" + " +y should point down in the image" "\n" + " +z should point into the plane of the image") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + "######################################################################" "\n" + " Calibration Parameters #" "\n" + "######################################################################" "\n" + " These are fixed during camera calibration. Their values will be the #" "\n" + " same in all messages until the camera is recalibrated. Note that #" "\n" + " self-calibrating systems may \"recalibrate\" frequently. #" "\n" + " #" "\n" + " The internal parameters can be used to warp a raw (distorted) image #" "\n" + " to: #" "\n" + " 1. An undistorted image (requires D and K) #" "\n" + " 2. A rectified image (requires D, K, R) #" "\n" + " The projection matrix P projects 3D points into the rectified image.#" "\n" + "######################################################################" "\n" + " The image dimensions with which the camera was calibrated." "\n" + " Normally this will be the full camera resolution in pixels.") + uint32 height; + + uint32 width; + + @verbatim (language="comment", text= + " The distortion model used. Supported models are listed in" "\n" + " sensor_msgs/distortion_models.hpp. For most cameras, \"plumb_bob\" - a" "\n" + " simple model of radial and tangential distortion - is sufficent.") + string distortion_model; + + @verbatim (language="comment", text= + " The distortion parameters, size depending on the distortion model." "\n" + " For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).") + sequence d; + + @verbatim (language="comment", text= + " Intrinsic camera matrix for the raw (distorted) images." "\n" + " [fx 0 cx]" "\n" + " K = [ 0 fy cy]" "\n" + " [ 0 0 1]" "\n" + " Projects 3D points in the camera coordinate frame to 2D pixel" "\n" + " coordinates using the focal lengths (fx, fy) and principal point" "\n" + " (cx, cy)." "\n" + " 3x3 row-major matrix") + double__9 k; + + @verbatim (language="comment", text= + " Rectification matrix (stereo cameras only)" "\n" + " A rotation matrix aligning the camera coordinate system to the ideal" "\n" + " stereo image plane so that epipolar lines in both stereo images are" "\n" + " parallel." "\n" + " 3x3 row-major matrix") + double__9 r; + + @verbatim (language="comment", text= + " Projection/camera matrix" "\n" + " [fx' 0 cx' Tx]" "\n" + " P = [ 0 fy' cy' Ty]" "\n" + " [ 0 0 1 0]" "\n" + " By convention, this matrix specifies the intrinsic (camera) matrix" "\n" + " of the processed (rectified) image. That is, the left 3x3 portion" "\n" + " is the normal camera intrinsic matrix for the rectified image." "\n" + " It projects 3D points in the camera coordinate frame to 2D pixel" "\n" + " coordinates using the focal lengths (fx', fy') and principal point" "\n" + " (cx', cy') - these may differ from the values in K." "\n" + " For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will" "\n" + " also have R = the identity and P[1:3,1:3] = K." "\n" + " For a stereo pair, the fourth column [Tx Ty 0]' is related to the" "\n" + " position of the optical center of the second camera in the first" "\n" + " camera's frame. We assume Tz = 0 so both cameras are in the same" "\n" + " stereo image plane. The first camera always has Tx = Ty = 0. For" "\n" + " the right (second) camera of a horizontal stereo pair, Ty = 0 and" "\n" + " Tx = -fx' * B, where B is the baseline between the cameras." "\n" + " Given a 3D point [X Y Z]', the projection (x, y) of the point onto" "\n" + " the rectified image is given by:" "\n" + " [u v w]' = P * [X Y Z 1]'" "\n" + " x = u / w" "\n" + " y = v / w" "\n" + " This holds for both images of a stereo pair." "\n" + " 3x4 row-major matrix") + double__12 p; + + @verbatim (language="comment", text= + "######################################################################" "\n" + " Operational Parameters #" "\n" + "######################################################################" "\n" + " These define the image region actually captured by the camera #" "\n" + " driver. Although they affect the geometry of the output image, they #" "\n" + " may be changed freely without recalibrating the camera. #" "\n" + "######################################################################" "\n" + " Binning refers here to any camera setting which combines rectangular" "\n" + " neighborhoods of pixels into larger \"super-pixels.\" It reduces the" "\n" + " resolution of the output image to" "\n" + " (width / binning_x) x (height / binning_y)." "\n" + " The default values binning_x = binning_y = 0 is considered the same" "\n" + " as binning_x = binning_y = 1 (no subsampling).") + uint32 binning_x; + + uint32 binning_y; + + @verbatim (language="comment", text= + " Region of interest (subwindow of full camera resolution), given in" "\n" + " full resolution (unbinned) image coordinates. A particular ROI" "\n" + " always denotes the same window of pixels on the camera sensor," "\n" + " regardless of binning settings." "\n" + " The default setting of roi (all values 0) is considered the same as" "\n" + " full resolution (roi.width = width, roi.height = height).") + sensor_msgs::msg::RegionOfInterest roi; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/CameraInfo.msg b/src/ros2/common_interfaces/sensor_msgs/CameraInfo.msg new file mode 100644 index 0000000..f2e7b06 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/CameraInfo.msg @@ -0,0 +1,131 @@ +# This message defines meta information for a camera. It should be in a +# camera namespace on topic "camera_info" and accompanied by up to five +# image topics named: +# +# image_raw - raw data from the camera driver, possibly Bayer encoded +# image - monochrome, distorted +# image_color - color, distorted +# image_rect - monochrome, rectified +# image_rect_color - color, rectified +# +# The image_pipeline contains packages (image_proc, stereo_image_proc) +# for producing the four processed image topics from image_raw and +# camera_info. The meaning of the camera parameters are described in +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. +# +# The image_geometry package provides a user-friendly interface to +# common operations using this meta information. If you want to, e.g., +# project a 3d point into image coordinates, we strongly recommend +# using image_geometry. +# +# If the camera is uncalibrated, the matrices D, K, R, P should be left +# zeroed out. In particular, clients may assume that K[0] == 0.0 +# indicates an uncalibrated camera. + +####################################################################### +# Image acquisition info # +####################################################################### + +# Time of image acquisition, camera coordinate frame ID +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of camera + # +x should point to the right in the image + # +y should point down in the image + # +z should point into the plane of the image + + +####################################################################### +# Calibration Parameters # +####################################################################### +# These are fixed during camera calibration. Their values will be the # +# same in all messages until the camera is recalibrated. Note that # +# self-calibrating systems may "recalibrate" frequently. # +# # +# The internal parameters can be used to warp a raw (distorted) image # +# to: # +# 1. An undistorted image (requires D and K) # +# 2. A rectified image (requires D, K, R) # +# The projection matrix P projects 3D points into the rectified image.# +####################################################################### + +# The image dimensions with which the camera was calibrated. +# Normally this will be the full camera resolution in pixels. +uint32 height +uint32 width + +# The distortion model used. Supported models are listed in +# sensor_msgs/distortion_models.hpp. For most cameras, "plumb_bob" - a +# simple model of radial and tangential distortion - is sufficent. +string distortion_model + +# The distortion parameters, size depending on the distortion model. +# For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). +float64[] d + +# Intrinsic camera matrix for the raw (distorted) images. +# [fx 0 cx] +# K = [ 0 fy cy] +# [ 0 0 1] +# Projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx, fy) and principal point +# (cx, cy). +float64[9] k # 3x3 row-major matrix + +# Rectification matrix (stereo cameras only) +# A rotation matrix aligning the camera coordinate system to the ideal +# stereo image plane so that epipolar lines in both stereo images are +# parallel. +float64[9] r # 3x3 row-major matrix + +# Projection/camera matrix +# [fx' 0 cx' Tx] +# P = [ 0 fy' cy' Ty] +# [ 0 0 1 0] +# By convention, this matrix specifies the intrinsic (camera) matrix +# of the processed (rectified) image. That is, the left 3x3 portion +# is the normal camera intrinsic matrix for the rectified image. +# It projects 3D points in the camera coordinate frame to 2D pixel +# coordinates using the focal lengths (fx', fy') and principal point +# (cx', cy') - these may differ from the values in K. +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will +# also have R = the identity and P[1:3,1:3] = K. +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the +# position of the optical center of the second camera in the first +# camera's frame. We assume Tz = 0 so both cameras are in the same +# stereo image plane. The first camera always has Tx = Ty = 0. For +# the right (second) camera of a horizontal stereo pair, Ty = 0 and +# Tx = -fx' * B, where B is the baseline between the cameras. +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto +# the rectified image is given by: +# [u v w]' = P * [X Y Z 1]' +# x = u / w +# y = v / w +# This holds for both images of a stereo pair. +float64[12] p # 3x4 row-major matrix + + +####################################################################### +# Operational Parameters # +####################################################################### +# These define the image region actually captured by the camera # +# driver. Although they affect the geometry of the output image, they # +# may be changed freely without recalibrating the camera. # +####################################################################### + +# Binning refers here to any camera setting which combines rectangular +# neighborhoods of pixels into larger "super-pixels." It reduces the +# resolution of the output image to +# (width / binning_x) x (height / binning_y). +# The default values binning_x = binning_y = 0 is considered the same +# as binning_x = binning_y = 1 (no subsampling). +uint32 binning_x +uint32 binning_y + +# Region of interest (subwindow of full camera resolution), given in +# full resolution (unbinned) image coordinates. A particular ROI +# always denotes the same window of pixels on the camera sensor, +# regardless of binning settings. +# The default setting of roi (all values 0) is considered the same as +# full resolution (roi.width = width, roi.height = height). +RegionOfInterest roi diff --git a/src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.idl b/src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.idl new file mode 100644 index 0000000..8d862c5 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.idl @@ -0,0 +1,37 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/ChannelFloat32.msg +// generated code does not contain a copyright notice + + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This message is used by the PointCloud message to hold optional data" "\n" + " associated with each point in the cloud. The length of the values" "\n" + " array should be the same as the length of the points array in the" "\n" + " PointCloud, and each value should be associated with the corresponding" "\n" + " point." "\n" + "" "\n" + " Channel names in existing practice include:" "\n" + " \"u\", \"v\" - row and column (respectively) in the left stereo image." "\n" + " This is opposite to usual conventions but remains for" "\n" + " historical reasons. The newer PointCloud2 message has no" "\n" + " such problem." "\n" + " \"rgb\" - For point clouds produced by color stereo cameras. uint8" "\n" + " (R,G,B) values packed into the least significant 24 bits," "\n" + " in order." "\n" + " \"intensity\" - laser or pixel intensity." "\n" + " \"distance\"") + struct ChannelFloat32 { + @verbatim (language="comment", text= + " The channel name should give semantics of the channel (e.g." "\n" + " \"intensity\" instead of \"value\").") + string name; + + @verbatim (language="comment", text= + " The values array should be 1-1 with the elements of the associated" "\n" + " PointCloud.") + sequence values; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.msg b/src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.msg new file mode 100644 index 0000000..0518d8d --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/ChannelFloat32.msg @@ -0,0 +1,24 @@ +# This message is used by the PointCloud message to hold optional data +# associated with each point in the cloud. The length of the values +# array should be the same as the length of the points array in the +# PointCloud, and each value should be associated with the corresponding +# point. +# +# Channel names in existing practice include: +# "u", "v" - row and column (respectively) in the left stereo image. +# This is opposite to usual conventions but remains for +# historical reasons. The newer PointCloud2 message has no +# such problem. +# "rgb" - For point clouds produced by color stereo cameras. uint8 +# (R,G,B) values packed into the least significant 24 bits, +# in order. +# "intensity" - laser or pixel intensity. +# "distance" + +# The channel name should give semantics of the channel (e.g. +# "intensity" instead of "value"). +string name + +# The values array should be 1-1 with the elements of the associated +# PointCloud. +float32[] values diff --git a/src/ros2/common_interfaces/sensor_msgs/CompressedImage.idl b/src/ros2/common_interfaces/sensor_msgs/CompressedImage.idl new file mode 100644 index 0000000..f7e6014 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/CompressedImage.idl @@ -0,0 +1,32 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/CompressedImage.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This message contains a compressed image.") + struct CompressedImage { + @verbatim (language="comment", text= + " Header timestamp should be acquisition time of image" "\n" + " Header frame_id should be optical frame of camera" "\n" + " origin of frame should be optical center of cameara" "\n" + " +x should point to the right in the image" "\n" + " +y should point down in the image" "\n" + " +z should point into to plane of the image") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Specifies the format of the data" "\n" + " Acceptable values:" "\n" + " jpeg, png, tiff") + string format; + + @verbatim (language="comment", text= + " Compressed image buffer") + sequence data; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/CompressedImage.msg b/src/ros2/common_interfaces/sensor_msgs/CompressedImage.msg new file mode 100644 index 0000000..0b0b4f5 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/CompressedImage.msg @@ -0,0 +1,14 @@ +# This message contains a compressed image. + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + +string format # Specifies the format of the data + # Acceptable values: + # jpeg, png, tiff + +uint8[] data # Compressed image buffer diff --git a/src/ros2/common_interfaces/sensor_msgs/FluidPressure.idl b/src/ros2/common_interfaces/sensor_msgs/FluidPressure.idl new file mode 100644 index 0000000..ddbda97 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/FluidPressure.idl @@ -0,0 +1,30 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/FluidPressure.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Single pressure reading. This message is appropriate for measuring the" "\n" + " pressure inside of a fluid (air, water, etc). This also includes" "\n" + " atmospheric or barometric pressure." "\n" + "" "\n" + " This message is not appropriate for force/pressure contact sensors.") + struct FluidPressure { + @verbatim (language="comment", text= + " timestamp of the measurement" "\n" + " frame_id is the location of the pressure sensor") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Absolute pressure reading in Pascals.") + double fluid_pressure; + + @verbatim (language="comment", text= + " 0 is interpreted as variance unknown") + double variance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/FluidPressure.msg b/src/ros2/common_interfaces/sensor_msgs/FluidPressure.msg new file mode 100644 index 0000000..2350d61 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/FluidPressure.msg @@ -0,0 +1,12 @@ +# Single pressure reading. This message is appropriate for measuring the +# pressure inside of a fluid (air, water, etc). This also includes +# atmospheric or barometric pressure. +# +# This message is not appropriate for force/pressure contact sensors. + +std_msgs/Header header # timestamp of the measurement + # frame_id is the location of the pressure sensor + +float64 fluid_pressure # Absolute pressure reading in Pascals. + +float64 variance # 0 is interpreted as variance unknown diff --git a/src/ros2/common_interfaces/sensor_msgs/Illuminance.idl b/src/ros2/common_interfaces/sensor_msgs/Illuminance.idl new file mode 100644 index 0000000..4e2a7b4 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Illuminance.idl @@ -0,0 +1,38 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/Illuminance.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Single photometric illuminance measurement. Light should be assumed to be" "\n" + " measured along the sensor's x-axis (the area of detection is the y-z plane)." "\n" + " The illuminance should have a 0 or positive value and be received with" "\n" + " the sensor's +X axis pointing toward the light source." "\n" + "" "\n" + " Photometric illuminance is the measure of the human eye's sensitivity of the" "\n" + " intensity of light encountering or passing through a surface." "\n" + "" "\n" + " All other Photometric and Radiometric measurements should not use this message." "\n" + " This message cannot represent:" "\n" + " - Luminous intensity (candela/light source output)" "\n" + " - Luminance (nits/light output per area)" "\n" + " - Irradiance (watt/area), etc.") + struct Illuminance { + @verbatim (language="comment", text= + " timestamp is the time the illuminance was measured" "\n" + " frame_id is the location and direction of the reading") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Measurement of the Photometric Illuminance in Lux.") + double illuminance; + + @verbatim (language="comment", text= + " 0 is interpreted as variance unknown") + double variance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/Illuminance.msg b/src/ros2/common_interfaces/sensor_msgs/Illuminance.msg new file mode 100644 index 0000000..43cd8e7 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Illuminance.msg @@ -0,0 +1,20 @@ +# Single photometric illuminance measurement. Light should be assumed to be +# measured along the sensor's x-axis (the area of detection is the y-z plane). +# The illuminance should have a 0 or positive value and be received with +# the sensor's +X axis pointing toward the light source. +# +# Photometric illuminance is the measure of the human eye's sensitivity of the +# intensity of light encountering or passing through a surface. +# +# All other Photometric and Radiometric measurements should not use this message. +# This message cannot represent: +# - Luminous intensity (candela/light source output) +# - Luminance (nits/light output per area) +# - Irradiance (watt/area), etc. + +std_msgs/Header header # timestamp is the time the illuminance was measured + # frame_id is the location and direction of the reading + +float64 illuminance # Measurement of the Photometric Illuminance in Lux. + +float64 variance # 0 is interpreted as variance unknown diff --git a/src/ros2/common_interfaces/sensor_msgs/Image.idl b/src/ros2/common_interfaces/sensor_msgs/Image.idl new file mode 100644 index 0000000..f1bbcf6 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Image.idl @@ -0,0 +1,54 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/Image.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This message contains an uncompressed image" "\n" + " (0, 0) is at top-left corner of image") + struct Image { + @verbatim (language="comment", text= + " Header timestamp should be acquisition time of image" "\n" + " Header frame_id should be optical frame of camera" "\n" + " origin of frame should be optical center of cameara" "\n" + " +x should point to the right in the image" "\n" + " +y should point down in the image" "\n" + " +z should point into to plane of the image" "\n" + " If the frame_id here and the frame_id of the CameraInfo" "\n" + " message associated with the image conflict" "\n" + " the behavior is undefined") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " image height, that is, number of rows") + uint32 height; + + @verbatim (language="comment", text= + " image width, that is, number of columns") + uint32 width; + + @verbatim (language="comment", text= + " The legal values for encoding are in file src/image_encodings.cpp" "\n" + " If you want to standardize a new string format, join" "\n" + " ros-users@lists.ros.org and send an email proposing a new encoding." "\n" + " Encoding of pixels -- channel meaning, ordering, size" "\n" + " taken from the list of strings in include/sensor_msgs/image_encodings.hpp") + string encoding; + + @verbatim (language="comment", text= + " is this data bigendian?") + uint8 is_bigendian; + + @verbatim (language="comment", text= + " Full row length in bytes") + uint32 step; + + @verbatim (language="comment", text= + " actual matrix data, size is (step * rows)") + sequence data; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/Image.msg b/src/ros2/common_interfaces/sensor_msgs/Image.msg new file mode 100644 index 0000000..daf8dde --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Image.msg @@ -0,0 +1,26 @@ +# This message contains an uncompressed image +# (0, 0) is at top-left corner of image + +std_msgs/Header header # Header timestamp should be acquisition time of image + # Header frame_id should be optical frame of camera + # origin of frame should be optical center of cameara + # +x should point to the right in the image + # +y should point down in the image + # +z should point into to plane of the image + # If the frame_id here and the frame_id of the CameraInfo + # message associated with the image conflict + # the behavior is undefined + +uint32 height # image height, that is, number of rows +uint32 width # image width, that is, number of columns + +# The legal values for encoding are in file src/image_encodings.cpp +# If you want to standardize a new string format, join +# ros-users@lists.ros.org and send an email proposing a new encoding. + +string encoding # Encoding of pixels -- channel meaning, ordering, size + # taken from the list of strings in include/sensor_msgs/image_encodings.hpp + +uint8 is_bigendian # is this data bigendian? +uint32 step # Full row length in bytes +uint8[] data # actual matrix data, size is (step * rows) diff --git a/src/ros2/common_interfaces/sensor_msgs/Imu.idl b/src/ros2/common_interfaces/sensor_msgs/Imu.idl new file mode 100644 index 0000000..51815a6 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Imu.idl @@ -0,0 +1,48 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/Imu.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Quaternion.idl" +#include "geometry_msgs/msg/Vector3.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + typedef double double__9[9]; + @verbatim (language="comment", text= + " This is a message to hold data from an IMU (Inertial Measurement Unit)" "\n" + "" "\n" + " Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec" "\n" + "" "\n" + " If the covariance of the measurement is known, it should be filled in (if all you know is the" "\n" + " variance of each measurement, e.g. from the datasheet, just put those along the diagonal)" "\n" + " A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the" "\n" + " data a covariance will have to be assumed or gotten from some other source" "\n" + "" "\n" + " If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an" "\n" + " orientation estimate), please set element 0 of the associated covariance matrix to -1" "\n" + " If you are interpreting this message, please check for a value of -1 in the first element of each" "\n" + " covariance matrix, and disregard the associated estimate.") + struct Imu { + std_msgs::msg::Header header; + + geometry_msgs::msg::Quaternion orientation; + + @verbatim (language="comment", text= + " Row major about x, y, z axes") + double__9 orientation_covariance; + + geometry_msgs::msg::Vector3 angular_velocity; + + @verbatim (language="comment", text= + " Row major about x, y, z axes") + double__9 angular_velocity_covariance; + + geometry_msgs::msg::Vector3 linear_acceleration; + + @verbatim (language="comment", text= + " Row major x, y z") + double__9 linear_acceleration_covariance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/Imu.msg b/src/ros2/common_interfaces/sensor_msgs/Imu.msg new file mode 100644 index 0000000..8d8a6bd --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Imu.msg @@ -0,0 +1,24 @@ +# This is a message to hold data from an IMU (Inertial Measurement Unit) +# +# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec +# +# If the covariance of the measurement is known, it should be filled in (if all you know is the +# variance of each measurement, e.g. from the datasheet, just put those along the diagonal) +# A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the +# data a covariance will have to be assumed or gotten from some other source +# +# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an +# orientation estimate), please set element 0 of the associated covariance matrix to -1 +# If you are interpreting this message, please check for a value of -1 in the first element of each +# covariance matrix, and disregard the associated estimate. + +std_msgs/Header header + +geometry_msgs/Quaternion orientation +float64[9] orientation_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 angular_velocity +float64[9] angular_velocity_covariance # Row major about x, y, z axes + +geometry_msgs/Vector3 linear_acceleration +float64[9] linear_acceleration_covariance # Row major x, y z diff --git a/src/ros2/common_interfaces/sensor_msgs/JointState.idl b/src/ros2/common_interfaces/sensor_msgs/JointState.idl new file mode 100644 index 0000000..bd6369a --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/JointState.idl @@ -0,0 +1,40 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/JointState.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This is a message that holds data to describe the state of a set of torque controlled joints." "\n" + "" "\n" + " The state of each joint (revolute or prismatic) is defined by:" "\n" + " * the position of the joint (rad or m)," "\n" + " * the velocity of the joint (rad/s or m/s) and" "\n" + " * the effort that is applied in the joint (Nm or N)." "\n" + "" "\n" + " Each joint is uniquely identified by its name" "\n" + " The header specifies the time at which the joint states were recorded. All the joint states" "\n" + " in one message have to be recorded at the same time." "\n" + "" "\n" + " This message consists of a multiple arrays, one for each part of the joint state." "\n" + " The goal is to make each of the fields optional. When e.g. your joints have no" "\n" + " effort associated with them, you can leave the effort array empty." "\n" + "" "\n" + " All arrays in this message should have the same size, or be empty." "\n" + " This is the only way to uniquely associate the joint name with the correct" "\n" + " states.") + struct JointState { + std_msgs::msg::Header header; + + sequence name; + + sequence position; + + sequence velocity; + + sequence effort; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/JointState.msg b/src/ros2/common_interfaces/sensor_msgs/JointState.msg new file mode 100644 index 0000000..ffaa9bf --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/JointState.msg @@ -0,0 +1,25 @@ +# This is a message that holds data to describe the state of a set of torque controlled joints. +# +# The state of each joint (revolute or prismatic) is defined by: +# * the position of the joint (rad or m), +# * the velocity of the joint (rad/s or m/s) and +# * the effort that is applied in the joint (Nm or N). +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# effort associated with them, you can leave the effort array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + +std_msgs/Header header + +string[] name +float64[] position +float64[] velocity +float64[] effort diff --git a/src/ros2/common_interfaces/sensor_msgs/Joy.idl b/src/ros2/common_interfaces/sensor_msgs/Joy.idl new file mode 100644 index 0000000..fda03c6 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Joy.idl @@ -0,0 +1,25 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/Joy.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Reports the state of a joystick's axes and buttons.") + struct Joy { + @verbatim (language="comment", text= + " The timestamp is the time at which data is received from the joystick.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " The axes measurements from a joystick.") + sequence axes; + + @verbatim (language="comment", text= + " The buttons measurements from a joystick.") + sequence buttons; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/Joy.msg b/src/ros2/common_interfaces/sensor_msgs/Joy.msg new file mode 100644 index 0000000..ca7801f --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Joy.msg @@ -0,0 +1,10 @@ +# Reports the state of a joystick's axes and buttons. + +# The timestamp is the time at which data is received from the joystick. +std_msgs/Header header + +# The axes measurements from a joystick. +float32[] axes + +# The buttons measurements from a joystick. +int32[] buttons diff --git a/src/ros2/common_interfaces/sensor_msgs/JoyFeedback.idl b/src/ros2/common_interfaces/sensor_msgs/JoyFeedback.idl new file mode 100644 index 0000000..543fa48 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/JoyFeedback.idl @@ -0,0 +1,29 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/JoyFeedback.msg +// generated code does not contain a copyright notice + + +module sensor_msgs { + module msg { + module JoyFeedback_Constants { + const uint8 TYPE_LED = 0; + const uint8 TYPE_RUMBLE = 1; + const uint8 TYPE_BUZZER = 2; + }; + @verbatim (language="comment", text= + " Declare of the type of feedback") + struct JoyFeedback { + uint8 type; + + @verbatim (language="comment", text= + " This will hold an id number for each type of each feedback." "\n" + " Example, the first led would be id=0, the second would be id=1") + uint8 id; + + @verbatim (language="comment", text= + " Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is" "\n" + " actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on.") + float intensity; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/JoyFeedback.msg b/src/ros2/common_interfaces/sensor_msgs/JoyFeedback.msg new file mode 100644 index 0000000..153cc09 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/JoyFeedback.msg @@ -0,0 +1,14 @@ +# Declare of the type of feedback +uint8 TYPE_LED = 0 +uint8 TYPE_RUMBLE = 1 +uint8 TYPE_BUZZER = 2 + +uint8 type + +# This will hold an id number for each type of each feedback. +# Example, the first led would be id=0, the second would be id=1 +uint8 id + +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. +float32 intensity diff --git a/src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.idl b/src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.idl new file mode 100644 index 0000000..e202b30 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.idl @@ -0,0 +1,15 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/JoyFeedbackArray.msg +// generated code does not contain a copyright notice + +#include "sensor_msgs/msg/JoyFeedback.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This message publishes values for multiple feedback at once.") + struct JoyFeedbackArray { + sequence array; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.msg b/src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.msg new file mode 100644 index 0000000..f6981b8 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/JoyFeedbackArray.msg @@ -0,0 +1,2 @@ +# This message publishes values for multiple feedback at once. +JoyFeedback[] array diff --git a/src/ros2/common_interfaces/sensor_msgs/LaserEcho.idl b/src/ros2/common_interfaces/sensor_msgs/LaserEcho.idl new file mode 100644 index 0000000..f67810e --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/LaserEcho.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/LaserEcho.msg +// generated code does not contain a copyright notice + + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This message is a submessage of MultiEchoLaserScan and is not intended" "\n" + " to be used separately.") + struct LaserEcho { + @verbatim (language="comment", text= + " Multiple values of ranges or intensities." "\n" + " Each array represents data from the same angle increment.") + sequence echoes; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/LaserEcho.msg b/src/ros2/common_interfaces/sensor_msgs/LaserEcho.msg new file mode 100644 index 0000000..cefdecf --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/LaserEcho.msg @@ -0,0 +1,5 @@ +# This message is a submessage of MultiEchoLaserScan and is not intended +# to be used separately. + +float32[] echoes # Multiple values of ranges or intensities. + # Each array represents data from the same angle increment. diff --git a/src/ros2/common_interfaces/sensor_msgs/LaserScan.idl b/src/ros2/common_interfaces/sensor_msgs/LaserScan.idl new file mode 100644 index 0000000..e0ae82a --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/LaserScan.idl @@ -0,0 +1,76 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/LaserScan.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Single scan from a planar laser range-finder" "\n" + "" "\n" + " If you have another ranging device with different behavior (e.g. a sonar" "\n" + " array), please find or create a different message, since applications" "\n" + " will make fairly laser-specific assumptions about this data") + struct LaserScan { + @verbatim (language="comment", text= + " timestamp in the header is the acquisition time of" "\n" + " the first ray in the scan." "\n" + "" "\n" + " in frame frame_id, angles are measured around" "\n" + " the positive Z axis (counterclockwise, if Z is up)" "\n" + " with zero angle being forward along the x axis") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " start angle of the scan") + @unit (value="rad") + float angle_min; + + @verbatim (language="comment", text= + " end angle of the scan") + @unit (value="rad") + float angle_max; + + @verbatim (language="comment", text= + " angular distance between measurements") + @unit (value="rad") + float angle_increment; + + @verbatim (language="comment", text= + " time between measurements - if your scanner" "\n" + " is moving, this will be used in interpolating position" "\n" + " of 3d points") + @unit (value="seconds") + float time_increment; + + @verbatim (language="comment", text= + " time between scans") + @unit (value="seconds") + float scan_time; + + @verbatim (language="comment", text= + " minimum range value") + @unit (value="m") + float range_min; + + @verbatim (language="comment", text= + " maximum range value") + @unit (value="m") + float range_max; + + @verbatim (language="comment", text= + " range data" "\n" + " (Note: values < range_min or > range_max should be discarded)") + @unit (value="m") + sequence ranges; + + @verbatim (language="comment", text= + " intensity data. If your" "\n" + " device does not provide intensities, please leave" "\n" + " the array empty.") + @unit (value="device-specific units") + sequence intensities; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/LaserScan.msg b/src/ros2/common_interfaces/sensor_msgs/LaserScan.msg new file mode 100644 index 0000000..6e5c2a1 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/LaserScan.msg @@ -0,0 +1,30 @@ +# Single scan from a planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +std_msgs/Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +float32[] ranges # range data [m] + # (Note: values < range_min or > range_max should be discarded) +float32[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. diff --git a/src/ros2/common_interfaces/sensor_msgs/MagneticField.idl b/src/ros2/common_interfaces/sensor_msgs/MagneticField.idl new file mode 100644 index 0000000..d58322c --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/MagneticField.idl @@ -0,0 +1,41 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/MagneticField.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Vector3.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + typedef double double__9[9]; + @verbatim (language="comment", text= + " Measurement of the Magnetic Field vector at a specific location." "\n" + "" "\n" + " If the covariance of the measurement is known, it should be filled in." "\n" + " If all you know is the variance of each measurement, e.g. from the datasheet," "\n" + " just put those along the diagonal." "\n" + " A covariance matrix of all zeros will be interpreted as \"covariance unknown\"," "\n" + " and to use the data a covariance will have to be assumed or gotten from some" "\n" + " other source.") + struct MagneticField { + @verbatim (language="comment", text= + " timestamp is the time the" "\n" + " field was measured" "\n" + " frame_id is the location and orientation" "\n" + " of the field measurement") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " x, y, and z components of the" "\n" + " field vector in Tesla" "\n" + " If your sensor does not output 3 axes," "\n" + " put NaNs in the components not reported.") + geometry_msgs::msg::Vector3 magnetic_field; + + @verbatim (language="comment", text= + " Row major about x, y, z axes" "\n" + " 0 is interpreted as variance unknown") + double__9 magnetic_field_covariance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/MagneticField.msg b/src/ros2/common_interfaces/sensor_msgs/MagneticField.msg new file mode 100644 index 0000000..a0468fa --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/MagneticField.msg @@ -0,0 +1,21 @@ +# Measurement of the Magnetic Field vector at a specific location. +# +# If the covariance of the measurement is known, it should be filled in. +# If all you know is the variance of each measurement, e.g. from the datasheet, +# just put those along the diagonal. +# A covariance matrix of all zeros will be interpreted as "covariance unknown", +# and to use the data a covariance will have to be assumed or gotten from some +# other source. + +std_msgs/Header header # timestamp is the time the + # field was measured + # frame_id is the location and orientation + # of the field measurement + +geometry_msgs/Vector3 magnetic_field # x, y, and z components of the + # field vector in Tesla + # If your sensor does not output 3 axes, + # put NaNs in the components not reported. + +float64[9] magnetic_field_covariance # Row major about x, y, z axes + # 0 is interpreted as variance unknown \ No newline at end of file diff --git a/src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.idl b/src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.idl new file mode 100644 index 0000000..e1995a1 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.idl @@ -0,0 +1,44 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/MultiDOFJointState.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Transform.idl" +#include "geometry_msgs/msg/Twist.idl" +#include "geometry_msgs/msg/Wrench.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Representation of state for joints with multiple degrees of freedom," "\n" + " following the structure of JointState which can only represent a single degree of freedom." "\n" + "" "\n" + " It is assumed that a joint in a system corresponds to a transform that gets applied" "\n" + " along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)" "\n" + " and those 3DOF can be expressed as a transformation matrix, and that transformation" "\n" + " matrix can be converted back to (x, y, yaw)" "\n" + "" "\n" + " Each joint is uniquely identified by its name" "\n" + " The header specifies the time at which the joint states were recorded. All the joint states" "\n" + " in one message have to be recorded at the same time." "\n" + "" "\n" + " This message consists of a multiple arrays, one for each part of the joint state." "\n" + " The goal is to make each of the fields optional. When e.g. your joints have no" "\n" + " wrench associated with them, you can leave the wrench array empty." "\n" + "" "\n" + " All arrays in this message should have the same size, or be empty." "\n" + " This is the only way to uniquely associate the joint name with the correct" "\n" + " states.") + struct MultiDOFJointState { + std_msgs::msg::Header header; + + sequence joint_names; + + sequence transforms; + + sequence twist; + + sequence wrench; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.msg b/src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.msg new file mode 100644 index 0000000..59edcef --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/MultiDOFJointState.msg @@ -0,0 +1,26 @@ +# Representation of state for joints with multiple degrees of freedom, +# following the structure of JointState which can only represent a single degree of freedom. +# +# It is assumed that a joint in a system corresponds to a transform that gets applied +# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) +# and those 3DOF can be expressed as a transformation matrix, and that transformation +# matrix can be converted back to (x, y, yaw) +# +# Each joint is uniquely identified by its name +# The header specifies the time at which the joint states were recorded. All the joint states +# in one message have to be recorded at the same time. +# +# This message consists of a multiple arrays, one for each part of the joint state. +# The goal is to make each of the fields optional. When e.g. your joints have no +# wrench associated with them, you can leave the wrench array empty. +# +# All arrays in this message should have the same size, or be empty. +# This is the only way to uniquely associate the joint name with the correct +# states. + +std_msgs/Header header + +string[] joint_names +geometry_msgs/Transform[] transforms +geometry_msgs/Twist[] twist +geometry_msgs/Wrench[] wrench diff --git a/src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.idl b/src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.idl new file mode 100644 index 0000000..0b32483 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.idl @@ -0,0 +1,79 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/MultiEchoLaserScan.msg +// generated code does not contain a copyright notice + +#include "sensor_msgs/msg/LaserEcho.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Single scan from a multi-echo planar laser range-finder" "\n" + "" "\n" + " If you have another ranging device with different behavior (e.g. a sonar" "\n" + " array), please find or create a different message, since applications" "\n" + " will make fairly laser-specific assumptions about this data") + struct MultiEchoLaserScan { + @verbatim (language="comment", text= + " timestamp in the header is the acquisition time of" "\n" + " the first ray in the scan." "\n" + "" "\n" + " in frame frame_id, angles are measured around" "\n" + " the positive Z axis (counterclockwise, if Z is up)" "\n" + " with zero angle being forward along the x axis") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " start angle of the scan") + @unit (value="rad") + float angle_min; + + @verbatim (language="comment", text= + " end angle of the scan") + @unit (value="rad") + float angle_max; + + @verbatim (language="comment", text= + " angular distance between measurements") + @unit (value="rad") + float angle_increment; + + @verbatim (language="comment", text= + " time between measurements - if your scanner" "\n" + " is moving, this will be used in interpolating position" "\n" + " of 3d points") + @unit (value="seconds") + float time_increment; + + @verbatim (language="comment", text= + " time between scans") + @unit (value="seconds") + float scan_time; + + @verbatim (language="comment", text= + " minimum range value") + @unit (value="m") + float range_min; + + @verbatim (language="comment", text= + " maximum range value") + @unit (value="m") + float range_max; + + @verbatim (language="comment", text= + " range data" "\n" + " (Note: NaNs, values < range_min or > range_max should be discarded)" "\n" + " +Inf measurements are out of range" "\n" + " -Inf measurements are too close to determine exact distance.") + @unit (value="m") + sequence ranges; + + @verbatim (language="comment", text= + " intensity data. If your" "\n" + " device does not provide intensities, please leave" "\n" + " the array empty.") + @unit (value="device-specific units") + sequence intensities; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.msg b/src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.msg new file mode 100644 index 0000000..47d1b9f --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/MultiEchoLaserScan.msg @@ -0,0 +1,32 @@ +# Single scan from a multi-echo planar laser range-finder +# +# If you have another ranging device with different behavior (e.g. a sonar +# array), please find or create a different message, since applications +# will make fairly laser-specific assumptions about this data + +std_msgs/Header header # timestamp in the header is the acquisition time of + # the first ray in the scan. + # + # in frame frame_id, angles are measured around + # the positive Z axis (counterclockwise, if Z is up) + # with zero angle being forward along the x axis + +float32 angle_min # start angle of the scan [rad] +float32 angle_max # end angle of the scan [rad] +float32 angle_increment # angular distance between measurements [rad] + +float32 time_increment # time between measurements [seconds] - if your scanner + # is moving, this will be used in interpolating position + # of 3d points +float32 scan_time # time between scans [seconds] + +float32 range_min # minimum range value [m] +float32 range_max # maximum range value [m] + +LaserEcho[] ranges # range data [m] + # (Note: NaNs, values < range_min or > range_max should be discarded) + # +Inf measurements are out of range + # -Inf measurements are too close to determine exact distance. +LaserEcho[] intensities # intensity data [device-specific units]. If your + # device does not provide intensities, please leave + # the array empty. diff --git a/src/ros2/common_interfaces/sensor_msgs/NavSatFix.idl b/src/ros2/common_interfaces/sensor_msgs/NavSatFix.idl new file mode 100644 index 0000000..fcb61e6 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/NavSatFix.idl @@ -0,0 +1,65 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/NavSatFix.msg +// generated code does not contain a copyright notice + +#include "sensor_msgs/msg/NavSatStatus.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + typedef double double__9[9]; + module NavSatFix_Constants { + const uint8 COVARIANCE_TYPE_UNKNOWN = 0; + const uint8 COVARIANCE_TYPE_APPROXIMATED = 1; + const uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2; + const uint8 COVARIANCE_TYPE_KNOWN = 3; + }; + @verbatim (language="comment", text= + " Navigation Satellite fix for any Global Navigation Satellite System" "\n" + "" "\n" + " Specified using the WGS 84 reference ellipsoid") + struct NavSatFix { + @verbatim (language="comment", text= + " header.stamp specifies the ROS time for this measurement (the" "\n" + " corresponding satellite time may be reported using the" "\n" + " sensor_msgs/TimeReference message)." "\n" + "" "\n" + " header.frame_id is the frame of reference reported by the satellite" "\n" + " receiver, usually the location of the antenna. This is a" "\n" + " Euclidean frame relative to the vehicle, not a reference" "\n" + " ellipsoid.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Satellite fix status information.") + sensor_msgs::msg::NavSatStatus status; + + @verbatim (language="comment", text= + " Latitude. Positive is north of equator; negative is south.") + @unit (value="degrees") + double latitude; + + @verbatim (language="comment", text= + " Longitude. Positive is east of prime meridian; negative is west.") + @unit (value="degrees") + double longitude; + + @verbatim (language="comment", text= + " Altitude. Positive is above the WGS 84 ellipsoid" "\n" + " (quiet NaN if no altitude is available).") + @unit (value="m") + double altitude; + + @verbatim (language="comment", text= + " Position covariance defined relative to a tangential plane" "\n" + " through the reported position. The components are East, North, and" "\n" + " Up (ENU), in row-major order." "\n" + "" "\n" + " Beware: this coordinate system exhibits singularities at the poles.") + @unit (value="m^2") + double__9 position_covariance; + + uint8 position_covariance_type; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/NavSatFix.msg b/src/ros2/common_interfaces/sensor_msgs/NavSatFix.msg new file mode 100644 index 0000000..3c4e977 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/NavSatFix.msg @@ -0,0 +1,45 @@ +# Navigation Satellite fix for any Global Navigation Satellite System +# +# Specified using the WGS 84 reference ellipsoid + +# header.stamp specifies the ROS time for this measurement (the +# corresponding satellite time may be reported using the +# sensor_msgs/TimeReference message). +# +# header.frame_id is the frame of reference reported by the satellite +# receiver, usually the location of the antenna. This is a +# Euclidean frame relative to the vehicle, not a reference +# ellipsoid. +std_msgs/Header header + +# Satellite fix status information. +NavSatStatus status + +# Latitude [degrees]. Positive is north of equator; negative is south. +float64 latitude + +# Longitude [degrees]. Positive is east of prime meridian; negative is west. +float64 longitude + +# Altitude [m]. Positive is above the WGS 84 ellipsoid +# (quiet NaN if no altitude is available). +float64 altitude + +# Position covariance [m^2] defined relative to a tangential plane +# through the reported position. The components are East, North, and +# Up (ENU), in row-major order. +# +# Beware: this coordinate system exhibits singularities at the poles. +float64[9] position_covariance + +# If the covariance of the fix is known, fill it in completely. If the +# GPS receiver provides the variance of each measurement, put them +# along the diagonal. If only Dilution of Precision is available, +# estimate an approximate covariance from that. + +uint8 COVARIANCE_TYPE_UNKNOWN = 0 +uint8 COVARIANCE_TYPE_APPROXIMATED = 1 +uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 +uint8 COVARIANCE_TYPE_KNOWN = 3 + +uint8 position_covariance_type diff --git a/src/ros2/common_interfaces/sensor_msgs/NavSatStatus.idl b/src/ros2/common_interfaces/sensor_msgs/NavSatStatus.idl new file mode 100644 index 0000000..927fe38 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/NavSatStatus.idl @@ -0,0 +1,30 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/NavSatStatus.msg +// generated code does not contain a copyright notice + + +module sensor_msgs { + module msg { + module NavSatStatus_Constants { + const int8 STATUS_NO_FIX = -1; + const int8 STATUS_FIX = 0; + const int8 STATUS_SBAS_FIX = 1; + const int8 STATUS_GBAS_FIX = 2; + const uint16 SERVICE_GPS = 1; + const uint16 SERVICE_GLONASS = 2; + const uint16 SERVICE_COMPASS = 4; + const uint16 SERVICE_GALILEO = 8; + }; + @verbatim (language="comment", text= + " Navigation Satellite fix status for any Global Navigation Satellite System." "\n" + "" "\n" + " Whether to output an augmented fix is determined by both the fix" "\n" + " type and the last time differential corrections were received. A" "\n" + " fix is valid when status >= STATUS_FIX.") + struct NavSatStatus { + int8 status; + + uint16 service; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/NavSatStatus.msg b/src/ros2/common_interfaces/sensor_msgs/NavSatStatus.msg new file mode 100644 index 0000000..7d2edc1 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/NavSatStatus.msg @@ -0,0 +1,22 @@ +# Navigation Satellite fix status for any Global Navigation Satellite System. +# +# Whether to output an augmented fix is determined by both the fix +# type and the last time differential corrections were received. A +# fix is valid when status >= STATUS_FIX. + +int8 STATUS_NO_FIX = -1 # unable to fix position +int8 STATUS_FIX = 0 # unaugmented fix +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation + +int8 status + +# Bits defining which Global Navigation Satellite System signals were +# used by the receiver. + +uint16 SERVICE_GPS = 1 +uint16 SERVICE_GLONASS = 2 +uint16 SERVICE_COMPASS = 4 # includes BeiDou. +uint16 SERVICE_GALILEO = 8 + +uint16 service diff --git a/src/ros2/common_interfaces/sensor_msgs/PointCloud.idl b/src/ros2/common_interfaces/sensor_msgs/PointCloud.idl new file mode 100644 index 0000000..fec016e --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/PointCloud.idl @@ -0,0 +1,33 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/PointCloud.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Point32.idl" +#include "sensor_msgs/msg/ChannelFloat32.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + "# THIS MESSAGE IS DEPRECATED AS OF FOXY" "\n" + "# Please use sensor_msgs/PointCloud2") + struct PointCloud { + @verbatim (language="comment", text= + " This message holds a collection of 3d points, plus optional additional" "\n" + " information about each point." "\n" + " Time of sensor data acquisition, coordinate frame ID.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Array of 3d points. Each Point32 should be interpreted as a 3d point" "\n" + " in the frame given in the header.") + sequence points; + + @verbatim (language="comment", text= + " Each channel should have the same number of elements as points array," "\n" + " and the data in each channel should correspond 1:1 with each point." "\n" + " Channel names in common practice are listed in ChannelFloat32.msg.") + sequence channels; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/PointCloud.msg b/src/ros2/common_interfaces/sensor_msgs/PointCloud.msg new file mode 100644 index 0000000..a07d450 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/PointCloud.msg @@ -0,0 +1,17 @@ +## THIS MESSAGE IS DEPRECATED AS OF FOXY +## Please use sensor_msgs/PointCloud2 + +# This message holds a collection of 3d points, plus optional additional +# information about each point. + +# Time of sensor data acquisition, coordinate frame ID. +std_msgs/Header header + +# Array of 3d points. Each Point32 should be interpreted as a 3d point +# in the frame given in the header. +geometry_msgs/Point32[] points + +# Each channel should have the same number of elements as points array, +# and the data in each channel should correspond 1:1 with each point. +# Channel names in common practice are listed in ChannelFloat32.msg. +ChannelFloat32[] channels diff --git a/src/ros2/common_interfaces/sensor_msgs/PointCloud2.idl b/src/ros2/common_interfaces/sensor_msgs/PointCloud2.idl new file mode 100644 index 0000000..a68a24f --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/PointCloud2.idl @@ -0,0 +1,56 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/PointCloud2.msg +// generated code does not contain a copyright notice + +#include "sensor_msgs/msg/PointField.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This message holds a collection of N-dimensional points, which may" "\n" + " contain additional information such as normals, intensity, etc. The" "\n" + " point data is stored as a binary blob, its layout described by the" "\n" + " contents of the \"fields\" array." "\n" + "" "\n" + " The point cloud data may be organized 2d (image-like) or 1d (unordered)." "\n" + " Point clouds organized as 2d images may be produced by camera depth sensors" "\n" + " such as stereo or time-of-flight.") + struct PointCloud2 { + @verbatim (language="comment", text= + " Time of sensor data acquisition, and the coordinate frame ID (for 3d points).") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " 2D structure of the point cloud. If the cloud is unordered, height is" "\n" + " 1 and width is the length of the point cloud.") + uint32 height; + + uint32 width; + + @verbatim (language="comment", text= + " Describes the channels and their layout in the binary data blob.") + sequence fields; + + @verbatim (language="comment", text= + " Is this data bigendian?") + boolean is_bigendian; + + @verbatim (language="comment", text= + " Length of a point in bytes") + uint32 point_step; + + @verbatim (language="comment", text= + " Length of a row in bytes") + uint32 row_step; + + @verbatim (language="comment", text= + " Actual point data, size is (row_step*height)") + sequence data; + + @verbatim (language="comment", text= + " True if there are no invalid points") + boolean is_dense; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/PointCloud2.msg b/src/ros2/common_interfaces/sensor_msgs/PointCloud2.msg new file mode 100644 index 0000000..0b27897 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/PointCloud2.msg @@ -0,0 +1,26 @@ +# This message holds a collection of N-dimensional points, which may +# contain additional information such as normals, intensity, etc. The +# point data is stored as a binary blob, its layout described by the +# contents of the "fields" array. +# +# The point cloud data may be organized 2d (image-like) or 1d (unordered). +# Point clouds organized as 2d images may be produced by camera depth sensors +# such as stereo or time-of-flight. + +# Time of sensor data acquisition, and the coordinate frame ID (for 3d points). +std_msgs/Header header + +# 2D structure of the point cloud. If the cloud is unordered, height is +# 1 and width is the length of the point cloud. +uint32 height +uint32 width + +# Describes the channels and their layout in the binary data blob. +PointField[] fields + +bool is_bigendian # Is this data bigendian? +uint32 point_step # Length of a point in bytes +uint32 row_step # Length of a row in bytes +uint8[] data # Actual point data, size is (row_step*height) + +bool is_dense # True if there are no invalid points diff --git a/src/ros2/common_interfaces/sensor_msgs/PointField.idl b/src/ros2/common_interfaces/sensor_msgs/PointField.idl new file mode 100644 index 0000000..c8e910d --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/PointField.idl @@ -0,0 +1,40 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/PointField.msg +// generated code does not contain a copyright notice + + +module sensor_msgs { + module msg { + module PointField_Constants { + const uint8 INT8 = 1; + const uint8 UINT8 = 2; + const uint8 INT16 = 3; + const uint8 UINT16 = 4; + const uint8 INT32 = 5; + const uint8 UINT32 = 6; + const uint8 FLOAT32 = 7; + const uint8 FLOAT64 = 8; + }; + @verbatim (language="comment", text= + " This message holds the description of one point entry in the" "\n" + " PointCloud2 message format.") + struct PointField { + @verbatim (language="comment", text= + " Common PointField names are x, y, z, intensity, rgb, rgba" "\n" + " Name of field") + string name; + + @verbatim (language="comment", text= + " Offset from start of point struct") + uint32 offset; + + @verbatim (language="comment", text= + " Datatype enumeration, see above") + uint8 datatype; + + @verbatim (language="comment", text= + " How many elements in the field") + uint32 count; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/PointField.msg b/src/ros2/common_interfaces/sensor_msgs/PointField.msg new file mode 100644 index 0000000..920bc4d --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/PointField.msg @@ -0,0 +1,16 @@ +# This message holds the description of one point entry in the +# PointCloud2 message format. +uint8 INT8 = 1 +uint8 UINT8 = 2 +uint8 INT16 = 3 +uint8 UINT16 = 4 +uint8 INT32 = 5 +uint8 UINT32 = 6 +uint8 FLOAT32 = 7 +uint8 FLOAT64 = 8 + +# Common PointField names are x, y, z, intensity, rgb, rgba +string name # Name of field +uint32 offset # Offset from start of point struct +uint8 datatype # Datatype enumeration, see above +uint32 count # How many elements in the field diff --git a/src/ros2/common_interfaces/sensor_msgs/Range.idl b/src/ros2/common_interfaces/sensor_msgs/Range.idl new file mode 100644 index 0000000..25ad028 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Range.idl @@ -0,0 +1,68 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/Range.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + module Range_Constants { + const uint8 ULTRASOUND = 0; + const uint8 INFRARED = 1; + }; + @verbatim (language="comment", text= + " Single range reading from an active ranger that emits energy and reports" "\n" + " one range reading that is valid along an arc at the distance measured." "\n" + " This message is not appropriate for laser scanners. See the LaserScan" "\n" + " message if you are working with a laser scanner." "\n" + "" "\n" + " This message also can represent a fixed-distance (binary) ranger. This" "\n" + " sensor will have min_range===max_range===distance of detection." "\n" + " These sensors follow REP 117 and will output -Inf if the object is detected" "\n" + " and +Inf if the object is outside of the detection range.") + struct Range { + @verbatim (language="comment", text= + " timestamp in the header is the time the ranger" "\n" + " returned the distance reading") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " the type of radiation used by the sensor" "\n" + " (sound, IR, etc)") + @unit (value="enum") + uint8 radiation_type; + + @verbatim (language="comment", text= + " the size of the arc that the distance reading is" "\n" + " valid for" "\n" + " the object causing the range reading may have" "\n" + " been anywhere within -field_of_view/2 and" "\n" + " field_of_view/2 at the measured range." "\n" + " 0 angle corresponds to the x-axis of the sensor.") + @unit (value="rad") + float field_of_view; + + @verbatim (language="comment", text= + " minimum range value") + @unit (value="m") + float min_range; + + @verbatim (language="comment", text= + " maximum range value" "\n" + " Fixed distance rangers require min_range==max_range") + @unit (value="m") + float max_range; + + @verbatim (language="comment", text= + " range data" "\n" + " (Note: values < range_min or > range_max should be discarded)" "\n" + " Fixed distance rangers only output -Inf or +Inf." "\n" + " -Inf represents a detection within fixed distance." "\n" + " (Detection too close to the sensor to quantify)" "\n" + " +Inf represents no detection within the fixed distance." "\n" + " (Object out of range)") + @unit (value="m") + float range; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/Range.msg b/src/ros2/common_interfaces/sensor_msgs/Range.msg new file mode 100644 index 0000000..abb027a --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Range.msg @@ -0,0 +1,39 @@ +# 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. +# This message is not appropriate for laser scanners. See the LaserScan +# message if you are working with a laser scanner. +# +# This message also can represent a fixed-distance (binary) ranger. This +# sensor will have min_range===max_range===distance of detection. +# These sensors follow REP 117 and will output -Inf if the object is detected +# and +Inf if the object is outside of the detection range. + +std_msgs/Header header # timestamp in the header is the time the ranger + # returned the distance reading + +# Radiation type enums +# If you want a value added to this list, send an email to the ros-users list +uint8 ULTRASOUND=0 +uint8 INFRARED=1 + +uint8 radiation_type # the type of radiation used by the sensor + # (sound, IR, etc) [enum] + +float32 field_of_view # the size of the arc that the distance reading is + # valid for [rad] + # the object causing the range reading may have + # been anywhere within -field_of_view/2 and + # field_of_view/2 at the measured range. + # 0 angle corresponds to the x-axis of the sensor. + +float32 min_range # minimum range value [m] +float32 max_range # maximum range value [m] + # Fixed distance rangers require min_range==max_range + +float32 range # range data [m] + # (Note: values < range_min or > range_max should be discarded) + # Fixed distance rangers only output -Inf or +Inf. + # -Inf represents a detection within fixed distance. + # (Detection too close to the sensor to quantify) + # +Inf represents no detection within the fixed distance. + # (Object out of range) diff --git a/src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.idl b/src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.idl new file mode 100644 index 0000000..3367cb5 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.idl @@ -0,0 +1,42 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/RegionOfInterest.msg +// generated code does not contain a copyright notice + + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " This message is used to specify a region of interest within an image." "\n" + "" "\n" + " When used to specify the ROI setting of the camera when the image was" "\n" + " taken, the height and width fields should either match the height and" "\n" + " width fields for the associated image; or height = width = 0" "\n" + " indicates that the full resolution image was captured.") + struct RegionOfInterest { + @verbatim (language="comment", text= + " Leftmost pixel of the ROI" "\n" + " (0 if the ROI includes the left edge of the image)") + uint32 x_offset; + + @verbatim (language="comment", text= + " Topmost pixel of the ROI" "\n" + " (0 if the ROI includes the top edge of the image)") + uint32 y_offset; + + @verbatim (language="comment", text= + " Height of ROI") + uint32 height; + + @verbatim (language="comment", text= + " Width of ROI") + uint32 width; + + @verbatim (language="comment", text= + " True if a distinct rectified ROI should be calculated from the \"raw\"" "\n" + " ROI in this message. Typically this should be False if the full image" "\n" + " is captured (ROI not used), and True if a subwindow is captured (ROI" "\n" + " used).") + boolean do_rectify; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.msg b/src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.msg new file mode 100644 index 0000000..c423dcf --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/RegionOfInterest.msg @@ -0,0 +1,19 @@ +# This message is used to specify a region of interest within an image. +# +# When used to specify the ROI setting of the camera when the image was +# taken, the height and width fields should either match the height and +# width fields for the associated image; or height = width = 0 +# indicates that the full resolution image was captured. + +uint32 x_offset # Leftmost pixel of the ROI + # (0 if the ROI includes the left edge of the image) +uint32 y_offset # Topmost pixel of the ROI + # (0 if the ROI includes the top edge of the image) +uint32 height # Height of ROI +uint32 width # Width of ROI + +# True if a distinct rectified ROI should be calculated from the "raw" +# ROI in this message. Typically this should be False if the full image +# is captured (ROI not used), and True if a subwindow is captured (ROI +# used). +bool do_rectify diff --git a/src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.idl b/src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.idl new file mode 100644 index 0000000..03a893e --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.idl @@ -0,0 +1,31 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/RelativeHumidity.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Single reading from a relative humidity sensor." "\n" + " Defines the ratio of partial pressure of water vapor to the saturated vapor" "\n" + " pressure at a temperature.") + struct RelativeHumidity { + @verbatim (language="comment", text= + " timestamp of the measurement" "\n" + " frame_id is the location of the humidity sensor") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Expression of the relative humidity" "\n" + " from 0.0 to 1.0." "\n" + " 0.0 is no partial pressure of water vapor" "\n" + " 1.0 represents partial pressure of saturation") + double relative_humidity; + + @verbatim (language="comment", text= + " 0 is interpreted as variance unknown") + double variance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.msg b/src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.msg new file mode 100644 index 0000000..b32398f --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/RelativeHumidity.msg @@ -0,0 +1,13 @@ +# Single reading from a relative humidity sensor. +# Defines the ratio of partial pressure of water vapor to the saturated vapor +# pressure at a temperature. + +std_msgs/Header header # timestamp of the measurement + # frame_id is the location of the humidity sensor + +float64 relative_humidity # Expression of the relative humidity + # from 0.0 to 1.0. + # 0.0 is no partial pressure of water vapor + # 1.0 represents partial pressure of saturation + +float64 variance # 0 is interpreted as variance unknown diff --git a/src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.idl b/src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.idl new file mode 100644 index 0000000..fa2b729 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.idl @@ -0,0 +1,32 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from sensor_msgs/srv/SetCameraInfo.srv +// generated code does not contain a copyright notice + +#include "sensor_msgs/msg/CameraInfo.idl" + +module sensor_msgs { + module srv { + @verbatim (language="comment", text= + " This service requests that a camera stores the given CameraInfo as that" "\n" + " camera's calibration information." "\n" + "" "\n" + " The width and height in the camera_info field should match what the" "\n" + " camera is currently outputting on its camera_info topic, and the camera" "\n" + " will assume that the region of the imager that is being referred to is" "\n" + " the region that the camera is currently capturing.") + struct SetCameraInfo_Request { + @verbatim (language="comment", text= + " The camera_info to store") + sensor_msgs::msg::CameraInfo camera_info; + }; + struct SetCameraInfo_Response { + @verbatim (language="comment", text= + " True if the call succeeded") + boolean success; + + @verbatim (language="comment", text= + " Used to give details about success") + string status_message; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.srv b/src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.srv new file mode 100644 index 0000000..98b5b26 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/SetCameraInfo.srv @@ -0,0 +1,12 @@ +# This service requests that a camera stores the given CameraInfo as that +# camera's calibration information. +# +# The width and height in the camera_info field should match what the +# camera is currently outputting on its camera_info topic, and the camera +# will assume that the region of the imager that is being referred to is +# the region that the camera is currently capturing. + +sensor_msgs/CameraInfo camera_info # The camera_info to store +--- +bool success # True if the call succeeded +string status_message # Used to give details about success diff --git a/src/ros2/common_interfaces/sensor_msgs/Temperature.idl b/src/ros2/common_interfaces/sensor_msgs/Temperature.idl new file mode 100644 index 0000000..b5aa7f5 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Temperature.idl @@ -0,0 +1,26 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/Temperature.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Single temperature reading.") + struct Temperature { + @verbatim (language="comment", text= + " timestamp is the time the temperature was measured" "\n" + " frame_id is the location of the temperature reading") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Measurement of the Temperature in Degrees Celsius.") + double temperature; + + @verbatim (language="comment", text= + " 0 is interpreted as variance unknown.") + double variance; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/Temperature.msg b/src/ros2/common_interfaces/sensor_msgs/Temperature.msg new file mode 100644 index 0000000..ca99285 --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/Temperature.msg @@ -0,0 +1,8 @@ +# Single temperature reading. + +std_msgs/Header header # timestamp is the time the temperature was measured + # frame_id is the location of the temperature reading + +float64 temperature # Measurement of the Temperature in Degrees Celsius. + +float64 variance # 0 is interpreted as variance unknown. diff --git a/src/ros2/common_interfaces/sensor_msgs/TimeReference.idl b/src/ros2/common_interfaces/sensor_msgs/TimeReference.idl new file mode 100644 index 0000000..cad2baa --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/TimeReference.idl @@ -0,0 +1,27 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from sensor_msgs/msg/TimeReference.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" +#include "std_msgs/msg/Header.idl" + +module sensor_msgs { + module msg { + @verbatim (language="comment", text= + " Measurement from an external time source not actively synchronized with the system clock.") + struct TimeReference { + @verbatim (language="comment", text= + " stamp is system time for which measurement was valid" "\n" + " frame_id is not used") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " corresponding time from this external source") + builtin_interfaces::msg::Time time_ref; + + @verbatim (language="comment", text= + " (optional) name of time source") + string source; + }; + }; +}; diff --git a/src/ros2/common_interfaces/sensor_msgs/TimeReference.msg b/src/ros2/common_interfaces/sensor_msgs/TimeReference.msg new file mode 100644 index 0000000..6f93c0e --- /dev/null +++ b/src/ros2/common_interfaces/sensor_msgs/TimeReference.msg @@ -0,0 +1,7 @@ +# Measurement from an external time source not actively synchronized with the system clock. + +std_msgs/Header header # stamp is system time for which measurement was valid + # frame_id is not used + +builtin_interfaces/Time time_ref # corresponding time from this external source +string source # (optional) name of time source diff --git a/src/ros2/common_interfaces/shape_msgs/Mesh.idl b/src/ros2/common_interfaces/shape_msgs/Mesh.idl new file mode 100644 index 0000000..e496461 --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/Mesh.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from shape_msgs/msg/Mesh.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Point.idl" +#include "shape_msgs/msg/MeshTriangle.idl" + +module shape_msgs { + module msg { + @verbatim (language="comment", text= + " Definition of a mesh.") + struct Mesh { + @verbatim (language="comment", text= + " List of triangles; the index values refer to positions in vertices[].") + sequence triangles; + + @verbatim (language="comment", text= + " The actual vertices that make up the mesh.") + sequence vertices; + }; + }; +}; diff --git a/src/ros2/common_interfaces/shape_msgs/Mesh.msg b/src/ros2/common_interfaces/shape_msgs/Mesh.msg new file mode 100644 index 0000000..2c3b0d0 --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/Mesh.msg @@ -0,0 +1,7 @@ +# Definition of a mesh. + +# List of triangles; the index values refer to positions in vertices[]. +MeshTriangle[] triangles + +# The actual vertices that make up the mesh. +geometry_msgs/Point[] vertices diff --git a/src/ros2/common_interfaces/shape_msgs/MeshTriangle.idl b/src/ros2/common_interfaces/shape_msgs/MeshTriangle.idl new file mode 100644 index 0000000..c16338f --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/MeshTriangle.idl @@ -0,0 +1,15 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from shape_msgs/msg/MeshTriangle.msg +// generated code does not contain a copyright notice + + +module shape_msgs { + module msg { + typedef uint32 uint32__3[3]; + @verbatim (language="comment", text= + " Definition of a triangle's vertices.") + struct MeshTriangle { + uint32__3 vertex_indices; + }; + }; +}; diff --git a/src/ros2/common_interfaces/shape_msgs/MeshTriangle.msg b/src/ros2/common_interfaces/shape_msgs/MeshTriangle.msg new file mode 100644 index 0000000..9de74df --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/MeshTriangle.msg @@ -0,0 +1,3 @@ +# Definition of a triangle's vertices. + +uint32[3] vertex_indices diff --git a/src/ros2/common_interfaces/shape_msgs/Plane.idl b/src/ros2/common_interfaces/shape_msgs/Plane.idl new file mode 100644 index 0000000..cac4982 --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/Plane.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from shape_msgs/msg/Plane.msg +// generated code does not contain a copyright notice + + +module shape_msgs { + module msg { + typedef double double__4[4]; + @verbatim (language="comment", text= + " Representation of a plane, using the plane equation ax + by + cz + d = 0." "\n" + "" "\n" + " a := coef[0]" "\n" + " b := coef[1]" "\n" + " c := coef[2]" "\n" + " d := coef[3]") + struct Plane { + double__4 coef; + }; + }; +}; diff --git a/src/ros2/common_interfaces/shape_msgs/Plane.msg b/src/ros2/common_interfaces/shape_msgs/Plane.msg new file mode 100644 index 0000000..9d8a43a --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/Plane.msg @@ -0,0 +1,7 @@ +# Representation of a plane, using the plane equation ax + by + cz + d = 0. +# +# a := coef[0] +# b := coef[1] +# c := coef[2] +# d := coef[3] +float64[4] coef diff --git a/src/ros2/common_interfaces/shape_msgs/SolidPrimitive.idl b/src/ros2/common_interfaces/shape_msgs/SolidPrimitive.idl new file mode 100644 index 0000000..dcd52b4 --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/SolidPrimitive.idl @@ -0,0 +1,41 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from shape_msgs/msg/SolidPrimitive.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Polygon.idl" + +module shape_msgs { + module msg { + module SolidPrimitive_Constants { + const uint8 BOX = 1; + const uint8 SPHERE = 2; + const uint8 CYLINDER = 3; + const uint8 CONE = 4; + const uint8 PRISM = 5; + const uint8 BOX_X = 0; + const uint8 BOX_Y = 1; + const uint8 BOX_Z = 2; + const uint8 SPHERE_RADIUS = 0; + const uint8 CYLINDER_HEIGHT = 0; + const uint8 CYLINDER_RADIUS = 1; + const uint8 CONE_HEIGHT = 0; + const uint8 CONE_RADIUS = 1; + const uint8 PRISM_HEIGHT = 0; + }; + @verbatim (language="comment", text= + " Defines box, sphere, cylinder, cone and prism." "\n" + " All shapes are defined to have their bounding boxes centered around 0,0,0.") + struct SolidPrimitive { + @verbatim (language="comment", text= + " The type of the shape") + uint8 type; + + @verbatim (language="comment", text= + " The dimensions of the shape" "\n" + " At no point will dimensions have a length > 3.") + sequence dimensions; + + sequence polygon; + }; + }; +}; diff --git a/src/ros2/common_interfaces/shape_msgs/SolidPrimitive.msg b/src/ros2/common_interfaces/shape_msgs/SolidPrimitive.msg new file mode 100644 index 0000000..a1189a0 --- /dev/null +++ b/src/ros2/common_interfaces/shape_msgs/SolidPrimitive.msg @@ -0,0 +1,50 @@ +# Defines box, sphere, cylinder, cone and prism. +# All shapes are defined to have their bounding boxes centered around 0,0,0. + +uint8 BOX=1 +uint8 SPHERE=2 +uint8 CYLINDER=3 +uint8 CONE=4 +uint8 PRISM=5 + +# The type of the shape +uint8 type + +# The dimensions of the shape +float64[<=3] dimensions # At no point will dimensions have a length > 3. + +# The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array. + +# For type BOX, the X, Y, and Z dimensions are the length of the corresponding sides of the box. +uint8 BOX_X=0 +uint8 BOX_Y=1 +uint8 BOX_Z=2 + +# For the SPHERE type, only one component is used, and it gives the radius of the sphere. +uint8 SPHERE_RADIUS=0 + +# For the CYLINDER and CONE types, the center line is oriented along the Z axis. +# Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component of dimensions gives the +# height of the cylinder (cone). +# The CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the radius of +# the base of the cylinder (cone). +# Cone and cylinder primitives are defined to be circular. The tip of the cone +# is pointing up, along +Z axis. + +uint8 CYLINDER_HEIGHT=0 +uint8 CYLINDER_RADIUS=1 + +uint8 CONE_HEIGHT=0 +uint8 CONE_RADIUS=1 + +# For the type PRISM, the center line is oriented along Z axis. +# The PRISM_HEIGHT component of dimensions gives the +# height of the prism. +# The polygon defines the Z axis centered base of the prism. +# The prism is constructed by extruding the base in +Z and -Z +# directions by half of the PRISM_HEIGHT +# Only x and y fields of the points are used in the polygon. +# Points of the polygon are ordered counter-clockwise. + +uint8 PRISM_HEIGHT=0 +geometry_msgs/Polygon[] polygon diff --git a/src/ros2/common_interfaces/std_msgs/ColorRGBA.idl b/src/ros2/common_interfaces/std_msgs/ColorRGBA.idl new file mode 100644 index 0000000..10e1325 --- /dev/null +++ b/src/ros2/common_interfaces/std_msgs/ColorRGBA.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from std_msgs/msg/ColorRGBA.msg +// generated code does not contain a copyright notice + + +module std_msgs { + module msg { + struct ColorRGBA { + float r; + + float g; + + float b; + + float a; + }; + }; +}; diff --git a/src/ros2/common_interfaces/std_msgs/ColorRGBA.msg b/src/ros2/common_interfaces/std_msgs/ColorRGBA.msg new file mode 100644 index 0000000..182dbc8 --- /dev/null +++ b/src/ros2/common_interfaces/std_msgs/ColorRGBA.msg @@ -0,0 +1,4 @@ +float32 r +float32 g +float32 b +float32 a diff --git a/src/ros2/common_interfaces/std_msgs/Empty.idl b/src/ros2/common_interfaces/std_msgs/Empty.idl new file mode 100644 index 0000000..a92b375 --- /dev/null +++ b/src/ros2/common_interfaces/std_msgs/Empty.idl @@ -0,0 +1,12 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from std_msgs/msg/Empty.msg +// generated code does not contain a copyright notice + + +module std_msgs { + module msg { + struct Empty { + uint8 structure_needs_at_least_one_member; + }; + }; +}; diff --git a/src/ros2/common_interfaces/std_msgs/Empty.msg b/src/ros2/common_interfaces/std_msgs/Empty.msg new file mode 100644 index 0000000..e69de29 diff --git a/src/ros2/common_interfaces/std_msgs/Header.idl b/src/ros2/common_interfaces/std_msgs/Header.idl new file mode 100644 index 0000000..a96ef32 --- /dev/null +++ b/src/ros2/common_interfaces/std_msgs/Header.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from std_msgs/msg/Header.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" + +module std_msgs { + module msg { + @verbatim (language="comment", text= + " Standard metadata for higher-level stamped data types." "\n" + " This is generally used to communicate timestamped data" "\n" + " in a particular coordinate frame.") + struct Header { + @verbatim (language="comment", text= + " Two-integer timestamp that is expressed as seconds and nanoseconds.") + builtin_interfaces::msg::Time stamp; + + @verbatim (language="comment", text= + " Transform frame with which this data is associated.") + string frame_id; + }; + }; +}; diff --git a/src/ros2/common_interfaces/std_msgs/Header.msg b/src/ros2/common_interfaces/std_msgs/Header.msg new file mode 100644 index 0000000..6966bb9 --- /dev/null +++ b/src/ros2/common_interfaces/std_msgs/Header.msg @@ -0,0 +1,9 @@ +# Standard metadata for higher-level stamped data types. +# This is generally used to communicate timestamped data +# in a particular coordinate frame. + +# Two-integer timestamp that is expressed as seconds and nanoseconds. +builtin_interfaces/Time stamp + +# Transform frame with which this data is associated. +string frame_id diff --git a/src/ros2/common_interfaces/std_srvs/Empty.idl b/src/ros2/common_interfaces/std_srvs/Empty.idl new file mode 100644 index 0000000..462126e --- /dev/null +++ b/src/ros2/common_interfaces/std_srvs/Empty.idl @@ -0,0 +1,15 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from std_srvs/srv/Empty.srv +// generated code does not contain a copyright notice + + +module std_srvs { + module srv { + struct Empty_Request { + uint8 structure_needs_at_least_one_member; + }; + struct Empty_Response { + uint8 structure_needs_at_least_one_member; + }; + }; +}; diff --git a/src/ros2/common_interfaces/std_srvs/Empty.srv b/src/ros2/common_interfaces/std_srvs/Empty.srv new file mode 100644 index 0000000..ed97d53 --- /dev/null +++ b/src/ros2/common_interfaces/std_srvs/Empty.srv @@ -0,0 +1 @@ +--- diff --git a/src/ros2/common_interfaces/std_srvs/SetBool.idl b/src/ros2/common_interfaces/std_srvs/SetBool.idl new file mode 100644 index 0000000..622f73a --- /dev/null +++ b/src/ros2/common_interfaces/std_srvs/SetBool.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from std_srvs/srv/SetBool.srv +// generated code does not contain a copyright notice + + +module std_srvs { + module srv { + struct SetBool_Request { + @verbatim (language="comment", text= + " e.g. for hardware enabling / disabling") + boolean data; + }; + struct SetBool_Response { + @verbatim (language="comment", text= + " indicate successful run of triggered service") + boolean success; + + @verbatim (language="comment", text= + " informational, e.g. for error messages") + string message; + }; + }; +}; diff --git a/src/ros2/common_interfaces/std_srvs/SetBool.srv b/src/ros2/common_interfaces/std_srvs/SetBool.srv new file mode 100644 index 0000000..9300347 --- /dev/null +++ b/src/ros2/common_interfaces/std_srvs/SetBool.srv @@ -0,0 +1,4 @@ +bool data # e.g. for hardware enabling / disabling +--- +bool success # indicate successful run of triggered service +string message # informational, e.g. for error messages diff --git a/src/ros2/common_interfaces/std_srvs/Trigger.idl b/src/ros2/common_interfaces/std_srvs/Trigger.idl new file mode 100644 index 0000000..9571133 --- /dev/null +++ b/src/ros2/common_interfaces/std_srvs/Trigger.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from std_srvs/srv/Trigger.srv +// generated code does not contain a copyright notice + + +module std_srvs { + module srv { + struct Trigger_Request { + uint8 structure_needs_at_least_one_member; + }; + struct Trigger_Response { + @verbatim (language="comment", text= + " indicate successful run of triggered service") + boolean success; + + @verbatim (language="comment", text= + " informational, e.g. for error messages") + string message; + }; + }; +}; diff --git a/src/ros2/common_interfaces/std_srvs/Trigger.srv b/src/ros2/common_interfaces/std_srvs/Trigger.srv new file mode 100644 index 0000000..371dfd2 --- /dev/null +++ b/src/ros2/common_interfaces/std_srvs/Trigger.srv @@ -0,0 +1,3 @@ +--- +bool success # indicate successful run of triggered service +string message # informational, e.g. for error messages diff --git a/src/ros2/common_interfaces/stereo_msgs/DisparityImage.idl b/src/ros2/common_interfaces/stereo_msgs/DisparityImage.idl new file mode 100644 index 0000000..6779730 --- /dev/null +++ b/src/ros2/common_interfaces/stereo_msgs/DisparityImage.idl @@ -0,0 +1,54 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from stereo_msgs/msg/DisparityImage.msg +// generated code does not contain a copyright notice + +#include "sensor_msgs/msg/Image.idl" +#include "sensor_msgs/msg/RegionOfInterest.idl" +#include "std_msgs/msg/Header.idl" + +module stereo_msgs { + module msg { + @verbatim (language="comment", text= + " Separate header for compatibility with current TimeSynchronizer." "\n" + " Likely to be removed in a later release, use image.header instead.") + struct DisparityImage { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Floating point disparity image. The disparities are pre-adjusted for any" "\n" + " x-offset between the principal points of the two cameras (in the case" "\n" + " that they are verged). That is: d = x_l - x_r - (cx_l - cx_r)") + sensor_msgs::msg::Image image; + + @verbatim (language="comment", text= + " Stereo geometry. For disparity d, the depth from the camera is Z = fT/d." "\n" + " Focal length, pixels") + float f; + + @verbatim (language="comment", text= + " Baseline, world units") + float t; + + @verbatim (language="comment", text= + " Subwindow of (potentially) valid disparity values.") + sensor_msgs::msg::RegionOfInterest valid_window; + + @verbatim (language="comment", text= + " The range of disparities searched." "\n" + " In the disparity image, any disparity less than min_disparity is invalid." "\n" + " The disparity search range defines the horopter, or 3D volume that the" "\n" + " stereo algorithm can \"see\". Points with Z outside of:" "\n" + " Z_min = fT / max_disparity" "\n" + " Z_max = fT / min_disparity" "\n" + " could not be found.") + float min_disparity; + + float max_disparity; + + @verbatim (language="comment", text= + " Smallest allowed disparity increment. The smallest achievable depth range" "\n" + " resolution is delta_Z = (Z^2/fT)*delta_d.") + float delta_d; + }; + }; +}; diff --git a/src/ros2/common_interfaces/stereo_msgs/DisparityImage.msg b/src/ros2/common_interfaces/stereo_msgs/DisparityImage.msg new file mode 100644 index 0000000..fac5af2 --- /dev/null +++ b/src/ros2/common_interfaces/stereo_msgs/DisparityImage.msg @@ -0,0 +1,29 @@ +# Separate header for compatibility with current TimeSynchronizer. +# Likely to be removed in a later release, use image.header instead. +std_msgs/Header header + +# Floating point disparity image. The disparities are pre-adjusted for any +# x-offset between the principal points of the two cameras (in the case +# that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) +sensor_msgs/Image image + +# Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. +float32 f # Focal length, pixels +float32 t # Baseline, world units + +# Subwindow of (potentially) valid disparity values. +sensor_msgs/RegionOfInterest valid_window + +# The range of disparities searched. +# In the disparity image, any disparity less than min_disparity is invalid. +# The disparity search range defines the horopter, or 3D volume that the +# stereo algorithm can "see". Points with Z outside of: +# Z_min = fT / max_disparity +# Z_max = fT / min_disparity +# could not be found. +float32 min_disparity +float32 max_disparity + +# Smallest allowed disparity increment. The smallest achievable depth range +# resolution is delta_Z = (Z^2/fT)*delta_d. +float32 delta_d diff --git a/src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.idl b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.idl new file mode 100644 index 0000000..42c284d --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.idl @@ -0,0 +1,27 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from trajectory_msgs/msg/JointTrajectory.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" +#include "trajectory_msgs/msg/JointTrajectoryPoint.idl" + +module trajectory_msgs { + module msg { + @verbatim (language="comment", text= + " The header is used to specify the coordinate frame and the reference time for" "\n" + " the trajectory durations") + struct JointTrajectory { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " The names of the active joints in each trajectory point. These names are" "\n" + " ordered and must correspond to the values in each trajectory point.") + sequence joint_names; + + @verbatim (language="comment", text= + " Array of trajectory points, which describe the positions, velocities," "\n" + " accelerations and/or efforts of the joints at each time point.") + sequence points; + }; + }; +}; diff --git a/src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.msg b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.msg new file mode 100644 index 0000000..a5d2198 --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectory.msg @@ -0,0 +1,11 @@ +# The header is used to specify the coordinate frame and the reference time for +# the trajectory durations +std_msgs/Header header + +# The names of the active joints in each trajectory point. These names are +# ordered and must correspond to the values in each trajectory point. +string[] joint_names + +# Array of trajectory points, which describe the positions, velocities, +# accelerations and/or efforts of the joints at each time point. +JointTrajectoryPoint[] points diff --git a/src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.idl b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.idl new file mode 100644 index 0000000..9897a6f --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.idl @@ -0,0 +1,43 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from trajectory_msgs/msg/JointTrajectoryPoint.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Duration.idl" + +module trajectory_msgs { + module msg { + @verbatim (language="comment", text= + " Each trajectory point specifies either positions[, velocities[, accelerations]]" "\n" + " or positions[, effort] for the trajectory to be executed." "\n" + " All specified values are in the same order as the joint names in JointTrajectory.msg.") + struct JointTrajectoryPoint { + @verbatim (language="comment", text= + " Single DOF joint positions for each joint relative to their \"0\" position." "\n" + " The units depend on the specific joint type: radians for revolute or" "\n" + " continuous joints, and meters for prismatic joints.") + sequence positions; + + @verbatim (language="comment", text= + " The rate of change in position of each joint. Units are joint type dependent." "\n" + " Radians/second for revolute or continuous joints, and meters/second for" "\n" + " prismatic joints.") + sequence velocities; + + @verbatim (language="comment", text= + " Rate of change in velocity of each joint. Units are joint type dependent." "\n" + " Radians/second^2 for revolute or continuous joints, and meters/second^2 for" "\n" + " prismatic joints.") + sequence accelerations; + + @verbatim (language="comment", text= + " The torque or the force to be applied at each joint. For revolute/continuous" "\n" + " joints effort denotes a torque in newton-meters. For prismatic joints, effort" "\n" + " denotes a force in newtons.") + sequence effort; + + @verbatim (language="comment", text= + " Desired time from the trajectory start to arrive at this trajectory point.") + builtin_interfaces::msg::Duration time_from_start; + }; + }; +}; diff --git a/src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.msg b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.msg new file mode 100644 index 0000000..01e38a4 --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/JointTrajectoryPoint.msg @@ -0,0 +1,26 @@ +# Each trajectory point specifies either positions[, velocities[, accelerations]] +# or positions[, effort] for the trajectory to be executed. +# All specified values are in the same order as the joint names in JointTrajectory.msg. + +# Single DOF joint positions for each joint relative to their "0" position. +# The units depend on the specific joint type: radians for revolute or +# continuous joints, and meters for prismatic joints. +float64[] positions + +# The rate of change in position of each joint. Units are joint type dependent. +# Radians/second for revolute or continuous joints, and meters/second for +# prismatic joints. +float64[] velocities + +# Rate of change in velocity of each joint. Units are joint type dependent. +# Radians/second^2 for revolute or continuous joints, and meters/second^2 for +# prismatic joints. +float64[] accelerations + +# The torque or the force to be applied at each joint. For revolute/continuous +# joints effort denotes a torque in newton-meters. For prismatic joints, effort +# denotes a force in newtons. +float64[] effort + +# Desired time from the trajectory start to arrive at this trajectory point. +builtin_interfaces/Duration time_from_start diff --git a/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.idl b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.idl new file mode 100644 index 0000000..910cc53 --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.idl @@ -0,0 +1,25 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from trajectory_msgs/msg/MultiDOFJointTrajectory.msg +// generated code does not contain a copyright notice + +#include "std_msgs/msg/Header.idl" +#include "trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.idl" + +module trajectory_msgs { + module msg { + @verbatim (language="comment", text= + " The header is used to specify the coordinate frame and the reference time for the trajectory durations") + struct MultiDOFJointTrajectory { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " A representation of a multi-dof joint trajectory (each point is a transformation)" "\n" + " Each point along the trajectory will include an array of positions/velocities/accelerations" "\n" + " that has the same length as the array of joint names, and has the same order of joints as" "\n" + " the joint names array.") + sequence joint_names; + + sequence points; + }; + }; +}; diff --git a/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.msg b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.msg new file mode 100644 index 0000000..155fddd --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectory.msg @@ -0,0 +1,10 @@ +# The header is used to specify the coordinate frame and the reference time for the trajectory durations +std_msgs/Header header + +# A representation of a multi-dof joint trajectory (each point is a transformation) +# Each point along the trajectory will include an array of positions/velocities/accelerations +# that has the same length as the array of joint names, and has the same order of joints as +# the joint names array. + +string[] joint_names +MultiDOFJointTrajectoryPoint[] points diff --git a/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.idl b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.idl new file mode 100644 index 0000000..d043f22 --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.idl @@ -0,0 +1,29 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Duration.idl" +#include "geometry_msgs/msg/Transform.idl" +#include "geometry_msgs/msg/Twist.idl" + +module trajectory_msgs { + module msg { + @verbatim (language="comment", text= + " Each multi-dof joint can specify a transform (up to 6 DOF).") + struct MultiDOFJointTrajectoryPoint { + sequence transforms; + + @verbatim (language="comment", text= + " There can be a velocity specified for the origin of the joint.") + sequence velocities; + + @verbatim (language="comment", text= + " There can be an acceleration specified for the origin of the joint.") + sequence accelerations; + + @verbatim (language="comment", text= + " Desired time from the trajectory start to arrive at this trajectory point.") + builtin_interfaces::msg::Duration time_from_start; + }; + }; +}; diff --git a/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.msg b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.msg new file mode 100644 index 0000000..b5f6457 --- /dev/null +++ b/src/ros2/common_interfaces/trajectory_msgs/MultiDOFJointTrajectoryPoint.msg @@ -0,0 +1,11 @@ +# Each multi-dof joint can specify a transform (up to 6 DOF). +geometry_msgs/Transform[] transforms + +# There can be a velocity specified for the origin of the joint. +geometry_msgs/Twist[] velocities + +# There can be an acceleration specified for the origin of the joint. +geometry_msgs/Twist[] accelerations + +# Desired time from the trajectory start to arrive at this trajectory point. +builtin_interfaces/Duration time_from_start diff --git a/src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.idl b/src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.idl new file mode 100644 index 0000000..c0a06e2 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.idl @@ -0,0 +1,25 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from visualization_msgs/srv/GetInteractiveMarkers.srv +// generated code does not contain a copyright notice + +#include "visualization_msgs/msg/InteractiveMarker.idl" + +module visualization_msgs { + module srv { + struct GetInteractiveMarkers_Request { + uint8 structure_needs_at_least_one_member; + }; + @verbatim (language="comment", text= + " Sequence number." "\n" + " Set to the sequence number of the latest update message" "\n" + " at the time the server received the request." "\n" + " Clients use this to detect if any updates were missed.") + struct GetInteractiveMarkers_Response { + uint64 sequence_number; + + @verbatim (language="comment", text= + " All interactive markers provided by the server.") + sequence markers; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.srv b/src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.srv new file mode 100644 index 0000000..493e885 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/GetInteractiveMarkers.srv @@ -0,0 +1,9 @@ +--- +# Sequence number. +# Set to the sequence number of the latest update message +# at the time the server received the request. +# Clients use this to detect if any updates were missed. +uint64 sequence_number + +# All interactive markers provided by the server. +InteractiveMarker[] markers diff --git a/src/ros2/common_interfaces/visualization_msgs/ImageMarker.idl b/src/ros2/common_interfaces/visualization_msgs/ImageMarker.idl new file mode 100644 index 0000000..49f78d0 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/ImageMarker.idl @@ -0,0 +1,75 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/ImageMarker.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Duration.idl" +#include "geometry_msgs/msg/Point.idl" +#include "std_msgs/msg/ColorRGBA.idl" +#include "std_msgs/msg/Header.idl" + +module visualization_msgs { + module msg { + module ImageMarker_Constants { + const int32 CIRCLE = 0; + const int32 LINE_STRIP = 1; + const int32 LINE_LIST = 2; + const int32 POLYGON = 3; + const int32 POINTS = 4; + const int32 ADD = 0; + const int32 REMOVE = 1; + }; + struct ImageMarker { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Namespace which is used with the id to form a unique id.") + string ns; + + @verbatim (language="comment", text= + " Unique id within the namespace.") + int32 id; + + @verbatim (language="comment", text= + " One of the above types, e.g. CIRCLE, LINE_STRIP, etc.") + int32 type; + + @verbatim (language="comment", text= + " Either ADD or REMOVE.") + int32 action; + + @verbatim (language="comment", text= + " Two-dimensional coordinate position, in pixel-coordinates.") + geometry_msgs::msg::Point position; + + @verbatim (language="comment", text= + " The scale of the object, e.g. the diameter for a CIRCLE.") + float scale; + + @verbatim (language="comment", text= + " The outline color of the marker.") + std_msgs::msg::ColorRGBA outline_color; + + @verbatim (language="comment", text= + " Whether or not to fill in the shape with color.") + uint8 filled; + + @verbatim (language="comment", text= + " Fill color; in the range:") + @unit (value="0.0-1.0") + std_msgs::msg::ColorRGBA fill_color; + + @verbatim (language="comment", text= + " How long the object should last before being automatically deleted." "\n" + " 0 indicates forever.") + builtin_interfaces::msg::Duration lifetime; + + @verbatim (language="comment", text= + " Coordinates in 2D in pixel coords. Used for LINE_STRIP, LINE_LIST, POINTS, etc.") + sequence points; + + @verbatim (language="comment", text= + " The color for each line, point, etc. in the points field.") + sequence outline_colors; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/ImageMarker.msg b/src/ros2/common_interfaces/visualization_msgs/ImageMarker.msg new file mode 100644 index 0000000..2b9e64a --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/ImageMarker.msg @@ -0,0 +1,36 @@ +int32 CIRCLE=0 +int32 LINE_STRIP=1 +int32 LINE_LIST=2 +int32 POLYGON=3 +int32 POINTS=4 + +int32 ADD=0 +int32 REMOVE=1 + +std_msgs/Header header +# Namespace which is used with the id to form a unique id. +string ns +# Unique id within the namespace. +int32 id +# One of the above types, e.g. CIRCLE, LINE_STRIP, etc. +int32 type +# Either ADD or REMOVE. +int32 action +# Two-dimensional coordinate position, in pixel-coordinates. +geometry_msgs/Point position +# The scale of the object, e.g. the diameter for a CIRCLE. +float32 scale +# The outline color of the marker. +std_msgs/ColorRGBA outline_color +# Whether or not to fill in the shape with color. +uint8 filled +# Fill color; in the range: [0.0-1.0] +std_msgs/ColorRGBA fill_color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime + +# Coordinates in 2D in pixel coords. Used for LINE_STRIP, LINE_LIST, POINTS, etc. +geometry_msgs/Point[] points +# The color for each line, point, etc. in the points field. +std_msgs/ColorRGBA[] outline_colors diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.idl b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.idl new file mode 100644 index 0000000..df89ed4 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.idl @@ -0,0 +1,48 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/InteractiveMarker.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Pose.idl" +#include "std_msgs/msg/Header.idl" +#include "visualization_msgs/msg/InteractiveMarkerControl.idl" +#include "visualization_msgs/msg/MenuEntry.idl" + +module visualization_msgs { + module msg { + @verbatim (language="comment", text= + " Time/frame info." "\n" + " If header.time is set to 0, the marker will be retransformed into" "\n" + " its frame on each timestep. You will receive the pose feedback" "\n" + " in the same frame." "\n" + " Otherwise, you might receive feedback in a different frame." "\n" + " For rviz, this will be the current 'fixed frame' set by the user.") + struct InteractiveMarker { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Initial pose. Also, defines the pivot point for rotations.") + geometry_msgs::msg::Pose pose; + + @verbatim (language="comment", text= + " Identifying string. Must be globally unique in" "\n" + " the topic that this message is sent through.") + string name; + + @verbatim (language="comment", text= + " Short description (< 40 characters).") + string description; + + @verbatim (language="comment", text= + " Scale to be used for default controls (default=1).") + float scale; + + @verbatim (language="comment", text= + " All menu and submenu entries associated with this marker.") + sequence menu_entries; + + @verbatim (language="comment", text= + " List of controls displayed for this marker.") + sequence controls; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.msg b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.msg new file mode 100644 index 0000000..c2af8dc --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarker.msg @@ -0,0 +1,26 @@ +# Time/frame info. +# If header.time is set to 0, the marker will be retransformed into +# its frame on each timestep. You will receive the pose feedback +# in the same frame. +# Otherwise, you might receive feedback in a different frame. +# For rviz, this will be the current 'fixed frame' set by the user. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name + +# Short description (< 40 characters). +string description + +# Scale to be used for default controls (default=1). +float32 scale + +# All menu and submenu entries associated with this marker. +MenuEntry[] menu_entries + +# List of controls displayed for this marker. +InteractiveMarkerControl[] controls diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.idl b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.idl new file mode 100644 index 0000000..73f2e09 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.idl @@ -0,0 +1,73 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/InteractiveMarkerControl.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Quaternion.idl" +#include "visualization_msgs/msg/Marker.idl" + +module visualization_msgs { + module msg { + module InteractiveMarkerControl_Constants { + const uint8 INHERIT = 0; + const uint8 FIXED = 1; + const uint8 VIEW_FACING = 2; + const uint8 NONE = 0; + const uint8 MENU = 1; + const uint8 BUTTON = 2; + const uint8 MOVE_AXIS = 3; + const uint8 MOVE_PLANE = 4; + const uint8 ROTATE_AXIS = 5; + const uint8 MOVE_ROTATE = 6; + const uint8 MOVE_3D = 7; + const uint8 ROTATE_3D = 8; + const uint8 MOVE_ROTATE_3D = 9; + }; + @verbatim (language="comment", text= + " Represents a control that is to be displayed together with an interactive marker") + struct InteractiveMarkerControl { + @verbatim (language="comment", text= + " Identifying string for this control." "\n" + " You need to assign a unique value to this to receive feedback from the GUI" "\n" + " on what actions the user performs on this control (e.g. a button click).") + string name; + + @verbatim (language="comment", text= + " Defines the local coordinate frame (relative to the pose of the parent" "\n" + " interactive marker) in which is being rotated and translated." "\n" + " Default: Identity") + geometry_msgs::msg::Quaternion orientation; + + uint8 orientation_mode; + + uint8 interaction_mode; + + @verbatim (language="comment", text= + " If true, the contained markers will also be visible" "\n" + " when the gui is not in interactive mode.") + boolean always_visible; + + @verbatim (language="comment", text= + " Markers to be displayed as custom visual representation." "\n" + " Leave this empty to use the default control handles." "\n" + "" "\n" + " Note:" "\n" + " - The markers can be defined in an arbitrary coordinate frame," "\n" + " but will be transformed into the local frame of the interactive marker." "\n" + " - If the header of a marker is empty, its pose will be interpreted as" "\n" + " relative to the pose of the parent interactive marker.") + sequence markers; + + @verbatim (language="comment", text= + " In VIEW_FACING mode, set this to true if you don't want the markers" "\n" + " to be aligned with the camera view point. The markers will show up" "\n" + " as in INHERIT mode.") + boolean independent_marker_orientation; + + @verbatim (language="comment", text= + " Short description (< 40 characters) of what this control does," "\n" + " e.g. \"Move the robot\"." "\n" + " Default: A generic description based on the interaction mode") + string description; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.msg b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.msg new file mode 100644 index 0000000..10f88c8 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerControl.msg @@ -0,0 +1,77 @@ +# Represents a control that is to be displayed together with an interactive marker + +# Identifying string for this control. +# You need to assign a unique value to this to receive feedback from the GUI +# on what actions the user performs on this control (e.g. a button click). +string name + + +# Defines the local coordinate frame (relative to the pose of the parent +# interactive marker) in which is being rotated and translated. +# Default: Identity +geometry_msgs/Quaternion orientation + + +# Orientation mode: controls how orientation changes. +# INHERIT: Follow orientation of interactive marker +# FIXED: Keep orientation fixed at initial state +# VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). +uint8 INHERIT = 0 +uint8 FIXED = 1 +uint8 VIEW_FACING = 2 + +uint8 orientation_mode + +# Interaction mode for this control +# +# NONE: This control is only meant for visualization; no context menu. +# MENU: Like NONE, but right-click menu is active. +# BUTTON: Element can be left-clicked. +# MOVE_AXIS: Translate along local x-axis. +# MOVE_PLANE: Translate in local y-z plane. +# ROTATE_AXIS: Rotate around local x-axis. +# MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. +uint8 NONE = 0 +uint8 MENU = 1 +uint8 BUTTON = 2 +uint8 MOVE_AXIS = 3 +uint8 MOVE_PLANE = 4 +uint8 ROTATE_AXIS = 5 +uint8 MOVE_ROTATE = 6 +# "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. +# MOVE_3D: Translate freely in 3D space. +# ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. +# MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. +uint8 MOVE_3D = 7 +uint8 ROTATE_3D = 8 +uint8 MOVE_ROTATE_3D = 9 + +uint8 interaction_mode + + +# If true, the contained markers will also be visible +# when the gui is not in interactive mode. +bool always_visible + + +# Markers to be displayed as custom visual representation. +# Leave this empty to use the default control handles. +# +# Note: +# - The markers can be defined in an arbitrary coordinate frame, +# but will be transformed into the local frame of the interactive marker. +# - If the header of a marker is empty, its pose will be interpreted as +# relative to the pose of the parent interactive marker. +Marker[] markers + + +# In VIEW_FACING mode, set this to true if you don't want the markers +# to be aligned with the camera view point. The markers will show up +# as in INHERIT mode. +bool independent_marker_orientation + + +# Short description (< 40 characters) of what this control does, +# e.g. "Move the robot". +# Default: A generic description based on the interaction mode +string description diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.idl b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.idl new file mode 100644 index 0000000..faa5dad --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.idl @@ -0,0 +1,58 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/InteractiveMarkerFeedback.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Point.idl" +#include "geometry_msgs/msg/Pose.idl" +#include "std_msgs/msg/Header.idl" + +module visualization_msgs { + module msg { + module InteractiveMarkerFeedback_Constants { + const uint8 KEEP_ALIVE = 0; + const uint8 POSE_UPDATE = 1; + const uint8 MENU_SELECT = 2; + const uint8 BUTTON_CLICK = 3; + const uint8 MOUSE_DOWN = 4; + const uint8 MOUSE_UP = 5; + }; + @verbatim (language="comment", text= + " Time/frame info.") + struct InteractiveMarkerFeedback { + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Identifying string. Must be unique in the topic namespace.") + string client_id; + + @verbatim (language="comment", text= + " Feedback message sent back from the GUI, e.g." "\n" + " when the status of an interactive marker was modified by the user." "\n" + " Specifies which interactive marker and control this message refers to") + string marker_name; + + string control_name; + + uint8 event_type; + + @verbatim (language="comment", text= + " Current pose of the marker" "\n" + " Note: Has to be valid for all feedback types.") + geometry_msgs::msg::Pose pose; + + @verbatim (language="comment", text= + " Contains the ID of the selected menu entry" "\n" + " Only valid for MENU_SELECT events.") + uint32 menu_entry_id; + + @verbatim (language="comment", text= + " If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point" "\n" + " may contain the 3 dimensional position of the event on the" "\n" + " control. If it does, mouse_point_valid will be true. mouse_point" "\n" + " will be relative to the frame listed in the header.") + geometry_msgs::msg::Point mouse_point; + + boolean mouse_point_valid; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.msg b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.msg new file mode 100644 index 0000000..43c754c --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerFeedback.msg @@ -0,0 +1,42 @@ +# Time/frame info. +std_msgs/Header header + +# Identifying string. Must be unique in the topic namespace. +string client_id + +# Feedback message sent back from the GUI, e.g. +# when the status of an interactive marker was modified by the user. + +# Specifies which interactive marker and control this message refers to +string marker_name +string control_name + +# Type of the event +# KEEP_ALIVE: sent while dragging to keep up control of the marker +# MENU_SELECT: a menu entry has been selected +# BUTTON_CLICK: a button control has been clicked +# POSE_UPDATE: the pose has been changed using one of the controls +uint8 KEEP_ALIVE = 0 +uint8 POSE_UPDATE = 1 +uint8 MENU_SELECT = 2 +uint8 BUTTON_CLICK = 3 + +uint8 MOUSE_DOWN = 4 +uint8 MOUSE_UP = 5 + +uint8 event_type + +# Current pose of the marker +# Note: Has to be valid for all feedback types. +geometry_msgs/Pose pose + +# Contains the ID of the selected menu entry +# Only valid for MENU_SELECT events. +uint32 menu_entry_id + +# If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point +# may contain the 3 dimensional position of the event on the +# control. If it does, mouse_point_valid will be true. mouse_point +# will be relative to the frame listed in the header. +geometry_msgs/Point mouse_point +bool mouse_point_valid diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.idl b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.idl new file mode 100644 index 0000000..0cf7930 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.idl @@ -0,0 +1,29 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/InteractiveMarkerInit.msg +// generated code does not contain a copyright notice + +#include "visualization_msgs/msg/InteractiveMarker.idl" + +module visualization_msgs { + module msg { + @verbatim (language="comment", text= + " Identifying string. Must be unique in the topic namespace" "\n" + " that this server works on.") + struct InteractiveMarkerInit { + string server_id; + + @verbatim (language="comment", text= + " Sequence number." "\n" + " The client will use this to detect if it has missed a subsequent" "\n" + " update. Every update message will have the same sequence number as" "\n" + " an init message. Clients will likely want to unsubscribe from the" "\n" + " init topic after a successful initialization to avoid receiving" "\n" + " duplicate data.") + uint64 seq_num; + + @verbatim (language="comment", text= + " All markers.") + sequence markers; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.msg b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.msg new file mode 100644 index 0000000..d73bcd0 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerInit.msg @@ -0,0 +1,14 @@ +# Identifying string. Must be unique in the topic namespace +# that this server works on. +string server_id + +# Sequence number. +# The client will use this to detect if it has missed a subsequent +# update. Every update message will have the same sequence number as +# an init message. Clients will likely want to unsubscribe from the +# init topic after a successful initialization to avoid receiving +# duplicate data. +uint64 seq_num + +# All markers. +InteractiveMarker[] markers diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.idl b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.idl new file mode 100644 index 0000000..4e53ad9 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.idl @@ -0,0 +1,25 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/InteractiveMarkerPose.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Pose.idl" +#include "std_msgs/msg/Header.idl" + +module visualization_msgs { + module msg { + struct InteractiveMarkerPose { + @verbatim (language="comment", text= + " Time/frame info.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Initial pose. Also, defines the pivot point for rotations.") + geometry_msgs::msg::Pose pose; + + @verbatim (language="comment", text= + " Identifying string. Must be globally unique in" "\n" + " the topic that this message is sent through.") + string name; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.msg b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.msg new file mode 100644 index 0000000..04a22e9 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerPose.msg @@ -0,0 +1,10 @@ + +# Time/frame info. +std_msgs/Header header + +# Initial pose. Also, defines the pivot point for rotations. +geometry_msgs/Pose pose + +# Identifying string. Must be globally unique in +# the topic that this message is sent through. +string name diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.idl b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.idl new file mode 100644 index 0000000..f01e3c1 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.idl @@ -0,0 +1,42 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/InteractiveMarkerUpdate.msg +// generated code does not contain a copyright notice + +#include "visualization_msgs/msg/InteractiveMarker.idl" +#include "visualization_msgs/msg/InteractiveMarkerPose.idl" + +module visualization_msgs { + module msg { + module InteractiveMarkerUpdate_Constants { + const uint8 KEEP_ALIVE = 0; + const uint8 UPDATE = 1; + }; + struct InteractiveMarkerUpdate { + @verbatim (language="comment", text= + " Identifying string. Must be unique in the topic namespace" "\n" + " that this server works on.") + string server_id; + + @verbatim (language="comment", text= + " Sequence number." "\n" + " The client will use this to detect if it has missed an update.") + uint64 seq_num; + + uint8 type; + + @verbatim (language="comment", text= + " Note: No guarantees on the order of processing." "\n" + " Contents must be kept consistent by sender." "\n" + " Markers to be added or updated") + sequence markers; + + @verbatim (language="comment", text= + " Poses of markers that should be moved") + sequence poses; + + @verbatim (language="comment", text= + " Names of markers to be erased") + sequence erases; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.msg b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.msg new file mode 100644 index 0000000..2070a03 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/InteractiveMarkerUpdate.msg @@ -0,0 +1,32 @@ + +# Identifying string. Must be unique in the topic namespace +# that this server works on. +string server_id + +# Sequence number. +# The client will use this to detect if it has missed an update. +uint64 seq_num + +# Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE. +# UPDATE: Incremental update to previous state. +# The sequence number must be 1 higher than for +# the previous update. +# KEEP_ALIVE: Indicates the that the server is still living. +# The sequence number does not increase. +# No payload data should be filled out (markers, poses, or erases). +uint8 KEEP_ALIVE = 0 +uint8 UPDATE = 1 + +uint8 type + +# Note: No guarantees on the order of processing. +# Contents must be kept consistent by sender. + +# Markers to be added or updated +InteractiveMarker[] markers + +# Poses of markers that should be moved +InteractiveMarkerPose[] poses + +# Names of markers to be erased +string[] erases diff --git a/src/ros2/common_interfaces/visualization_msgs/Marker.idl b/src/ros2/common_interfaces/visualization_msgs/Marker.idl new file mode 100644 index 0000000..bae1858 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/Marker.idl @@ -0,0 +1,134 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/Marker.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Duration.idl" +#include "geometry_msgs/msg/Point.idl" +#include "geometry_msgs/msg/Pose.idl" +#include "geometry_msgs/msg/Vector3.idl" +#include "sensor_msgs/msg/CompressedImage.idl" +#include "std_msgs/msg/ColorRGBA.idl" +#include "std_msgs/msg/Header.idl" +#include "visualization_msgs/msg/MeshFile.idl" +#include "visualization_msgs/msg/UVCoordinate.idl" + +module visualization_msgs { + module msg { + module Marker_Constants { + const int32 ARROW = 0; + const int32 CUBE = 1; + const int32 SPHERE = 2; + const int32 CYLINDER = 3; + const int32 LINE_STRIP = 4; + const int32 LINE_LIST = 5; + const int32 CUBE_LIST = 6; + const int32 SPHERE_LIST = 7; + const int32 POINTS = 8; + const int32 TEXT_VIEW_FACING = 9; + const int32 MESH_RESOURCE = 10; + const int32 TRIANGLE_LIST = 11; + const int32 ADD = 0; + const int32 MODIFY = 0; + const int32 DELETE = 2; + const int32 DELETEALL = 3; + }; + @verbatim (language="comment", text= + " See:" "\n" + " - http://www.ros.org/wiki/rviz/DisplayTypes/Marker" "\n" + " - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes" "\n" + "" "\n" + " for more information on using this message with rviz.") + struct Marker { + @verbatim (language="comment", text= + " Header for timestamp and frame id.") + std_msgs::msg::Header header; + + @verbatim (language="comment", text= + " Namespace in which to place the object." "\n" + " Used in conjunction with id to create a unique name for the object.") + string ns; + + @verbatim (language="comment", text= + " Object ID used in conjunction with the namespace for manipulating and deleting the object later.") + int32 id; + + @verbatim (language="comment", text= + " Type of object.") + int32 type; + + @verbatim (language="comment", text= + " Action to take; one of:" "\n" + " - 0 add/modify an object" "\n" + " - 1 (deprecated)" "\n" + " - 2 deletes an object (with the given ns and id)" "\n" + " - 3 deletes all objects (or those with the given ns if any)") + int32 action; + + @verbatim (language="comment", text= + " Pose of the object with respect the frame_id specified in the header.") + geometry_msgs::msg::Pose pose; + + @verbatim (language="comment", text= + " Scale of the object; 1,1,1 means default (usually 1 meter square).") + geometry_msgs::msg::Vector3 scale; + + @verbatim (language="comment", text= + " Color of the object; in the range:") + @unit (value="0.0-1.0") + std_msgs::msg::ColorRGBA color; + + @verbatim (language="comment", text= + " How long the object should last before being automatically deleted." "\n" + " 0 indicates forever.") + builtin_interfaces::msg::Duration lifetime; + + @verbatim (language="comment", text= + " If this marker should be frame-locked, i.e. retransformed into its frame every timestep.") + boolean frame_locked; + + @verbatim (language="comment", text= + " Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.)") + sequence points; + + @verbatim (language="comment", text= + " Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.)" "\n" + " The number of colors provided must either be 0 or equal to the number of points provided." "\n" + " NOTE: alpha is not yet used") + sequence colors; + + @verbatim (language="comment", text= + " Texture resource is a special URI that can either reference a texture file in" "\n" + " a format acceptable to (resource retriever)" "\n" + " or an embedded texture via a string matching the format:" "\n" + " \"embedded://texture_name\"") + @unit (value="https://index.ros.org/p/resource_retriever/") + string texture_resource; + + @verbatim (language="comment", text= + " An image to be loaded into the rendering engine as the texture for this marker." "\n" + " This will be used iff texture_resource is set to embedded.") + sensor_msgs::msg::CompressedImage texture; + + @verbatim (language="comment", text= + " Location of each vertex within the texture; in the range:") + @unit (value="0.0-1.0") + sequence uv_coordinates; + + @verbatim (language="comment", text= + " Only used for text markers") + string text; + + @verbatim (language="comment", text= + " Only used for MESH_RESOURCE markers." "\n" + " Similar to texture_resource, mesh_resource uses resource retriever to load a mesh." "\n" + " Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so," "\n" + " use the following format for mesh_resource:" "\n" + " \"embedded://mesh_name\"") + string mesh_resource; + + visualization_msgs::msg::MeshFile mesh_file; + + boolean mesh_use_embedded_materials; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/Marker.msg b/src/ros2/common_interfaces/visualization_msgs/Marker.msg new file mode 100644 index 0000000..53811d5 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/Marker.msg @@ -0,0 +1,80 @@ +# See: +# - http://www.ros.org/wiki/rviz/DisplayTypes/Marker +# - http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes +# +# for more information on using this message with rviz. + +int32 ARROW=0 +int32 CUBE=1 +int32 SPHERE=2 +int32 CYLINDER=3 +int32 LINE_STRIP=4 +int32 LINE_LIST=5 +int32 CUBE_LIST=6 +int32 SPHERE_LIST=7 +int32 POINTS=8 +int32 TEXT_VIEW_FACING=9 +int32 MESH_RESOURCE=10 +int32 TRIANGLE_LIST=11 + +int32 ADD=0 +int32 MODIFY=0 +int32 DELETE=2 +int32 DELETEALL=3 + +# Header for timestamp and frame id. +std_msgs/Header header +# Namespace in which to place the object. +# Used in conjunction with id to create a unique name for the object. +string ns +# Object ID used in conjunction with the namespace for manipulating and deleting the object later. +int32 id +# Type of object. +int32 type +# Action to take; one of: +# - 0 add/modify an object +# - 1 (deprecated) +# - 2 deletes an object (with the given ns and id) +# - 3 deletes all objects (or those with the given ns if any) +int32 action +# Pose of the object with respect the frame_id specified in the header. +geometry_msgs/Pose pose +# Scale of the object; 1,1,1 means default (usually 1 meter square). +geometry_msgs/Vector3 scale +# Color of the object; in the range: [0.0-1.0] +std_msgs/ColorRGBA color +# How long the object should last before being automatically deleted. +# 0 indicates forever. +builtin_interfaces/Duration lifetime +# If this marker should be frame-locked, i.e. retransformed into its frame every timestep. +bool frame_locked + +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +geometry_msgs/Point[] points +# Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, etc.) +# The number of colors provided must either be 0 or equal to the number of points provided. +# NOTE: alpha is not yet used +std_msgs/ColorRGBA[] colors + +# Texture resource is a special URI that can either reference a texture file in +# a format acceptable to (resource retriever)[https://index.ros.org/p/resource_retriever/] +# or an embedded texture via a string matching the format: +# "embedded://texture_name" +string texture_resource +# An image to be loaded into the rendering engine as the texture for this marker. +# This will be used iff texture_resource is set to embedded. +sensor_msgs/CompressedImage texture +# Location of each vertex within the texture; in the range: [0.0-1.0] +UVCoordinate[] uv_coordinates + +# Only used for text markers +string text + +# Only used for MESH_RESOURCE markers. +# Similar to texture_resource, mesh_resource uses resource retriever to load a mesh. +# Optionally, a mesh file can be sent in-message via the mesh_file field. If doing so, +# use the following format for mesh_resource: +# "embedded://mesh_name" +string mesh_resource +MeshFile mesh_file +bool mesh_use_embedded_materials diff --git a/src/ros2/common_interfaces/visualization_msgs/MarkerArray.idl b/src/ros2/common_interfaces/visualization_msgs/MarkerArray.idl new file mode 100644 index 0000000..7907481 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/MarkerArray.idl @@ -0,0 +1,13 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/MarkerArray.msg +// generated code does not contain a copyright notice + +#include "visualization_msgs/msg/Marker.idl" + +module visualization_msgs { + module msg { + struct MarkerArray { + sequence markers; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/MarkerArray.msg b/src/ros2/common_interfaces/visualization_msgs/MarkerArray.msg new file mode 100644 index 0000000..dd0fab4 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/MarkerArray.msg @@ -0,0 +1 @@ +Marker[] markers diff --git a/src/ros2/common_interfaces/visualization_msgs/MenuEntry.idl b/src/ros2/common_interfaces/visualization_msgs/MenuEntry.idl new file mode 100644 index 0000000..e03f231 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/MenuEntry.idl @@ -0,0 +1,66 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/MenuEntry.msg +// generated code does not contain a copyright notice + + +module visualization_msgs { + module msg { + module MenuEntry_Constants { + const uint8 FEEDBACK = 0; + const uint8 ROSRUN = 1; + const uint8 ROSLAUNCH = 2; + }; + @verbatim (language="comment", text= + " MenuEntry message." "\n" + "" "\n" + " Each InteractiveMarker message has an array of MenuEntry messages." "\n" + " A collection of MenuEntries together describe a" "\n" + " menu/submenu/subsubmenu/etc tree, though they are stored in a flat" "\n" + " array. The tree structure is represented by giving each menu entry" "\n" + " an ID number and a \"parent_id\" field. Top-level entries are the" "\n" + " ones with parent_id = 0. Menu entries are ordered within their" "\n" + " level the same way they are ordered in the containing array. Parent" "\n" + " entries must appear before their children." "\n" + "" "\n" + " Example:" "\n" + " - id = 3" "\n" + " parent_id = 0" "\n" + " title = \"fun\"" "\n" + " - id = 2" "\n" + " parent_id = 0" "\n" + " title = \"robot\"" "\n" + " - id = 4" "\n" + " parent_id = 2" "\n" + " title = \"pr2\"" "\n" + " - id = 5" "\n" + " parent_id = 2" "\n" + " title = \"turtle\"" "\n" + "" "\n" + " Gives a menu tree like this:" "\n" + " - fun" "\n" + " - robot" "\n" + " - pr2" "\n" + " - turtle") + struct MenuEntry { + @verbatim (language="comment", text= + " ID is a number for each menu entry. Must be unique within the" "\n" + " control, and should never be 0.") + uint32 id; + + @verbatim (language="comment", text= + " ID of the parent of this menu entry, if it is a submenu. If this" "\n" + " menu entry is a top-level entry, set parent_id to 0.") + uint32 parent_id; + + @verbatim (language="comment", text= + " menu / entry title") + string title; + + @verbatim (language="comment", text= + " Arguments to command indicated by command_type (below)") + string command; + + uint8 command_type; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/MenuEntry.msg b/src/ros2/common_interfaces/visualization_msgs/MenuEntry.msg new file mode 100644 index 0000000..aee5720 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/MenuEntry.msg @@ -0,0 +1,54 @@ +# MenuEntry message. +# +# Each InteractiveMarker message has an array of MenuEntry messages. +# A collection of MenuEntries together describe a +# menu/submenu/subsubmenu/etc tree, though they are stored in a flat +# array. The tree structure is represented by giving each menu entry +# an ID number and a "parent_id" field. Top-level entries are the +# ones with parent_id = 0. Menu entries are ordered within their +# level the same way they are ordered in the containing array. Parent +# entries must appear before their children. +# +# Example: +# - id = 3 +# parent_id = 0 +# title = "fun" +# - id = 2 +# parent_id = 0 +# title = "robot" +# - id = 4 +# parent_id = 2 +# title = "pr2" +# - id = 5 +# parent_id = 2 +# title = "turtle" +# +# Gives a menu tree like this: +# - fun +# - robot +# - pr2 +# - turtle + +# ID is a number for each menu entry. Must be unique within the +# control, and should never be 0. +uint32 id + +# ID of the parent of this menu entry, if it is a submenu. If this +# menu entry is a top-level entry, set parent_id to 0. +uint32 parent_id + +# menu / entry title +string title + +# Arguments to command indicated by command_type (below) +string command + +# Command_type stores the type of response desired when this menu +# entry is clicked. +# FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. +# ROSRUN: execute "rosrun" with arguments given in the command field (above). +# ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). +uint8 FEEDBACK=0 +uint8 ROSRUN=1 +uint8 ROSLAUNCH=2 +uint8 command_type diff --git a/src/ros2/common_interfaces/visualization_msgs/MeshFile.idl b/src/ros2/common_interfaces/visualization_msgs/MeshFile.idl new file mode 100644 index 0000000..0e8f7d4 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/MeshFile.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/MeshFile.msg +// generated code does not contain a copyright notice + + +module visualization_msgs { + module msg { + @verbatim (language="comment", text= + " Used to send raw mesh files.") + struct MeshFile { + @verbatim (language="comment", text= + " The filename is used for both debug purposes and to provide a file extension" "\n" + " for whatever parser is used.") + string filename; + + @verbatim (language="comment", text= + " This stores the raw text of the mesh file.") + sequence data; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/MeshFile.msg b/src/ros2/common_interfaces/visualization_msgs/MeshFile.msg new file mode 100644 index 0000000..f7c4339 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/MeshFile.msg @@ -0,0 +1,8 @@ +# Used to send raw mesh files. + +# The filename is used for both debug purposes and to provide a file extension +# for whatever parser is used. +string filename + +# This stores the raw text of the mesh file. +uint8[] data diff --git a/src/ros2/common_interfaces/visualization_msgs/UVCoordinate.idl b/src/ros2/common_interfaces/visualization_msgs/UVCoordinate.idl new file mode 100644 index 0000000..7f611ca --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/UVCoordinate.idl @@ -0,0 +1,17 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from visualization_msgs/msg/UVCoordinate.msg +// generated code does not contain a copyright notice + + +module visualization_msgs { + module msg { + @verbatim (language="comment", text= + " Location of the pixel as a ratio of the width of a 2D texture." "\n" + " Values should be in range:.") + struct UVCoordinate { + float u; + + float v; + }; + }; +}; diff --git a/src/ros2/common_interfaces/visualization_msgs/UVCoordinate.msg b/src/ros2/common_interfaces/visualization_msgs/UVCoordinate.msg new file mode 100644 index 0000000..d48b0f2 --- /dev/null +++ b/src/ros2/common_interfaces/visualization_msgs/UVCoordinate.msg @@ -0,0 +1,4 @@ +# Location of the pixel as a ratio of the width of a 2D texture. +# Values should be in range: [0.0-1.0]. +float32 u +float32 v diff --git a/src/ros2/rcl_interfaces/REF.txt b/src/ros2/rcl_interfaces/REF.txt new file mode 100644 index 0000000..e53dd12 --- /dev/null +++ b/src/ros2/rcl_interfaces/REF.txt @@ -0,0 +1,2 @@ +https://github.com/ros2/rcl_interfaces.git +@ 9c9f5935cff0eeeffe7e3eb31beba396cb22dd1a Update maintainers to Chris Lalancette (#130) diff --git a/src/ros2/rcl_interfaces/action_msgs/CancelGoal.idl b/src/ros2/rcl_interfaces/action_msgs/CancelGoal.idl new file mode 100644 index 0000000..21795b6 --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/CancelGoal.idl @@ -0,0 +1,44 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from action_msgs/srv/CancelGoal.srv +// generated code does not contain a copyright notice + +#include "action_msgs/msg/GoalInfo.idl" + +module action_msgs { + module srv { + @verbatim (language="comment", text= + " Cancel one or more goals with the following policy:" "\n" + "" "\n" + " - If the goal ID is zero and timestamp is zero, cancel all goals." "\n" + " - If the goal ID is zero and timestamp is not zero, cancel all goals accepted" "\n" + " at or before the timestamp." "\n" + " - If the goal ID is not zero and timestamp is zero, cancel the goal with the" "\n" + " given ID regardless of the time it was accepted." "\n" + " - If the goal ID is not zero and timestamp is not zero, cancel the goal with" "\n" + " the given ID and all goals accepted at or before the timestamp.") + struct CancelGoal_Request { + @verbatim (language="comment", text= + " Goal info describing the goals to cancel, see above.") + action_msgs::msg::GoalInfo goal_info; + }; + module CancelGoal_Response_Constants { + const int8 ERROR_NONE = 0; + const int8 ERROR_REJECTED = 1; + const int8 ERROR_UNKNOWN_GOAL_ID = 2; + const int8 ERROR_GOAL_TERMINATED = 3; + }; + @verbatim (language="comment", text= + "#" "\n" + "# Return codes." "\n" + "#") + struct CancelGoal_Response { + @verbatim (language="comment", text= + " Return code, see above definitions.") + int8 return_code; + + @verbatim (language="comment", text= + " Goals that accepted the cancel request.") + sequence goals_canceling; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/action_msgs/CancelGoal.srv b/src/ros2/rcl_interfaces/action_msgs/CancelGoal.srv new file mode 100644 index 0000000..86afbdb --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/CancelGoal.srv @@ -0,0 +1,46 @@ +# Cancel one or more goals with the following policy: +# +# - If the goal ID is zero and timestamp is zero, cancel all goals. +# - If the goal ID is zero and timestamp is not zero, cancel all goals accepted +# at or before the timestamp. +# - If the goal ID is not zero and timestamp is zero, cancel the goal with the +# given ID regardless of the time it was accepted. +# - If the goal ID is not zero and timestamp is not zero, cancel the goal with +# the given ID and all goals accepted at or before the timestamp. + +# Goal info describing the goals to cancel, see above. +GoalInfo goal_info +--- +## +## Return codes. +## + +# Indicates the request was accepted without any errors. +# +# One or more goals have transitioned to the CANCELING state. The +# goals_canceling list is not empty. +int8 ERROR_NONE=0 + +# Indicates the request was rejected. +# +# No goals have transitioned to the CANCELING state. The goals_canceling list is +# empty. +int8 ERROR_REJECTED=1 + +# Indicates the requested goal ID does not exist. +# +# No goals have transitioned to the CANCELING state. The goals_canceling list is +# empty. +int8 ERROR_UNKNOWN_GOAL_ID=2 + +# Indicates the goal is not cancelable because it is already in a terminal state. +# +# No goals have transitioned to the CANCELING state. The goals_canceling list is +# empty. +int8 ERROR_GOAL_TERMINATED=3 + +# Return code, see above definitions. +int8 return_code + +# Goals that accepted the cancel request. +GoalInfo[] goals_canceling diff --git a/src/ros2/rcl_interfaces/action_msgs/GoalInfo.idl b/src/ros2/rcl_interfaces/action_msgs/GoalInfo.idl new file mode 100644 index 0000000..b60fc73 --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/GoalInfo.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from action_msgs/msg/GoalInfo.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" +#include "unique_identifier_msgs/msg/UUID.idl" + +module action_msgs { + module msg { + @verbatim (language="comment", text= + " Goal ID") + struct GoalInfo { + unique_identifier_msgs::msg::UUID goal_id; + + @verbatim (language="comment", text= + " Time when the goal was accepted") + builtin_interfaces::msg::Time stamp; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/action_msgs/GoalInfo.msg b/src/ros2/rcl_interfaces/action_msgs/GoalInfo.msg new file mode 100644 index 0000000..3f16d05 --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/GoalInfo.msg @@ -0,0 +1,5 @@ +# Goal ID +unique_identifier_msgs/UUID goal_id + +# Time when the goal was accepted +builtin_interfaces/Time stamp diff --git a/src/ros2/rcl_interfaces/action_msgs/GoalStatus.idl b/src/ros2/rcl_interfaces/action_msgs/GoalStatus.idl new file mode 100644 index 0000000..a32ea0a --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/GoalStatus.idl @@ -0,0 +1,33 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from action_msgs/msg/GoalStatus.msg +// generated code does not contain a copyright notice + +#include "action_msgs/msg/GoalInfo.idl" + +module action_msgs { + module msg { + module GoalStatus_Constants { + const int8 STATUS_UNKNOWN = 0; + const int8 STATUS_ACCEPTED = 1; + const int8 STATUS_EXECUTING = 2; + const int8 STATUS_CANCELING = 3; + const int8 STATUS_SUCCEEDED = 4; + const int8 STATUS_CANCELED = 5; + const int8 STATUS_ABORTED = 6; + }; + @verbatim (language="comment", text= + " An action goal can be in one of these states after it is accepted by an action" "\n" + " server." "\n" + "" "\n" + " For more information, see http://design.ros2.org/articles/actions.html") + struct GoalStatus { + @verbatim (language="comment", text= + " Goal info (contains ID and timestamp).") + action_msgs::msg::GoalInfo goal_info; + + @verbatim (language="comment", text= + " Action goal state-machine status.") + int8 status; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/action_msgs/GoalStatus.msg b/src/ros2/rcl_interfaces/action_msgs/GoalStatus.msg new file mode 100644 index 0000000..6e84a91 --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/GoalStatus.msg @@ -0,0 +1,32 @@ +# An action goal can be in one of these states after it is accepted by an action +# server. +# +# For more information, see http://design.ros2.org/articles/actions.html + +# Indicates status has not been properly set. +int8 STATUS_UNKNOWN = 0 + +# The goal has been accepted and is awaiting execution. +int8 STATUS_ACCEPTED = 1 + +# The goal is currently being executed by the action server. +int8 STATUS_EXECUTING = 2 + +# The client has requested that the goal be canceled and the action server has +# accepted the cancel request. +int8 STATUS_CANCELING = 3 + +# The goal was achieved successfully by the action server. +int8 STATUS_SUCCEEDED = 4 + +# The goal was canceled after an external request from an action client. +int8 STATUS_CANCELED = 5 + +# The goal was terminated by the action server without an external request. +int8 STATUS_ABORTED = 6 + +# Goal info (contains ID and timestamp). +GoalInfo goal_info + +# Action goal state-machine status. +int8 status diff --git a/src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.idl b/src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.idl new file mode 100644 index 0000000..d9d4b0c --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.idl @@ -0,0 +1,15 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from action_msgs/msg/GoalStatusArray.msg +// generated code does not contain a copyright notice + +#include "action_msgs/msg/GoalStatus.idl" + +module action_msgs { + module msg { + @verbatim (language="comment", text= + " An array of goal statuses.") + struct GoalStatusArray { + sequence status_list; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.msg b/src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.msg new file mode 100644 index 0000000..3b68b0e --- /dev/null +++ b/src/ros2/rcl_interfaces/action_msgs/GoalStatusArray.msg @@ -0,0 +1,2 @@ +# An array of goal statuses. +GoalStatus[] status_list diff --git a/src/ros2/rcl_interfaces/builtin_interfaces/Duration.idl b/src/ros2/rcl_interfaces/builtin_interfaces/Duration.idl new file mode 100644 index 0000000..83d8a1f --- /dev/null +++ b/src/ros2/rcl_interfaces/builtin_interfaces/Duration.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from builtin_interfaces/msg/Duration.msg +// generated code does not contain a copyright notice + + +module builtin_interfaces { + module msg { + @verbatim (language="comment", text= + " Duration defines a period between two time points." "\n" + " Messages of this datatype are of ROS Time following this design:" "\n" + " https://design.ros2.org/articles/clock_and_time.html") + struct Duration { + @verbatim (language="comment", text= + " Seconds component, range is valid over any possible int32 value.") + int32 sec; + + @verbatim (language="comment", text= + " Nanoseconds component in the range of [0, 10e9).") + uint32 nanosec; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/builtin_interfaces/Duration.msg b/src/ros2/rcl_interfaces/builtin_interfaces/Duration.msg new file mode 100644 index 0000000..fab5e4f --- /dev/null +++ b/src/ros2/rcl_interfaces/builtin_interfaces/Duration.msg @@ -0,0 +1,9 @@ +# Duration defines a period between two time points. +# Messages of this datatype are of ROS Time following this design: +# https://design.ros2.org/articles/clock_and_time.html + +# Seconds component, range is valid over any possible int32 value. +int32 sec + +# Nanoseconds component in the range of [0, 10e9). +uint32 nanosec diff --git a/src/ros2/rcl_interfaces/builtin_interfaces/Time.idl b/src/ros2/rcl_interfaces/builtin_interfaces/Time.idl new file mode 100644 index 0000000..7e532c8 --- /dev/null +++ b/src/ros2/rcl_interfaces/builtin_interfaces/Time.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from builtin_interfaces/msg/Time.msg +// generated code does not contain a copyright notice + + +module builtin_interfaces { + module msg { + @verbatim (language="comment", text= + " This message communicates ROS Time defined here:" "\n" + " https://design.ros2.org/articles/clock_and_time.html") + struct Time { + @verbatim (language="comment", text= + " The seconds component, valid over all int32 values.") + int32 sec; + + @verbatim (language="comment", text= + " The nanoseconds component, valid in the range [0, 10e9).") + uint32 nanosec; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/builtin_interfaces/Time.msg b/src/ros2/rcl_interfaces/builtin_interfaces/Time.msg new file mode 100644 index 0000000..874f15e --- /dev/null +++ b/src/ros2/rcl_interfaces/builtin_interfaces/Time.msg @@ -0,0 +1,8 @@ +# This message communicates ROS Time defined here: +# https://design.ros2.org/articles/clock_and_time.html + +# The seconds component, valid over all int32 values. +int32 sec + +# The nanoseconds component, valid in the range [0, 10e9). +uint32 nanosec diff --git a/src/ros2/rcl_interfaces/composition_interfaces/ListNodes.idl b/src/ros2/rcl_interfaces/composition_interfaces/ListNodes.idl new file mode 100644 index 0000000..680b9dd --- /dev/null +++ b/src/ros2/rcl_interfaces/composition_interfaces/ListNodes.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from composition_interfaces/srv/ListNodes.srv +// generated code does not contain a copyright notice + + +module composition_interfaces { + module srv { + struct ListNodes_Request { + uint8 structure_needs_at_least_one_member; + }; + @verbatim (language="comment", text= + " List of full node names including namespace.") + struct ListNodes_Response { + sequence full_node_names; + + @verbatim (language="comment", text= + " corresponding unique ids (must have same length as full_node_names).") + sequence unique_ids; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/composition_interfaces/ListNodes.srv b/src/ros2/rcl_interfaces/composition_interfaces/ListNodes.srv new file mode 100644 index 0000000..4b1421e --- /dev/null +++ b/src/ros2/rcl_interfaces/composition_interfaces/ListNodes.srv @@ -0,0 +1,5 @@ +--- +# List of full node names including namespace. +string[] full_node_names +# corresponding unique ids (must have same length as full_node_names). +uint64[] unique_ids diff --git a/src/ros2/rcl_interfaces/composition_interfaces/LoadNode.idl b/src/ros2/rcl_interfaces/composition_interfaces/LoadNode.idl new file mode 100644 index 0000000..ff53f26 --- /dev/null +++ b/src/ros2/rcl_interfaces/composition_interfaces/LoadNode.idl @@ -0,0 +1,67 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from composition_interfaces/srv/LoadNode.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/Parameter.idl" + +module composition_interfaces { + module srv { + @verbatim (language="comment", text= + " The ROS package in which the composable node can be found.") + struct LoadNode_Request { + string package_name; + + @verbatim (language="comment", text= + " A plugin within the ROS package \"package_name\".") + string plugin_name; + + @verbatim (language="comment", text= + " The assigned name of the composable node. Leave empty to use the node's" "\n" + " default name.") + string node_name; + + @verbatim (language="comment", text= + " The assigned namespace of the composable node. Leave empty to use the node's" "\n" + " default namespace.") + string node_namespace; + + @verbatim (language="comment", text= + " The assigned log level of the composable node. Enum values are found in" "\n" + " message rcl_interfaces/Log.") + uint8 log_level; + + @verbatim (language="comment", text= + " Remapping rules for this composable node." "\n" + "" "\n" + " For more info about static_remapping rules and their syntax, see" "\n" + " https://design.ros2.org/articles/static_remapping.html" "\n" + " TODO(sloretz) rcl_interfaces message for remap rules?") + sequence remap_rules; + + @verbatim (language="comment", text= + " The Parameters of this composable node to set.") + sequence parameters; + + @verbatim (language="comment", text= + " key/value arguments that are specific to a type of container process.") + sequence extra_arguments; + }; + @verbatim (language="comment", text= + " True if the node was successfully loaded.") + struct LoadNode_Response { + boolean success; + + @verbatim (language="comment", text= + " Human readable error message if success is false, else empty string.") + string error_message; + + @verbatim (language="comment", text= + " Name of the loaded composable node (including namespace).") + string full_node_name; + + @verbatim (language="comment", text= + " A unique identifier for the loaded node.") + uint64 unique_id; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/composition_interfaces/LoadNode.srv b/src/ros2/rcl_interfaces/composition_interfaces/LoadNode.srv new file mode 100644 index 0000000..ffd243f --- /dev/null +++ b/src/ros2/rcl_interfaces/composition_interfaces/LoadNode.srv @@ -0,0 +1,42 @@ +# The ROS package in which the composable node can be found. +string package_name + +# A plugin within the ROS package "package_name". +string plugin_name + +# The assigned name of the composable node. Leave empty to use the node's +# default name. +string node_name + +# The assigned namespace of the composable node. Leave empty to use the node's +# default namespace. +string node_namespace + +# The assigned log level of the composable node. Enum values are found in +# message rcl_interfaces/Log. +uint8 log_level + +# Remapping rules for this composable node. +# +# For more info about static_remapping rules and their syntax, see +# https://design.ros2.org/articles/static_remapping.html +# TODO(sloretz) rcl_interfaces message for remap rules? +string[] remap_rules + +# The Parameters of this composable node to set. +rcl_interfaces/Parameter[] parameters + +# key/value arguments that are specific to a type of container process. +rcl_interfaces/Parameter[] extra_arguments +--- +# True if the node was successfully loaded. +bool success + +# Human readable error message if success is false, else empty string. +string error_message + +# Name of the loaded composable node (including namespace). +string full_node_name + +# A unique identifier for the loaded node. +uint64 unique_id diff --git a/src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.idl b/src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.idl new file mode 100644 index 0000000..4dea9e5 --- /dev/null +++ b/src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from composition_interfaces/srv/UnloadNode.srv +// generated code does not contain a copyright notice + + +module composition_interfaces { + module srv { + @verbatim (language="comment", text= + " Container specific unique id of a loaded node.") + struct UnloadNode_Request { + uint64 unique_id; + }; + @verbatim (language="comment", text= + " True if the node existed and was unloaded.") + struct UnloadNode_Response { + boolean success; + + @verbatim (language="comment", text= + " Human readable error message if success is false, else empty string.") + string error_message; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.srv b/src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.srv new file mode 100644 index 0000000..0fa36a5 --- /dev/null +++ b/src/ros2/rcl_interfaces/composition_interfaces/UnloadNode.srv @@ -0,0 +1,8 @@ +# Container specific unique id of a loaded node. +uint64 unique_id +--- +# True if the node existed and was unloaded. +bool success + +# Human readable error message if success is false, else empty string. +string error_message diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.idl new file mode 100644 index 0000000..079f996 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from lifecycle_msgs/srv/ChangeState.srv +// generated code does not contain a copyright notice + +#include "lifecycle_msgs/msg/Transition.idl" + +module lifecycle_msgs { + module srv { + @verbatim (language="comment", text= + " The requested transition." "\n" + "" "\n" + " This change state service will fail if the transition is not possible.") + struct ChangeState_Request { + lifecycle_msgs::msg::Transition transition; + }; + struct ChangeState_Response { + @verbatim (language="comment", text= + " Indicates whether the service was able to initiate the state transition") + boolean success; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.srv b/src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.srv new file mode 100644 index 0000000..1bad3d1 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/ChangeState.srv @@ -0,0 +1,8 @@ +# The requested transition. +# +# This change state service will fail if the transition is not possible. +Transition transition +--- + +# Indicates whether the service was able to initiate the state transition +bool success diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.idl new file mode 100644 index 0000000..d0deeef --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from lifecycle_msgs/srv/GetAvailableStates.srv +// generated code does not contain a copyright notice + +#include "lifecycle_msgs/msg/State.idl" + +module lifecycle_msgs { + module srv { + struct GetAvailableStates_Request { + uint8 structure_needs_at_least_one_member; + }; + @verbatim (language="comment", text= + " Array of possible states that can be transitioned to.") + struct GetAvailableStates_Response { + sequence available_states; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.srv b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.srv new file mode 100644 index 0000000..2faa79b --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableStates.srv @@ -0,0 +1,3 @@ +--- +# Array of possible states that can be transitioned to. +State[] available_states diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.idl new file mode 100644 index 0000000..3634772 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from lifecycle_msgs/srv/GetAvailableTransitions.srv +// generated code does not contain a copyright notice + +#include "lifecycle_msgs/msg/TransitionDescription.idl" + +module lifecycle_msgs { + module srv { + struct GetAvailableTransitions_Request { + uint8 structure_needs_at_least_one_member; + }; + @verbatim (language="comment", text= + " An array of the possible start_state-goal_state transitions") + struct GetAvailableTransitions_Response { + sequence available_transitions; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.srv b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.srv new file mode 100644 index 0000000..a7f4e50 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/GetAvailableTransitions.srv @@ -0,0 +1,3 @@ +--- +# An array of the possible start_state-goal_state transitions +TransitionDescription[] available_transitions diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/GetState.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/GetState.idl new file mode 100644 index 0000000..9fd43dc --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/GetState.idl @@ -0,0 +1,18 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from lifecycle_msgs/srv/GetState.srv +// generated code does not contain a copyright notice + +#include "lifecycle_msgs/msg/State.idl" + +module lifecycle_msgs { + module srv { + struct GetState_Request { + uint8 structure_needs_at_least_one_member; + }; + @verbatim (language="comment", text= + " The current state-machine state of the node.") + struct GetState_Response { + lifecycle_msgs::msg::State current_state; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/GetState.srv b/src/ros2/rcl_interfaces/lifecycle_msgs/GetState.srv new file mode 100644 index 0000000..b2569fa --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/GetState.srv @@ -0,0 +1,3 @@ +--- +# The current state-machine state of the node. +State current_state diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/State.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/State.idl new file mode 100644 index 0000000..3a9c876 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/State.idl @@ -0,0 +1,34 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from lifecycle_msgs/msg/State.msg +// generated code does not contain a copyright notice + + +module lifecycle_msgs { + module msg { + module State_Constants { + const uint8 PRIMARY_STATE_UNKNOWN = 0; + const uint8 PRIMARY_STATE_UNCONFIGURED = 1; + const uint8 PRIMARY_STATE_INACTIVE = 2; + const uint8 PRIMARY_STATE_ACTIVE = 3; + const uint8 PRIMARY_STATE_FINALIZED = 4; + const uint8 TRANSITION_STATE_CONFIGURING = 10; + const uint8 TRANSITION_STATE_CLEANINGUP = 11; + const uint8 TRANSITION_STATE_SHUTTINGDOWN = 12; + const uint8 TRANSITION_STATE_ACTIVATING = 13; + const uint8 TRANSITION_STATE_DEACTIVATING = 14; + const uint8 TRANSITION_STATE_ERRORPROCESSING = 15; + }; + @verbatim (language="comment", text= + " Primary state definitions as depicted in:" "\n" + " http://design.ros2.org/articles/node_lifecycle.html") + struct State { + @verbatim (language="comment", text= + " The state id value from the above definitions.") + uint8 id; + + @verbatim (language="comment", text= + " A text label of the state.") + string label; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/State.msg b/src/ros2/rcl_interfaces/lifecycle_msgs/State.msg new file mode 100644 index 0000000..4fd07b1 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/State.msg @@ -0,0 +1,57 @@ +# Primary state definitions as depicted in: +# http://design.ros2.org/articles/node_lifecycle.html + +# These are the primary states. State changes can only be requested when the +# node is in one of these states. + +# Indicates state has not yet been set. +uint8 PRIMARY_STATE_UNKNOWN = 0 + +# This is the life cycle state the node is in immediately after being +# instantiated. +uint8 PRIMARY_STATE_UNCONFIGURED = 1 + +# This state represents a node that is not currently performing any processing. +uint8 PRIMARY_STATE_INACTIVE = 2 + +# This is the main state of the node’s life cycle. While in this state, the node +# performs any processing, responds to service requests, reads and processes +# data, produces output, etc. +uint8 PRIMARY_STATE_ACTIVE = 3 + +# The finalized state is the state in which the node ends immediately before +# being destroyed. +uint8 PRIMARY_STATE_FINALIZED = 4 + +# Temporary intermediate states. When a transition is requested, the node +# changes its state into one of these states. + +# In this transition state the node’s onConfigure callback will be called to +# allow the node to load its configuration and conduct any required setup. +uint8 TRANSITION_STATE_CONFIGURING = 10 + +# In this transition state the node’s callback onCleanup will be called to clear +# all state and return the node to a functionally equivalent state as when +# first created. +uint8 TRANSITION_STATE_CLEANINGUP = 11 + +# In this transition state the callback onShutdown will be executed to do any +# cleanup necessary before destruction. +uint8 TRANSITION_STATE_SHUTTINGDOWN = 12 + +# In this transition state the callback onActivate will be executed to do any +# final preparations to start executing. +uint8 TRANSITION_STATE_ACTIVATING = 13 + +# In this transition state the callback onDeactivate will be executed to do any +# cleanup to start executing, and reverse the onActivate changes. +uint8 TRANSITION_STATE_DEACTIVATING = 14 + +# This transition state is where any error may be cleaned up. +uint8 TRANSITION_STATE_ERRORPROCESSING = 15 + +# The state id value from the above definitions. +uint8 id + +# A text label of the state. +string label diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/Transition.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/Transition.idl new file mode 100644 index 0000000..dd9ecf7 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/Transition.idl @@ -0,0 +1,56 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from lifecycle_msgs/msg/Transition.msg +// generated code does not contain a copyright notice + + +module lifecycle_msgs { + module msg { + module Transition_Constants { + const uint8 TRANSITION_CREATE = 0; + const uint8 TRANSITION_CONFIGURE = 1; + const uint8 TRANSITION_CLEANUP = 2; + const uint8 TRANSITION_ACTIVATE = 3; + const uint8 TRANSITION_DEACTIVATE = 4; + const uint8 TRANSITION_UNCONFIGURED_SHUTDOWN = 5; + const uint8 TRANSITION_INACTIVE_SHUTDOWN = 6; + const uint8 TRANSITION_ACTIVE_SHUTDOWN = 7; + const uint8 TRANSITION_DESTROY = 8; + const uint8 TRANSITION_ON_CONFIGURE_SUCCESS = 10; + const uint8 TRANSITION_ON_CONFIGURE_FAILURE = 11; + const uint8 TRANSITION_ON_CONFIGURE_ERROR = 12; + const uint8 TRANSITION_ON_CLEANUP_SUCCESS = 20; + const uint8 TRANSITION_ON_CLEANUP_FAILURE = 21; + const uint8 TRANSITION_ON_CLEANUP_ERROR = 22; + const uint8 TRANSITION_ON_ACTIVATE_SUCCESS = 30; + const uint8 TRANSITION_ON_ACTIVATE_FAILURE = 31; + const uint8 TRANSITION_ON_ACTIVATE_ERROR = 32; + const uint8 TRANSITION_ON_DEACTIVATE_SUCCESS = 40; + const uint8 TRANSITION_ON_DEACTIVATE_FAILURE = 41; + const uint8 TRANSITION_ON_DEACTIVATE_ERROR = 42; + const uint8 TRANSITION_ON_SHUTDOWN_SUCCESS = 50; + const uint8 TRANSITION_ON_SHUTDOWN_FAILURE = 51; + const uint8 TRANSITION_ON_SHUTDOWN_ERROR = 52; + const uint8 TRANSITION_ON_ERROR_SUCCESS = 60; + const uint8 TRANSITION_ON_ERROR_FAILURE = 61; + const uint8 TRANSITION_ON_ERROR_ERROR = 62; + const uint8 TRANSITION_CALLBACK_SUCCESS = 97; + const uint8 TRANSITION_CALLBACK_FAILURE = 98; + const uint8 TRANSITION_CALLBACK_ERROR = 99; + }; + @verbatim (language="comment", text= + " Default values for transitions as described in:" "\n" + " http://design.ros2.org/articles/node_lifecycle.html") + struct Transition { + @verbatim (language="comment", text= + "#" "\n" + "# Fields" "\n" + "#" "\n" + " The transition id from above definitions.") + uint8 id; + + @verbatim (language="comment", text= + " A text label of the transition.") + string label; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/Transition.msg b/src/ros2/rcl_interfaces/lifecycle_msgs/Transition.msg new file mode 100644 index 0000000..8b09a2d --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/Transition.msg @@ -0,0 +1,94 @@ +# Default values for transitions as described in: +# http://design.ros2.org/articles/node_lifecycle.html + +# Reserved [0-9], publicly available transitions. +# When a node is in one of these primary states, these transitions can be +# invoked. + +# This transition will instantiate the node, but will not run any code beyond +# the constructor. +uint8 TRANSITION_CREATE = 0 + +# The node’s onConfigure callback will be called to allow the node to load its +# configuration and conduct any required setup. +uint8 TRANSITION_CONFIGURE = 1 + +# The node’s callback onCleanup will be called in this transition to allow the +# node to load its configuration and conduct any required setup. +uint8 TRANSITION_CLEANUP = 2 + +# The node's callback onActivate will be executed to do any final preparations +# to start executing. +uint8 TRANSITION_ACTIVATE = 3 + +# The node's callback onDeactivate will be executed to do any cleanup to start +# executing, and reverse the onActivate changes. +uint8 TRANSITION_DEACTIVATE = 4 + +# This signals shutdown during an unconfigured state, the node's callback +# onShutdown will be executed to do any cleanup necessary before destruction. +uint8 TRANSITION_UNCONFIGURED_SHUTDOWN = 5 + +# This signals shutdown during an inactive state, the node's callback onShutdown +# will be executed to do any cleanup necessary before destruction. +uint8 TRANSITION_INACTIVE_SHUTDOWN = 6 + +# This signals shutdown during an active state, the node's callback onShutdown +# will be executed to do any cleanup necessary before destruction. +uint8 TRANSITION_ACTIVE_SHUTDOWN = 7 + +# This transition will simply cause the deallocation of the node. +uint8 TRANSITION_DESTROY = 8 + +# Reserved [10-69], private transitions +# These transitions are not publicly available and cannot be invoked by a user. +# The following transitions are implicitly invoked based on the callback +# feedback of the intermediate transition states. +uint8 TRANSITION_ON_CONFIGURE_SUCCESS = 10 +uint8 TRANSITION_ON_CONFIGURE_FAILURE = 11 +uint8 TRANSITION_ON_CONFIGURE_ERROR = 12 + +uint8 TRANSITION_ON_CLEANUP_SUCCESS = 20 +uint8 TRANSITION_ON_CLEANUP_FAILURE = 21 +uint8 TRANSITION_ON_CLEANUP_ERROR = 22 + +uint8 TRANSITION_ON_ACTIVATE_SUCCESS = 30 +uint8 TRANSITION_ON_ACTIVATE_FAILURE = 31 +uint8 TRANSITION_ON_ACTIVATE_ERROR = 32 + +uint8 TRANSITION_ON_DEACTIVATE_SUCCESS = 40 +uint8 TRANSITION_ON_DEACTIVATE_FAILURE = 41 +uint8 TRANSITION_ON_DEACTIVATE_ERROR = 42 + +uint8 TRANSITION_ON_SHUTDOWN_SUCCESS = 50 +uint8 TRANSITION_ON_SHUTDOWN_FAILURE = 51 +uint8 TRANSITION_ON_SHUTDOWN_ERROR = 52 + +uint8 TRANSITION_ON_ERROR_SUCCESS = 60 +uint8 TRANSITION_ON_ERROR_FAILURE = 61 +uint8 TRANSITION_ON_ERROR_ERROR = 62 + +# Reserved [90-99]. Transition callback success values. +# These return values ought to be set as a return value for each callback. +# Depending on which return value, the transition will be executed correctly or +# fallback/error callbacks will be triggered. + +# The transition callback successfully performed its required functionality. +uint8 TRANSITION_CALLBACK_SUCCESS = 97 + +# The transition callback failed to perform its required functionality. +uint8 TRANSITION_CALLBACK_FAILURE = 98 + +# The transition callback encountered an error that requires special cleanup, if +# possible. +uint8 TRANSITION_CALLBACK_ERROR = 99 + +## +## Fields +## + +# The transition id from above definitions. +uint8 id + +# A text label of the transition. +string label diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.idl new file mode 100644 index 0000000..5b890da --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.idl @@ -0,0 +1,24 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from lifecycle_msgs/msg/TransitionDescription.msg +// generated code does not contain a copyright notice + +#include "lifecycle_msgs/msg/State.idl" +#include "lifecycle_msgs/msg/Transition.idl" + +module lifecycle_msgs { + module msg { + @verbatim (language="comment", text= + " The transition id and label of this description.") + struct TransitionDescription { + lifecycle_msgs::msg::Transition transition; + + @verbatim (language="comment", text= + " The current state from which this transition transitions.") + lifecycle_msgs::msg::State start_state; + + @verbatim (language="comment", text= + " The desired target state of this transition.") + lifecycle_msgs::msg::State goal_state; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.msg b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.msg new file mode 100644 index 0000000..b028173 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionDescription.msg @@ -0,0 +1,8 @@ +# The transition id and label of this description. +Transition transition + +# The current state from which this transition transitions. +State start_state + +# The desired target state of this transition. +State goal_state diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.idl b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.idl new file mode 100644 index 0000000..bdf9f04 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.idl @@ -0,0 +1,28 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from lifecycle_msgs/msg/TransitionEvent.msg +// generated code does not contain a copyright notice + +#include "lifecycle_msgs/msg/State.idl" +#include "lifecycle_msgs/msg/Transition.idl" + +module lifecycle_msgs { + module msg { + @verbatim (language="comment", text= + " The time point at which this event occurred.") + struct TransitionEvent { + uint64 timestamp; + + @verbatim (language="comment", text= + " The id and label of this transition event.") + lifecycle_msgs::msg::Transition transition; + + @verbatim (language="comment", text= + " The starting state from which this event transitioned.") + lifecycle_msgs::msg::State start_state; + + @verbatim (language="comment", text= + " The end state of this transition event.") + lifecycle_msgs::msg::State goal_state; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.msg b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.msg new file mode 100644 index 0000000..48c8499 --- /dev/null +++ b/src/ros2/rcl_interfaces/lifecycle_msgs/TransitionEvent.msg @@ -0,0 +1,11 @@ +# The time point at which this event occurred. +uint64 timestamp + +# The id and label of this transition event. +Transition transition + +# The starting state from which this event transitioned. +State start_state + +# The end state of this transition event. +State goal_state diff --git a/src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.idl b/src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.idl new file mode 100644 index 0000000..3f2e5ab --- /dev/null +++ b/src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.idl @@ -0,0 +1,49 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from statistics_msgs/msg/MetricsMessage.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" +#include "statistics_msgs/msg/StatisticDataPoint.idl" + +module statistics_msgs { + module msg { + @verbatim (language="comment", text= + "############################################" "\n" + " A generic metrics message providing statistics for measurements from different sources. For example," "\n" + " measure a system's CPU % for a given window yields the following data points over a window of time:" "\n" + "" "\n" + " - average cpu %" "\n" + " - std deviation" "\n" + " - min" "\n" + " - max" "\n" + " - sample count" "\n" + "" "\n" + " These are all represented as different 'StatisticDataPoint's." "\n" + "############################################") + struct MetricsMessage { + @verbatim (language="comment", text= + " Name metric measurement source, e.g., node, topic, or process name") + string measurement_source_name; + + @verbatim (language="comment", text= + " Name of the metric being measured, e.g. cpu_percentage, free_memory_mb, message_age, etc.") + string metrics_source; + + @verbatim (language="comment", text= + " Unit of measure of the metric, e.g. percent, mb, seconds, etc.") + string unit; + + @verbatim (language="comment", text= + " Measurement window start time") + builtin_interfaces::msg::Time window_start; + + @verbatim (language="comment", text= + " Measurement window end time") + builtin_interfaces::msg::Time window_stop; + + @verbatim (language="comment", text= + " A list of statistics data point, defined in StatisticDataPoint.msg") + sequence statistics; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.msg b/src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.msg new file mode 100644 index 0000000..f4f1731 --- /dev/null +++ b/src/ros2/rcl_interfaces/metrics_statistics_msgs/MetricsMessage.msg @@ -0,0 +1,30 @@ +############################################# +# A generic metrics message providing statistics for measurements from different sources. For example, +# measure a system's CPU % for a given window yields the following data points over a window of time: +# +# - average cpu % +# - std deviation +# - min +# - max +# - sample count +# +# These are all represented as different 'StatisticDataPoint's. +############################################# + +# Name metric measurement source, e.g., node, topic, or process name +string measurement_source_name + +# Name of the metric being measured, e.g. cpu_percentage, free_memory_mb, message_age, etc. +string metrics_source + +# Unit of measure of the metric, e.g. percent, mb, seconds, etc. +string unit + +# Measurement window start time +builtin_interfaces/Time window_start + +# Measurement window end time +builtin_interfaces/Time window_stop + +# A list of statistics data point, defined in StatisticDataPoint.msg +StatisticDataPoint[] statistics diff --git a/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.idl b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.idl new file mode 100644 index 0000000..ca747ac --- /dev/null +++ b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.idl @@ -0,0 +1,36 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from statistics_msgs/msg/StatisticDataPoint.msg +// generated code does not contain a copyright notice + + +module statistics_msgs { + module msg { + @verbatim (language="comment", text= + "############################################" "\n" + " This holds the structure of a single data point of a StatisticDataType." "\n" + "" "\n" + " This message is used in MetricsStatisticsMessage, defined in MetricsStatisticsMessage.msg." "\n" + "" "\n" + " Examples of the value of data point are" "\n" + " - average size of messages received" "\n" + " - standard deviation of the period of messages published" "\n" + " - maximum age of messages published" "\n" + "" "\n" + " A value of nan represents no data is available." "\n" + " One example is that standard deviation is only available when there are two or more data points but there is only one," "\n" + " and in this case the value would be nan." "\n" + " +inf and -inf are not allowed." "\n" + "" "\n" + "############################################") + struct StatisticDataPoint { + @verbatim (language="comment", text= + " The statistic type of this data point, defined in StatisticDataType.msg" "\n" + " Default value should be StatisticDataType.STATISTICS_DATA_TYPE_UNINITIALIZED (0).") + uint8 data_type; + + @verbatim (language="comment", text= + " The value of the data point") + double data; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.msg b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.msg new file mode 100644 index 0000000..eafea35 --- /dev/null +++ b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataPoint.msg @@ -0,0 +1,23 @@ +############################################# +# This holds the structure of a single data point of a StatisticDataType. +# +# This message is used in MetricsStatisticsMessage, defined in MetricsStatisticsMessage.msg. +# +# Examples of the value of data point are +# - average size of messages received +# - standard deviation of the period of messages published +# - maximum age of messages published +# +# A value of nan represents no data is available. +# One example is that standard deviation is only available when there are two or more data points but there is only one, +# and in this case the value would be nan. +# +inf and -inf are not allowed. +# +############################################# + +# The statistic type of this data point, defined in StatisticDataType.msg +# Default value should be StatisticDataType.STATISTICS_DATA_TYPE_UNINITIALIZED (0). +uint8 data_type + +# The value of the data point +float64 data diff --git a/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.idl b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.idl new file mode 100644 index 0000000..b82a9c1 --- /dev/null +++ b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.idl @@ -0,0 +1,29 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from statistics_msgs/msg/StatisticDataType.msg +// generated code does not contain a copyright notice + + +module statistics_msgs { + module msg { + module StatisticDataType_Constants { + const uint8 STATISTICS_DATA_TYPE_UNINITIALIZED = 0; + const uint8 STATISTICS_DATA_TYPE_AVERAGE = 1; + const uint8 STATISTICS_DATA_TYPE_MINIMUM = 2; + const uint8 STATISTICS_DATA_TYPE_MAXIMUM = 3; + const uint8 STATISTICS_DATA_TYPE_STDDEV = 4; + const uint8 STATISTICS_DATA_TYPE_SAMPLE_COUNT = 5; + }; + @verbatim (language="comment", text= + "############################################" "\n" + " This file contains the commonly used constants for the statistics data type." "\n" + "" "\n" + " The value 0 is reserved for unitialized statistic message data type." "\n" + " Range of values: [0, 255]." "\n" + " Unallowed values: any value that is not specified in this file." "\n" + "" "\n" + "############################################") + struct StatisticDataType { + uint8 structure_needs_at_least_one_member; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.msg b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.msg new file mode 100644 index 0000000..70f9184 --- /dev/null +++ b/src/ros2/rcl_interfaces/metrics_statistics_msgs/StatisticDataType.msg @@ -0,0 +1,18 @@ +############################################# +# This file contains the commonly used constants for the statistics data type. +# +# The value 0 is reserved for unitialized statistic message data type. +# Range of values: [0, 255]. +# Unallowed values: any value that is not specified in this file. +# +############################################# + +# Constant for uninitialized +uint8 STATISTICS_DATA_TYPE_UNINITIALIZED = 0 + +# Allowed values +uint8 STATISTICS_DATA_TYPE_AVERAGE = 1 +uint8 STATISTICS_DATA_TYPE_MINIMUM = 2 +uint8 STATISTICS_DATA_TYPE_MAXIMUM = 3 +uint8 STATISTICS_DATA_TYPE_STDDEV = 4 +uint8 STATISTICS_DATA_TYPE_SAMPLE_COUNT = 5 diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.idl b/src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.idl new file mode 100644 index 0000000..77d7012 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.idl @@ -0,0 +1,22 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/DescribeParameters.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/ParameterDescriptor.idl" + +module rcl_interfaces { + module srv { + @verbatim (language="comment", text= + " A list of parameters of which to get the descriptor.") + struct DescribeParameters_Request { + sequence names; + }; + @verbatim (language="comment", text= + " A list of the descriptors of all parameters requested in the same order" "\n" + " as they were requested. This list has the same length as the list of" "\n" + " parameters requested.") + struct DescribeParameters_Response { + sequence descriptors; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.srv b/src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.srv new file mode 100644 index 0000000..a8f0b91 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/DescribeParameters.srv @@ -0,0 +1,8 @@ +# A list of parameters of which to get the descriptor. +string[] names + +--- +# A list of the descriptors of all parameters requested in the same order +# as they were requested. This list has the same length as the list of +# parameters requested. +ParameterDescriptor[] descriptors diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.idl b/src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.idl new file mode 100644 index 0000000..c6bc060 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.idl @@ -0,0 +1,42 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/FloatingPointRange.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " Represents bounds and a step value for a floating point typed parameter.") + struct FloatingPointRange { + @verbatim (language="comment", text= + " Start value for valid values, inclusive.") + double from_value; + + @verbatim (language="comment", text= + " End value for valid values, inclusive.") + double to_value; + + @verbatim (language="comment", text= + " Size of valid steps between the from and to bound." "\n" + "" "\n" + " Step is considered to be a magnitude, therefore negative values are treated" "\n" + " the same as positive values, and a step value of zero implies a continuous" "\n" + " range of values." "\n" + "" "\n" + " Ideally, the step would be less than or equal to the distance between the" "\n" + " bounds, as well as an even multiple of the distance between the bounds, but" "\n" + " neither are required." "\n" + "" "\n" + " If the absolute value of the step is larger than or equal to the distance" "\n" + " between the two bounds, then the bounds will be the only valid values. e.g. if" "\n" + " the range is defined as {from_value: 1.0, to_value: 2.0, step: 5.0} then the" "\n" + " valid values will be 1.0 and 2.0." "\n" + "" "\n" + " If the step is less than the distance between the bounds, but the distance is" "\n" + " not a multiple of the step, then the \"to\" bound will always be a valid value," "\n" + " e.g. if the range is defined as {from_value: 2.0, to_value: 5.0, step: 2.0}" "\n" + " then the valid values will be 2.0, 4.0, and 5.0.") + double step; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.msg b/src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.msg new file mode 100644 index 0000000..a2ececa --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/FloatingPointRange.msg @@ -0,0 +1,28 @@ +# Represents bounds and a step value for a floating point typed parameter. + +# Start value for valid values, inclusive. +float64 from_value + +# End value for valid values, inclusive. +float64 to_value + +# Size of valid steps between the from and to bound. +# +# Step is considered to be a magnitude, therefore negative values are treated +# the same as positive values, and a step value of zero implies a continuous +# range of values. +# +# Ideally, the step would be less than or equal to the distance between the +# bounds, as well as an even multiple of the distance between the bounds, but +# neither are required. +# +# If the absolute value of the step is larger than or equal to the distance +# between the two bounds, then the bounds will be the only valid values. e.g. if +# the range is defined as {from_value: 1.0, to_value: 2.0, step: 5.0} then the +# valid values will be 1.0 and 2.0. +# +# If the step is less than the distance between the bounds, but the distance is +# not a multiple of the step, then the "to" bound will always be a valid value, +# e.g. if the range is defined as {from_value: 2.0, to_value: 5.0, step: 2.0} +# then the valid values will be 2.0, 4.0, and 5.0. +float64 step diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.idl b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.idl new file mode 100644 index 0000000..60eac41 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/GetParameterTypes.srv +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module srv { + @verbatim (language="comment", text= + " A list of parameter names." "\n" + " TODO(wjwwood): link to parameter naming rules.") + struct GetParameterTypes_Request { + sequence names; + }; + @verbatim (language="comment", text= + " List of types which is the same length and order as the provided names." "\n" + "" "\n" + " The type enum is defined in ParameterType.msg. ParameterType.PARAMETER_NOT_SET" "\n" + " indicates that the parameter is not currently set.") + struct GetParameterTypes_Response { + sequence types; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.srv b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.srv new file mode 100644 index 0000000..cdf0e78 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameterTypes.srv @@ -0,0 +1,10 @@ +# A list of parameter names. +# TODO(wjwwood): link to parameter naming rules. +string[] names + +--- +# List of types which is the same length and order as the provided names. +# +# The type enum is defined in ParameterType.msg. ParameterType.PARAMETER_NOT_SET +# indicates that the parameter is not currently set. +uint8[] types diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.idl b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.idl new file mode 100644 index 0000000..75f54b4 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.idl @@ -0,0 +1,29 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/GetParameters.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/ParameterValue.idl" + +module rcl_interfaces { + module srv { + @verbatim (language="comment", text= + " TODO(wjwwood): Decide on the rules for grouping, nodes, and parameter \"names\"" "\n" + " in general, then link to that." "\n" + "" "\n" + " For more information about parameters and naming rules, see:" "\n" + " https://design.ros2.org/articles/ros_parameters.html" "\n" + " https://github.com/ros2/design/pull/241") + struct GetParameters_Request { + @verbatim (language="comment", text= + " A list of parameter names to get.") + sequence names; + }; + @verbatim (language="comment", text= + " List of values which is the same length and order as the provided names. If a" "\n" + " parameter was not yet set, the value will have PARAMETER_NOT_SET as the" "\n" + " type.") + struct GetParameters_Response { + sequence values; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.srv b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.srv new file mode 100644 index 0000000..1822479 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/GetParameters.srv @@ -0,0 +1,15 @@ +# TODO(wjwwood): Decide on the rules for grouping, nodes, and parameter "names" +# in general, then link to that. +# +# For more information about parameters and naming rules, see: +# https://design.ros2.org/articles/ros_parameters.html +# https://github.com/ros2/design/pull/241 + +# A list of parameter names to get. +string[] names + +--- +# List of values which is the same length and order as the provided names. If a +# parameter was not yet set, the value will have PARAMETER_NOT_SET as the +# type. +ParameterValue[] values diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.idl b/src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.idl new file mode 100644 index 0000000..74f9f32 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.idl @@ -0,0 +1,38 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/IntegerRange.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " Represents bounds and a step value for an integer typed parameter.") + struct IntegerRange { + @verbatim (language="comment", text= + " Start value for valid values, inclusive.") + int64 from_value; + + @verbatim (language="comment", text= + " End value for valid values, inclusive.") + int64 to_value; + + @verbatim (language="comment", text= + " Size of valid steps between the from and to bound." "\n" + "" "\n" + " A step value of zero implies a continuous range of values. Ideally, the step" "\n" + " would be less than or equal to the distance between the bounds, as well as an" "\n" + " even multiple of the distance between the bounds, but neither are required." "\n" + "" "\n" + " If the absolute value of the step is larger than or equal to the distance" "\n" + " between the two bounds, then the bounds will be the only valid values. e.g. if" "\n" + " the range is defined as {from_value: 1, to_value: 2, step: 5} then the valid" "\n" + " values will be 1 and 2." "\n" + "" "\n" + " If the step is less than the distance between the bounds, but the distance is" "\n" + " not a multiple of the step, then the \"to\" bound will always be a valid value," "\n" + " e.g. if the range is defined as {from_value: 2, to_value: 5, step: 2} then" "\n" + " the valid values will be 2, 4, and 5.") + uint64 step; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.msg b/src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.msg new file mode 100644 index 0000000..b41aec1 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/IntegerRange.msg @@ -0,0 +1,24 @@ +# Represents bounds and a step value for an integer typed parameter. + +# Start value for valid values, inclusive. +int64 from_value + +# End value for valid values, inclusive. +int64 to_value + +# Size of valid steps between the from and to bound. +# +# A step value of zero implies a continuous range of values. Ideally, the step +# would be less than or equal to the distance between the bounds, as well as an +# even multiple of the distance between the bounds, but neither are required. +# +# If the absolute value of the step is larger than or equal to the distance +# between the two bounds, then the bounds will be the only valid values. e.g. if +# the range is defined as {from_value: 1, to_value: 2, step: 5} then the valid +# values will be 1 and 2. +# +# If the step is less than the distance between the bounds, but the distance is +# not a multiple of the step, then the "to" bound will always be a valid value, +# e.g. if the range is defined as {from_value: 2, to_value: 5, step: 2} then +# the valid values will be 2, 4, and 5. +uint64 step diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.idl b/src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.idl new file mode 100644 index 0000000..d9e777a --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.idl @@ -0,0 +1,31 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/ListParameters.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/ListParametersResult.idl" + +module rcl_interfaces { + module srv { + module ListParameters_Request_Constants { + const uint64 DEPTH_RECURSIVE = 0; + }; + @verbatim (language="comment", text= + " Recursively get parameters with unlimited depth.") + struct ListParameters_Request { + @verbatim (language="comment", text= + " The list of parameter prefixes to query.") + sequence prefixes; + + @verbatim (language="comment", text= + " Relative depth from given prefixes to return." "\n" + "" "\n" + " Use DEPTH_RECURSIVE to get the recursive parameters and prefixes for each prefix.") + uint64 depth; + }; + @verbatim (language="comment", text= + " The list of parameter names and their prefixes.") + struct ListParameters_Response { + rcl_interfaces::msg::ListParametersResult result; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.srv b/src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.srv new file mode 100644 index 0000000..ee1b7a6 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ListParameters.srv @@ -0,0 +1,14 @@ +# Recursively get parameters with unlimited depth. +uint64 DEPTH_RECURSIVE=0 + +# The list of parameter prefixes to query. +string[] prefixes + +# Relative depth from given prefixes to return. +# +# Use DEPTH_RECURSIVE to get the recursive parameters and prefixes for each prefix. +uint64 depth + +--- +# The list of parameter names and their prefixes. +ListParametersResult result diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.idl b/src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.idl new file mode 100644 index 0000000..c98283e --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.idl @@ -0,0 +1,19 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ListParametersResult.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " The resulting parameters under the given prefixes.") + struct ListParametersResult { + sequence names; + + @verbatim (language="comment", text= + " The resulting prefixes under the given prefixes." "\n" + " TODO(wjwwood): link to prefix definition and rules.") + sequence prefixes; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.msg b/src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.msg new file mode 100644 index 0000000..85334f5 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ListParametersResult.msg @@ -0,0 +1,6 @@ +# The resulting parameters under the given prefixes. +string[] names + +# The resulting prefixes under the given prefixes. +# TODO(wjwwood): link to prefix definition and rules. +string[] prefixes diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/Log.idl b/src/ros2/rcl_interfaces/rcl_interfaces/Log.idl new file mode 100644 index 0000000..4eda25b --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/Log.idl @@ -0,0 +1,62 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/Log.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" + +module rcl_interfaces { + module msg { + module Log_Constants { + const octet DEBUG = 10; + const octet INFO = 20; + const octet WARN = 30; + const octet ERROR = 40; + const octet FATAL = 50; + }; + @verbatim (language="comment", text= + "#" "\n" + "# Severity level constants" "\n" + "#" "\n" + "# These logging levels follow the Python Standard" "\n" + "# https://docs.python.org/3/library/logging.html#logging-levels" "\n" + "# And are implemented in rcutils as well" "\n" + "# https://github.com/ros2/rcutils/blob/35f29850064e0c33a4063cbc947ebbfeada11dba/include/rcutils/logging.h#L164-L172" "\n" + "# This leaves space for other standard logging levels to be inserted in the middle in the future," "\n" + "# as well as custom user defined levels." "\n" + "# Since there are several other logging enumeration standard for different implementations," "\n" + "# other logging implementations may need to provide level mappings to match their internal implementations." "\n" + "#") + struct Log { + @verbatim (language="comment", text= + "#" "\n" + "# Fields" "\n" + "#" "\n" + " Timestamp when this message was generated by the node.") + builtin_interfaces::msg::Time stamp; + + @verbatim (language="comment", text= + " Corresponding log level, see above definitions.") + uint8 level; + + @verbatim (language="comment", text= + " The name representing the logger this message came from.") + string name; + + @verbatim (language="comment", text= + " The full log message.") + string msg; + + @verbatim (language="comment", text= + " The file the message came from.") + string file; + + @verbatim (language="comment", text= + " The function the message came from.") + string function; + + @verbatim (language="comment", text= + " The line in the file the message came from.") + uint32 line; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/Log.msg b/src/ros2/rcl_interfaces/rcl_interfaces/Log.msg new file mode 100644 index 0000000..c96cdb7 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/Log.msg @@ -0,0 +1,54 @@ +## +## Severity level constants +## +## These logging levels follow the Python Standard +## https://docs.python.org/3/library/logging.html#logging-levels +## And are implemented in rcutils as well +## https://github.com/ros2/rcutils/blob/35f29850064e0c33a4063cbc947ebbfeada11dba/include/rcutils/logging.h#L164-L172 +## This leaves space for other standard logging levels to be inserted in the middle in the future, +## as well as custom user defined levels. +## Since there are several other logging enumeration standard for different implementations, +## other logging implementations may need to provide level mappings to match their internal implementations. +## + +# Debug is for pedantic information, which is useful when debugging issues. +byte DEBUG=10 + +# Info is the standard informational level and is used to report expected +# information. +byte INFO=20 + +# Warning is for information that may potentially cause issues or possibly unexpected +# behavior. +byte WARN=30 + +# Error is for information that this node cannot resolve. +byte ERROR=40 + +# Information about a impending node shutdown. +byte FATAL=50 + +## +## Fields +## + +# Timestamp when this message was generated by the node. +builtin_interfaces/Time stamp + +# Corresponding log level, see above definitions. +uint8 level + +# The name representing the logger this message came from. +string name + +# The full log message. +string msg + +# The file the message came from. +string file + +# The function the message came from. +string function + +# The line in the file the message came from. +uint32 line diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/Parameter.idl b/src/ros2/rcl_interfaces/rcl_interfaces/Parameter.idl new file mode 100644 index 0000000..8bd9f2b --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/Parameter.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/Parameter.msg +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/ParameterValue.idl" + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " This is the message to communicate a parameter. It is an open struct with an enum in" "\n" + " the descriptor to select which value is active.") + struct Parameter { + @verbatim (language="comment", text= + " The full name of the parameter.") + string name; + + @verbatim (language="comment", text= + " The parameter's value which can be one of several types, see" "\n" + " `ParameterValue.msg` and `ParameterType.msg`.") + rcl_interfaces::msg::ParameterValue value; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/Parameter.msg b/src/ros2/rcl_interfaces/rcl_interfaces/Parameter.msg new file mode 100644 index 0000000..51c09ba --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/Parameter.msg @@ -0,0 +1,9 @@ +# This is the message to communicate a parameter. It is an open struct with an enum in +# the descriptor to select which value is active. + +# The full name of the parameter. +string name + +# The parameter's value which can be one of several types, see +# `ParameterValue.msg` and `ParameterType.msg`. +ParameterValue value diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.idl b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.idl new file mode 100644 index 0000000..c5e0fb3 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.idl @@ -0,0 +1,57 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ParameterDescriptor.msg +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/FloatingPointRange.idl" +#include "rcl_interfaces/msg/IntegerRange.idl" + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " This is the message to communicate a parameter's descriptor.") + struct ParameterDescriptor { + @verbatim (language="comment", text= + " The name of the parameter.") + string name; + + @verbatim (language="comment", text= + " Enum values are defined in the `ParameterType.msg` message.") + uint8 type; + + @verbatim (language="comment", text= + " Description of the parameter, visible from introspection tools.") + string description; + + @verbatim (language="comment", text= + " Parameter constraints" "\n" + " Plain English description of additional constraints which cannot be expressed" "\n" + " with the available constraints, e.g. \"only prime numbers\"." "\n" + "" "\n" + " By convention, this should only be used to clarify constraints which cannot" "\n" + " be completely expressed with the parameter constraints below.") + string additional_constraints; + + @verbatim (language="comment", text= + " If 'true' then the value cannot change after it has been initialized.") + @default (value=FALSE) + boolean read_only; + + @verbatim (language="comment", text= + " If true, the parameter is allowed to change type.") + @default (value=FALSE) + boolean dynamic_typing; + + @verbatim (language="comment", text= + " If any of the following sequences are not empty, then the constraint inside of" "\n" + " them apply to this parameter." "\n" + "" "\n" + " FloatingPointRange and IntegerRange are mutually exclusive." "\n" + " FloatingPointRange consists of a from_value, a to_value, and a step.") + sequence floating_point_range; + + @verbatim (language="comment", text= + " IntegerRange consists of a from_value, a to_value, and a step.") + sequence integer_range; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.msg b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.msg new file mode 100644 index 0000000..714400a --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterDescriptor.msg @@ -0,0 +1,36 @@ +# This is the message to communicate a parameter's descriptor. + +# The name of the parameter. +string name + +# Enum values are defined in the `ParameterType.msg` message. +uint8 type + +# Description of the parameter, visible from introspection tools. +string description + +# Parameter constraints + +# Plain English description of additional constraints which cannot be expressed +# with the available constraints, e.g. "only prime numbers". +# +# By convention, this should only be used to clarify constraints which cannot +# be completely expressed with the parameter constraints below. +string additional_constraints + +# If 'true' then the value cannot change after it has been initialized. +bool read_only false + +# If true, the parameter is allowed to change type. +bool dynamic_typing false + +# If any of the following sequences are not empty, then the constraint inside of +# them apply to this parameter. +# +# FloatingPointRange and IntegerRange are mutually exclusive. + +# FloatingPointRange consists of a from_value, a to_value, and a step. +FloatingPointRange[<=1] floating_point_range + +# IntegerRange consists of a from_value, a to_value, and a step. +IntegerRange[<=1] integer_range diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.idl b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.idl new file mode 100644 index 0000000..f0cfc8e --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.idl @@ -0,0 +1,36 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ParameterEvent.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" +#include "rcl_interfaces/msg/Parameter.idl" + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " This message contains a parameter event." "\n" + " Because the parameter event was an atomic update, a specific parameter name" "\n" + " can only be in one of the three sets.") + struct ParameterEvent { + @verbatim (language="comment", text= + " The time stamp when this parameter event occurred.") + builtin_interfaces::msg::Time stamp; + + @verbatim (language="comment", text= + " Fully qualified ROS path to node.") + string node; + + @verbatim (language="comment", text= + " New parameters that have been set for this node.") + sequence new_parameters; + + @verbatim (language="comment", text= + " Parameters that have been changed during this event.") + sequence changed_parameters; + + @verbatim (language="comment", text= + " Parameters that have been deleted during this event.") + sequence deleted_parameters; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.msg b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.msg new file mode 100644 index 0000000..ace2544 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEvent.msg @@ -0,0 +1,18 @@ +# This message contains a parameter event. +# Because the parameter event was an atomic update, a specific parameter name +# can only be in one of the three sets. + +# The time stamp when this parameter event occurred. +builtin_interfaces/Time stamp + +# Fully qualified ROS path to node. +string node + +# New parameters that have been set for this node. +Parameter[] new_parameters + +# Parameters that have been changed during this event. +Parameter[] changed_parameters + +# Parameters that have been deleted during this event. +Parameter[] deleted_parameters diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.idl b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.idl new file mode 100644 index 0000000..ae96cf8 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ParameterEventDescriptors.msg +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/ParameterDescriptor.idl" + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " This message contains descriptors of a parameter event." "\n" + " It was an atomic update." "\n" + " A specific parameter name can only be in one of the three sets.") + struct ParameterEventDescriptors { + sequence new_parameters; + + sequence changed_parameters; + + sequence deleted_parameters; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.msg b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.msg new file mode 100644 index 0000000..28bbeb9 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterEventDescriptors.msg @@ -0,0 +1,7 @@ +# This message contains descriptors of a parameter event. +# It was an atomic update. +# A specific parameter name can only be in one of the three sets. + +ParameterDescriptor[] new_parameters +ParameterDescriptor[] changed_parameters +ParameterDescriptor[] deleted_parameters diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.idl b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.idl new file mode 100644 index 0000000..2d42e94 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.idl @@ -0,0 +1,26 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ParameterType.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + module ParameterType_Constants { + const uint8 PARAMETER_NOT_SET = 0; + const uint8 PARAMETER_BOOL = 1; + const uint8 PARAMETER_INTEGER = 2; + const uint8 PARAMETER_DOUBLE = 3; + const uint8 PARAMETER_STRING = 4; + const uint8 PARAMETER_BYTE_ARRAY = 5; + const uint8 PARAMETER_BOOL_ARRAY = 6; + const uint8 PARAMETER_INTEGER_ARRAY = 7; + const uint8 PARAMETER_DOUBLE_ARRAY = 8; + const uint8 PARAMETER_STRING_ARRAY = 9; + }; + @verbatim (language="comment", text= + " These types correspond to the value that is set in the ParameterValue message.") + struct ParameterType { + uint8 structure_needs_at_least_one_member; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.msg b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.msg new file mode 100644 index 0000000..e3c4f26 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterType.msg @@ -0,0 +1,14 @@ +# These types correspond to the value that is set in the ParameterValue message. + +# Default value, which implies this is not a valid parameter. +uint8 PARAMETER_NOT_SET=0 + +uint8 PARAMETER_BOOL=1 +uint8 PARAMETER_INTEGER=2 +uint8 PARAMETER_DOUBLE=3 +uint8 PARAMETER_STRING=4 +uint8 PARAMETER_BYTE_ARRAY=5 +uint8 PARAMETER_BOOL_ARRAY=6 +uint8 PARAMETER_INTEGER_ARRAY=7 +uint8 PARAMETER_DOUBLE_ARRAY=8 +uint8 PARAMETER_STRING_ARRAY=9 diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.idl b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.idl new file mode 100644 index 0000000..d25a90b --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.idl @@ -0,0 +1,58 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/ParameterValue.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " Used to determine which of the next *_value fields are set." "\n" + " ParameterType.PARAMETER_NOT_SET indicates that the parameter was not set" "\n" + " (if gotten) or is uninitialized." "\n" + " Values are enumerated in `ParameterType.msg`.") + struct ParameterValue { + @verbatim (language="comment", text= + " The type of this parameter, which corresponds to the appropriate field below.") + uint8 type; + + @verbatim (language="comment", text= + " \"Variant\" style storage of the parameter value. Only the value corresponding" "\n" + " the type field will have valid information." "\n" + " Boolean value, can be either true or false.") + boolean bool_value; + + @verbatim (language="comment", text= + " Integer value ranging from -9,223,372,036,854,775,808 to" "\n" + " 9,223,372,036,854,775,807.") + int64 integer_value; + + @verbatim (language="comment", text= + " A double precision floating point value following IEEE 754.") + double double_value; + + @verbatim (language="comment", text= + " A textual value with no practical length limit.") + string string_value; + + @verbatim (language="comment", text= + " An array of bytes, used for non-textual information.") + sequence byte_array_value; + + @verbatim (language="comment", text= + " An array of boolean values.") + sequence bool_array_value; + + @verbatim (language="comment", text= + " An array of 64-bit integer values.") + sequence integer_array_value; + + @verbatim (language="comment", text= + " An array of 64-bit floating point values.") + sequence double_array_value; + + @verbatim (language="comment", text= + " An array of string values.") + sequence string_array_value; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.msg b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.msg new file mode 100644 index 0000000..4fba1bd --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/ParameterValue.msg @@ -0,0 +1,38 @@ +# Used to determine which of the next *_value fields are set. +# ParameterType.PARAMETER_NOT_SET indicates that the parameter was not set +# (if gotten) or is uninitialized. +# Values are enumerated in `ParameterType.msg`. + +# The type of this parameter, which corresponds to the appropriate field below. +uint8 type + +# "Variant" style storage of the parameter value. Only the value corresponding +# the type field will have valid information. + +# Boolean value, can be either true or false. +bool bool_value + +# Integer value ranging from -9,223,372,036,854,775,808 to +# 9,223,372,036,854,775,807. +int64 integer_value + +# A double precision floating point value following IEEE 754. +float64 double_value + +# A textual value with no practical length limit. +string string_value + +# An array of bytes, used for non-textual information. +byte[] byte_array_value + +# An array of boolean values. +bool[] bool_array_value + +# An array of 64-bit integer values. +int64[] integer_array_value + +# An array of 64-bit floating point values. +float64[] double_array_value + +# An array of string values. +string[] string_array_value diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.idl b/src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.idl new file mode 100644 index 0000000..c70e83f --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.idl @@ -0,0 +1,21 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/SetParameters.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/Parameter.idl" +#include "rcl_interfaces/msg/SetParametersResult.idl" + +module rcl_interfaces { + module srv { + @verbatim (language="comment", text= + " A list of parameters to set.") + struct SetParameters_Request { + sequence parameters; + }; + @verbatim (language="comment", text= + " Indicates whether setting each parameter succeeded or not and why.") + struct SetParameters_Response { + sequence results; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.srv b/src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.srv new file mode 100644 index 0000000..97d1179 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/SetParameters.srv @@ -0,0 +1,6 @@ +# A list of parameters to set. +Parameter[] parameters + +--- +# Indicates whether setting each parameter succeeded or not and why. +SetParametersResult[] results diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.idl b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.idl new file mode 100644 index 0000000..e28ca64 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.idl @@ -0,0 +1,23 @@ +// generated from rosidl_adapter/resource/srv.idl.em +// with input from rcl_interfaces/srv/SetParametersAtomically.srv +// generated code does not contain a copyright notice + +#include "rcl_interfaces/msg/Parameter.idl" +#include "rcl_interfaces/msg/SetParametersResult.idl" + +module rcl_interfaces { + module srv { + @verbatim (language="comment", text= + " A list of parameters to set atomically." "\n" + "" "\n" + " This call will either set all values, or none of the values.") + struct SetParametersAtomically_Request { + sequence parameters; + }; + @verbatim (language="comment", text= + " Indicates whether setting all of the parameters succeeded or not and why.") + struct SetParametersAtomically_Response { + rcl_interfaces::msg::SetParametersResult result; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.srv b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.srv new file mode 100644 index 0000000..2df928a --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersAtomically.srv @@ -0,0 +1,8 @@ +# A list of parameters to set atomically. +# +# This call will either set all values, or none of the values. +Parameter[] parameters + +--- +# Indicates whether setting all of the parameters succeeded or not and why. +SetParametersResult result diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.idl b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.idl new file mode 100644 index 0000000..fd80679 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.idl @@ -0,0 +1,20 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rcl_interfaces/msg/SetParametersResult.msg +// generated code does not contain a copyright notice + + +module rcl_interfaces { + module msg { + @verbatim (language="comment", text= + " A true value of the same index indicates that the parameter was set" "\n" + " successfully. A false value indicates the change was rejected.") + struct SetParametersResult { + boolean successful; + + @verbatim (language="comment", text= + " Reason why the setting was either successful or a failure. This should only be" "\n" + " used for logging and user interfaces.") + string reason; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.msg b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.msg new file mode 100644 index 0000000..4c9e944 --- /dev/null +++ b/src/ros2/rcl_interfaces/rcl_interfaces/SetParametersResult.msg @@ -0,0 +1,7 @@ +# A true value of the same index indicates that the parameter was set +# successfully. A false value indicates the change was rejected. +bool successful + +# Reason why the setting was either successful or a failure. This should only be +# used for logging and user interfaces. +string reason diff --git a/src/ros2/rcl_interfaces/rosgraph_msgs/Clock.idl b/src/ros2/rcl_interfaces/rosgraph_msgs/Clock.idl new file mode 100644 index 0000000..9a0c83e --- /dev/null +++ b/src/ros2/rcl_interfaces/rosgraph_msgs/Clock.idl @@ -0,0 +1,17 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from rosgraph_msgs/msg/Clock.msg +// generated code does not contain a copyright notice + +#include "builtin_interfaces/msg/Time.idl" + +module rosgraph_msgs { + module msg { + @verbatim (language="comment", text= + " This message communicates the current time." "\n" + "" "\n" + " For more information, see https://design.ros2.org/articles/clock_and_time.html.") + struct Clock { + builtin_interfaces::msg::Time clock; + }; + }; +}; diff --git a/src/ros2/rcl_interfaces/rosgraph_msgs/Clock.msg b/src/ros2/rcl_interfaces/rosgraph_msgs/Clock.msg new file mode 100644 index 0000000..25af0e4 --- /dev/null +++ b/src/ros2/rcl_interfaces/rosgraph_msgs/Clock.msg @@ -0,0 +1,4 @@ +# This message communicates the current time. +# +# For more information, see https://design.ros2.org/articles/clock_and_time.html. +builtin_interfaces/Time clock