Skip to content

[sensor_msgs] Proposal: Add Altitude.msg (scalar vertical position + variance) #294

@ViktorCVS

Description

@ViktorCVS

Description

Add a new scalar message to sensor_msgs named Altitude.msg, containing a timestamped vertical position z in meters (positive up), with an optional uncertainty. This fills the gap between existing messages that either (a) embed altitude together with latitude/longitude (NavSatFix) or (b) represent barometric pressure or generic ranges rather than altitude itself. The proposed definition mirrors existing scalar messages (e.g., Temperature, Illuminance) that carry a variance field.

Motivation

Many robotics applications need a standardized, timestamped scalar for vertical position (z) that is independent of latitude/longitude. The most common sources are barometric altimeters (converting absolute air pressure to altitude using a reference such as QNH or a locally defined “home” level), radar/laser/ultrasonic altimeters that directly measure height above ground along a downward beam (AGL), and underwater pressure sensors that map hydrostatic pressure to depth; DVLs and single‑beam echosounders also report altitude above the seabed as a single range.
Today these signals are typically published as FluidPressure, NavSatFix, or Range (or as community‑specific messages), which forces consumers to infer semantics, perform conversions, or carry unrelated fields. A minimal Altitude.msg, Header + altitude [m] (positive up, negative for depth) + variance [m²], would let drivers and estimators exchange vertical‑only observations with unambiguous units, frames, and uncertainty, reducing boilerplate conversions and improving interoperability in state‑estimation pipelines.

Why not Range? Range denotes along-beam distance from an active ranger and has different semantics/fields (min/max, FOV, radiation type). Many altitude sources are not active rangers (e.g., barometers), and even when they are (radar altimeters), the semantic intent is “vertical position”, not raw range.

Design / Implementation Considerations

Units & Sign (REP-103): meters, +Z up; negative altitude = depth (explicit in docstring). This keeps consistency with ROS axis conventions.

Uncertainty: follow scalar pattern → variance (float64, m²), where 0.0 = unknown, as in Temperature/FluidPressure/Illuminance.

Frame semantics (REP-105): header.frame_id declares the measurement frame (e.g., base_link, imu_link, map, or earth).

Additional Information

I’m opening this issue to quickly gauge community feedback on adding a minimal, source‑agnostic vertical position message to sensor_msgs; if there is support, I volunteer to author the PR (message and docs)

Metadata

Metadata

Assignees

No one assigned

    Labels

    enhancementNew feature or request

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions