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 sensor_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)

set(msg_files
"msg/Altitude.msg"
"msg/BatteryState.msg"
"msg/CameraInfo.msg"
"msg/ChannelFloat32.msg"
Expand Down
1 change: 1 addition & 0 deletions sensor_msgs/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ This package provides some common C++ functionality relating to manipulating a c
* [point_field_conversion.hpp](include/sensor_msgs/point_field_conversion.hpp): A type to enum mapping for the different PointField types, and methods to read and write in a PointCloud2 buffer for the different PointField types.

## Messages (.msg)
* [Altitude](msg/Altitude.msg): Single vertical position (altitude/depth) measurement.
* [BatteryState](msg/BatteryState.msg): Describes the power state of the battery.
* [CameraInfo](msg/CameraInfo.msg): Meta information for a camera.
* [ChannelFloat32](msg/ChannelFloat32.msg): Holds optional data associated with each point in a PointCloud message.
Expand Down
34 changes: 34 additions & 0 deletions sensor_msgs/msg/Altitude.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# Single vertical position (altitude/depth) measurement.
#
# Units & sign (REP-103): meters, +Z up. Negative altitude indicates depth.
#
# Semantics (REP-105):
# - 'altitude' is the height (or depth if negative) of the origin of header.frame_id,
# measured vertically in the selected 'reference'.
# - header.frame_id identifies the point this measurement applies to.
#
# Reference:
# The 'reference' field indicates what this measurement is relative to.
#
# Uncertainty:
# - 'variance' is the measurement variance in m^2; 0.0 indicates unknown.

# Reference enumeration
uint8 REFERENCE_UNKNOWN=0
uint8 REFERENCE_MSL=1 # altitude above mean sea level (as provided by the sensor/system)
uint8 REFERENCE_WGS84=2 # altitude above WGS84 ellipsoid (matches NavSatFix semantics)
uint8 REFERENCE_EGM96=3 # altitude relative to EGM96 geoid model
uint8 REFERENCE_LOCAL_DATUM=4 # altitude relative to a publisher-defined local vertical datum
uint8 REFERENCE_SURFACE=5 # altitude relative to a local physical surface (ground, seabed, water surface, etc.)

# Timestamp and point of the measurement
std_msgs/Header header # stamp: measurement time; frame_id: measurement point

# Scalar vertical position
float64 altitude # Vertical position in meters (+Z up); negative for depth

# Measurement uncertainty
float64 variance # 0 is interpreted as variance unknown

# Which reference 'altitude' is relative to (see REFERENCE_* constants above)
uint8 reference