From d401fbb5dc8a3ee6a352de5f5b97d411ec680581 Mon Sep 17 00:00:00 2001 From: Benjamin Perseghetti Date: Fri, 19 Sep 2025 12:21:03 -0400 Subject: [PATCH] Add set of messages for embedded sensors. Adds a bounded string header useful for static allocation on embedded platforms. IMU, magentometer and pressure sensors added as they exist in real world. Note an IMU is not an Absolute Orientation Sensor. Introduces a Vector3 version of the Point32. Signed-off-by: Benjamin Perseghetti --- geometry_msgs/CMakeLists.txt | 1 + geometry_msgs/README.md | 1 + geometry_msgs/msg/Vector3F32.msg | 14 ++++++++++++++ sensor_msgs/CMakeLists.txt | 3 +++ sensor_msgs/README.md | 3 +++ sensor_msgs/msg/ImuSensor.msg | 9 +++++++++ sensor_msgs/msg/Magnetometer.msg | 11 +++++++++++ sensor_msgs/msg/PressureSensor.msg | 11 +++++++++++ std_msgs/CMakeLists.txt | 1 + std_msgs/README.md | 1 + std_msgs/msg/HeaderBounded48.msg | 10 ++++++++++ 11 files changed, 65 insertions(+) create mode 100644 geometry_msgs/msg/Vector3F32.msg create mode 100644 sensor_msgs/msg/ImuSensor.msg create mode 100644 sensor_msgs/msg/Magnetometer.msg create mode 100644 sensor_msgs/msg/PressureSensor.msg create mode 100644 std_msgs/msg/HeaderBounded48.msg diff --git a/geometry_msgs/CMakeLists.txt b/geometry_msgs/CMakeLists.txt index 6d69d3af..2ae4445f 100644 --- a/geometry_msgs/CMakeLists.txt +++ b/geometry_msgs/CMakeLists.txt @@ -43,6 +43,7 @@ set(msg_files "msg/TwistWithCovariance.msg" "msg/TwistWithCovarianceStamped.msg" "msg/Vector3.msg" + "msg/Vector3F32.msg" "msg/Vector3Stamped.msg" "msg/VelocityStamped.msg" "msg/Wrench.msg" diff --git a/geometry_msgs/README.md b/geometry_msgs/README.md index 3d6193a6..7b452e2d 100644 --- a/geometry_msgs/README.md +++ b/geometry_msgs/README.md @@ -32,6 +32,7 @@ For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros * [TwistWithCovariance](msg/TwistWithCovariance.msg): Velocity in 3-dimensional free space with uncertainty. * [TwistWithCovarianceStamped](msg/TwistWithCovarianceStamped.msg): An estimated twist with reference coordinate frame and timestamp. * [Vector3](msg/Vector3.msg): Represents a vector in 3-dimensional free space. +* [Vector3F32](msg/Vector3F32.msg): Represents a vector in 3-dimensional free space, with 32-bit fields. * [Vector3Stamped](msg/Vector3Stamped.msg): Represents a Vector3 with reference coordinate frame and timestamp. * [Wrench](msg/Wrench.msg): Represents force in free space, separated into its linear and angular parts. * [WrenchStamped](msg/WrenchStamped.msg): A wrench with reference coordinate frame and timestamp. diff --git a/geometry_msgs/msg/Vector3F32.msg b/geometry_msgs/msg/Vector3F32.msg new file mode 100644 index 00000000..5b8b7a3b --- /dev/null +++ b/geometry_msgs/msg/Vector3F32.msg @@ -0,0 +1,14 @@ +# This represents a vector in free space (with 32 bits of precision). +# +# 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. +# It is recommended to use Vector3 wherever possible instead of Vector3F32. +# +# This recommendation is to promote interoperability. +# +# This message is designed to take up less space when sending lots of vectors. + +float32 x +float32 y +float32 z diff --git a/sensor_msgs/CMakeLists.txt b/sensor_msgs/CMakeLists.txt index 530141e3..e53d9572 100644 --- a/sensor_msgs/CMakeLists.txt +++ b/sensor_msgs/CMakeLists.txt @@ -26,6 +26,7 @@ set(msg_files "msg/Illuminance.msg" "msg/Image.msg" "msg/Imu.msg" + "msg/ImuSensor.msg" "msg/JointState.msg" "msg/Joy.msg" "msg/JoyFeedback.msg" @@ -33,6 +34,7 @@ set(msg_files "msg/LaserEcho.msg" "msg/LaserScan.msg" "msg/MagneticField.msg" + "msg/Magnetometer.msg" "msg/MultiDOFJointState.msg" "msg/MultiEchoLaserScan.msg" "msg/NavSatFix.msg" @@ -40,6 +42,7 @@ set(msg_files "msg/PointCloud.msg" "msg/PointCloud2.msg" "msg/PointField.msg" + "msg/PressureSensor.msg" "msg/Range.msg" "msg/RegionOfInterest.msg" "msg/RelativeHumidity.msg" diff --git a/sensor_msgs/README.md b/sensor_msgs/README.md index 7385aaad..eeddd333 100644 --- a/sensor_msgs/README.md +++ b/sensor_msgs/README.md @@ -24,6 +24,7 @@ This package provides some common C++ functionality relating to manipulating a c * [Illuminance](msg/Illuminance.msg): Single photometric illuminance measurement. * [Image](msg/Image.msg): An uncompressed image. * [Imu](msg/Imu.msg): Holds data from an IMU (Inertial Measurement Unit). +* [ImuSensor](msg/ImuSensor.msg): Holds data from an IMU (Inertial Measurement Unit) Sensor. * [JointState](msg/JointState.msg): Holds data to describe the state of a set of torque controlled joints. * [JoyFeedbackArray](msg/JoyFeedbackArray.msg): An array of JoyFeedback messages. * [JoyFeedback](msg/JoyFeedback.msg): Describes user feedback in a joystick, like an LED, rumble pad, or buzzer. @@ -31,6 +32,7 @@ This package provides some common C++ functionality relating to manipulating a c * [LaserEcho](msg/LaserEcho.msg): A submessage of MultiEchoLaserScan and is not intended to be used separately. * [LaserScan](msg/LaserScan.msg): Single scan from a planar laser range-finder. * [MagneticField](msg/MagneticField.msg): Measurement of the Magnetic Field vector at a specific location. +* [Magnetometer](msg/Magnetometer.msg): Measurement of planets Magnetic Field vector in microTesla. * [MultiDOFJointState](msg/MultiDOFJointState.msg): Representation of state for joints with multiple degrees of freedom, following the structure of JointState. * [MultiEchoLaserScan](msg/MultiEchoLaserScan.msg): Single scan from a multi-echo planar laser range-finder. * [NavSatFix](msg/NavSatFix.msg): Navigation Satellite fix for any Global Navigation Satellite System. @@ -38,6 +40,7 @@ This package provides some common C++ functionality relating to manipulating a c * [PointCloud2](msg/PointCloud2.msg): Holds a collection of N-dimensional points, which may contain additional information such as normals, intensity, etc. * [PointCloud](msg/PointCloud.msg): **THIS MESSAGE IS DEPRECATED AS OF FOXY, use PointCloud2 instead** * [PointField](msg/PointField.msg): Holds the description of one point entry in the PointCloud2 message format. +* [PressureSensor](msg/PressureSensor.msg): Single pressure sensor reading like static atmospheric and differential pressures. * [Range](msg/Range.msg): Single range reading from an active ranger that emits energy and reports one range reading that is valid along an arc at the distance measured. * [RegionOfInterest](msg/RegionOfInterest.msg): Used to specify a region of interest within an image. * [RelativeHumidity](msg/RelativeHumidity.msg): A single reading from a relative humidity sensor. diff --git a/sensor_msgs/msg/ImuSensor.msg b/sensor_msgs/msg/ImuSensor.msg new file mode 100644 index 00000000..03f74259 --- /dev/null +++ b/sensor_msgs/msg/ImuSensor.msg @@ -0,0 +1,9 @@ +# This is a message to hold data from an IMU (Inertial Measurement Unit) sensor. +# +# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec + +std_msgs/HeaderBounded48 header + +geometry_msgs/Vector3F32 angular_velocity + +geometry_msgs/Vector3F32 linear_acceleration diff --git a/sensor_msgs/msg/Magnetometer.msg b/sensor_msgs/msg/Magnetometer.msg new file mode 100644 index 00000000..1f185d86 --- /dev/null +++ b/sensor_msgs/msg/Magnetometer.msg @@ -0,0 +1,11 @@ +# Measurement of the Magnetic Field vector at a specific location. + +std_msgs/HeaderBounded48 header # timestamp is the time the + # field was measured + # frame_id is the location and orientation + # of the field measurement + +geometry_msgs/Vector3F32 magnetic_field # x, y, and z components of the + # field vector in MicroTesla + # If your sensor does not output 3 axes, + # put NaNs in the components not reported. diff --git a/sensor_msgs/msg/PressureSensor.msg b/sensor_msgs/msg/PressureSensor.msg new file mode 100644 index 00000000..ce9e1729 --- /dev/null +++ b/sensor_msgs/msg/PressureSensor.msg @@ -0,0 +1,11 @@ +# Single pressure reading. This message is appropriate for measuring +# static atmospheric or differential pressure. Requires temperature. +# +# This message is not appropriate for force/pressure contact sensors. + +std_msgs/HeaderBounded48 header # timestamp of the measurement + # frame_id is the location of the pressure sensor + +float32 pressure # Pressure reading in hectopascals or millibar. + +float32 temperature # Measurement of the Temperature in Degrees Celsius. diff --git a/std_msgs/CMakeLists.txt b/std_msgs/CMakeLists.txt index 56fae110..606d9f1e 100644 --- a/std_msgs/CMakeLists.txt +++ b/std_msgs/CMakeLists.txt @@ -27,6 +27,7 @@ set(msg_files "msg/Float64.msg" "msg/Float64MultiArray.msg" "msg/Header.msg" + "msg/HeaderBounded48.msg" "msg/Int16.msg" "msg/Int16MultiArray.msg" "msg/Int32.msg" diff --git a/std_msgs/README.md b/std_msgs/README.md index 48455113..b00176fe 100644 --- a/std_msgs/README.md +++ b/std_msgs/README.md @@ -8,6 +8,7 @@ For more information about ROS 2 interfaces, see [docs.ros.org](https://docs.ros * [ColorRGBA](msg/ColorRGBA.msg): A single RGBA value for representing colors. * [Empty](msg/Empty.msg): Does not hold any information, useful when the sending of a message would provide sufficient information. * [Header](msg/Header.msg): Standard metadata for higher-level stamped data types used to communicate timestamped data in a particular coordinate frame. +* [HeaderBounded48](msg/HeaderBounded48.msg): Standard metadata for higher-level stamped data types used to communicate timestamped data in a particular bounded length (48) string coordinate frame. ### Primitive Types `std_msgs` provides the following wrappers for ROS primitive types, which are documented in the msg specification. It also contains the Empty type, which is useful for sending an empty signal. However, these types do not convey semantic meaning about their contents: every message simply has a field called "data". Therefore, while the messages in this package can be useful for quick prototyping, they are NOT intended for "long-term" usage. For ease of documentation and collaboration, we recommend that existing messages be used, or new messages created, that provide meaningful field name(s). diff --git a/std_msgs/msg/HeaderBounded48.msg b/std_msgs/msg/HeaderBounded48.msg new file mode 100644 index 00000000..0e505d15 --- /dev/null +++ b/std_msgs/msg/HeaderBounded48.msg @@ -0,0 +1,10 @@ +# 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. +# Limited in size to 47 bytes plus 1 termination byte for 48 bytes. +string<=47 frame_id