Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions geometry_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
1 change: 1 addition & 0 deletions geometry_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
14 changes: 14 additions & 0 deletions geometry_msgs/msg/Vector3F32.msg
Original file line number Diff line number Diff line change
@@ -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
3 changes: 3 additions & 0 deletions sensor_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,20 +26,23 @@ set(msg_files
"msg/Illuminance.msg"
"msg/Image.msg"
"msg/Imu.msg"
"msg/ImuSensor.msg"
"msg/JointState.msg"
"msg/Joy.msg"
"msg/JoyFeedback.msg"
"msg/JoyFeedbackArray.msg"
"msg/LaserEcho.msg"
"msg/LaserScan.msg"
"msg/MagneticField.msg"
"msg/Magnetometer.msg"
"msg/MultiDOFJointState.msg"
"msg/MultiEchoLaserScan.msg"
"msg/NavSatFix.msg"
"msg/NavSatStatus.msg"
"msg/PointCloud.msg"
"msg/PointCloud2.msg"
"msg/PointField.msg"
"msg/PressureSensor.msg"
"msg/Range.msg"
"msg/RegionOfInterest.msg"
"msg/RelativeHumidity.msg"
Expand Down
3 changes: 3 additions & 0 deletions sensor_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,20 +24,23 @@ 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.
* [Joy](msg/Joy.msg): Reports the state of a joystick's axes and buttons.
* [LaserEcho](msg/LaserEcho.msg): A submessage of MultiEchoLaserScan and is not intended to be used separately.
* [LaserScan](msg/LaserScan.msg): Single scan from a planar laser range-finder.
* [MagneticField](msg/MagneticField.msg): Measurement of the Magnetic Field vector at a specific location.
* [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.
* [NavSatStatus](msg/NavSatStatus.msg): Navigation Satellite fix status for any Global Navigation Satellite System.
* [PointCloud2](msg/PointCloud2.msg): Holds a collection of N-dimensional points, which may contain additional information such as normals, intensity, etc.
* [PointCloud](msg/PointCloud.msg): **THIS MESSAGE IS DEPRECATED AS OF FOXY, use PointCloud2 instead**
* [PointField](msg/PointField.msg): Holds the description of one point entry in the PointCloud2 message format.
* [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.
Expand Down
9 changes: 9 additions & 0 deletions sensor_msgs/msg/ImuSensor.msg
Original file line number Diff line number Diff line change
@@ -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
11 changes: 11 additions & 0 deletions sensor_msgs/msg/Magnetometer.msg
Original file line number Diff line number Diff line change
@@ -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.
11 changes: 11 additions & 0 deletions sensor_msgs/msg/PressureSensor.msg
Original file line number Diff line number Diff line change
@@ -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.
1 change: 1 addition & 0 deletions std_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
1 change: 1 addition & 0 deletions std_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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).
Expand Down
10 changes: 10 additions & 0 deletions std_msgs/msg/HeaderBounded48.msg
Original file line number Diff line number Diff line change
@@ -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