From dd177ac8cfa8e881c7d8b6310fc8dd7438457ec0 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Thu, 12 Feb 2026 16:19:48 +0100 Subject: [PATCH] uorb: add AuxGlobalPosition message Add dedicated AuxGlobalPosition uORB message to replace the previous approach of reusing VehicleGlobalPosition for auxiliary global position sources. --- msg/CMakeLists.txt | 1 + msg/versioned/AuxGlobalPosition.msg | 31 +++++++++++++++++++++++++ msg/versioned/VehicleGlobalPosition.msg | 1 - 3 files changed, 32 insertions(+), 1 deletion(-) create mode 100644 msg/versioned/AuxGlobalPosition.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index dbdaf79b7f..66a9f7e599 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -248,6 +248,7 @@ set(msg_files versioned/AirspeedValidated.msg versioned/ArmingCheckReply.msg versioned/ArmingCheckRequest.msg + versioned/AuxGlobalPosition.msg versioned/BatteryStatus.msg versioned/ConfigOverrides.msg versioned/FixedWingLateralSetpoint.msg diff --git a/msg/versioned/AuxGlobalPosition.msg b/msg/versioned/AuxGlobalPosition.msg new file mode 100644 index 0000000000..b8e6f1f9ad --- /dev/null +++ b/msg/versioned/AuxGlobalPosition.msg @@ -0,0 +1,31 @@ +# Auxiliary global position +# +# This message provides global position data from an external source such as +# pseudolites, visual navigation, or other positioning system. + +uint32 MESSAGE_VERSION = 0 + +uint64 timestamp # [us] Time since system start +uint64 timestamp_sample # [us] Timestamp of the raw data + +uint8 id # [-] Unique identifier for the AGP source +uint8 source # [@enum SOURCE] Source type of the position data (based on mavlink::GLOBAL_POSITION_SRC) +uint8 SOURCE_UNKNOWN = 0 # Unknown source +uint8 SOURCE_GNSS = 1 # GNSS +uint8 SOURCE_VISION = 2 # Vision +uint8 SOURCE_PSEUDOLITES = 3 # Pseudolites +uint8 SOURCE_TERRAIN = 4 # Terrain +uint8 SOURCE_MAGNETIC = 5 # Magnetic +uint8 SOURCE_ESTIMATOR = 6 # Estimator + +# lat, lon: required for horizontal position fusion, alt: required for vertical position fusion +float64 lat # [deg] Latitude in WGS84 +float64 lon # [deg] Longitude in WGS84 +float32 alt # [m] [@invalid NaN] Altitude above mean sea level (AMSL) + +float32 eph # [m] [@invalid NaN] Std dev of horizontal position, lower bounded by NOISE param +float32 epv # [m] [@invalid NaN] Std dev of vertical position, lower bounded by NOISE param + +uint8 lat_lon_reset_counter # [-] Counter for reset events on horizontal position coordinates + +# TOPICS aux_global_position diff --git a/msg/versioned/VehicleGlobalPosition.msg b/msg/versioned/VehicleGlobalPosition.msg index 387576d8c7..eae8a489a4 100644 --- a/msg/versioned/VehicleGlobalPosition.msg +++ b/msg/versioned/VehicleGlobalPosition.msg @@ -34,4 +34,3 @@ bool dead_reckoning # True if this position is estimated through dead-reckoning # TOPICS vehicle_global_position vehicle_global_position_groundtruth external_ins_global_position # TOPICS estimator_global_position -# TOPICS aux_global_position