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
41 changes: 41 additions & 0 deletions sensor_msgs/msg/Altitude.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# Single vertical position (altitude/depth) measurement.
#
# Units & sign (REP-103): meters, +Z up. Negative altitude indicates depth
# below the chosen reference.
#
# Semantics (REP-105):
# - 'altitude' is the vertical position along the +Z axis of header.frame_id.
# - header.frame_id is the frame in which the measurement is expressed
# (e.g., base_link, imu_link, map, earth).
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We need to be careful on this. base_link and imu_link are rarely actually vertical in the world. Isn't this about being vertical in the datum?

#
# Reference:
# The 'reference' field indicates what this measurement is relative to:
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This field doesn't appear to exist.

# REFERENCE_UNKNOWN (0): unspecified or mixed semantics.
# REFERENCE_DATUM (1): relative to a vertical datum / ellipsoid / geoid.
# When used, 'datum' should name the model, e.g.
# "WGS84", "EGM96", "MSL", or a local datum identifier.
# REFERENCE_SURFACE (2): relative to a local physical surface (ground, seabed,
# water surface). Typical for AGL/height-above-surface sensors.
#
# Uncertainty:
# - 'variance' is the measurement variance in m^2; 0.0 indicates unknown.

# Reference enumeration
uint8 REFERENCE_UNKNOWN=0
uint8 REFERENCE_DATUM=1
uint8 REFERENCE_SURFACE=2

# Timestamp and frame of the measurement
std_msgs/Header header # timestamp is when the altitude was measured;
# frame_id is the frame whose +Z defines "up"

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

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

# Optional name of the datum/surface
string datum # Name of vertical datum or surface if applicable
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Each datum supported should be in the enum above, not a string here.

# (e.g., "WGS84", "EGM96", "MSL", "GROUND", "SEA_SURFACE");
# empty if unknown or not applicable