mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
uorb: add AuxGlobalPosition message
Add dedicated AuxGlobalPosition uORB message to replace the previous approach of reusing VehicleGlobalPosition for auxiliary global position sources.
This commit is contained in:
parent
68b533f79f
commit
dd177ac8cf
@ -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
|
||||
|
||||
31
msg/versioned/AuxGlobalPosition.msg
Normal file
31
msg/versioned/AuxGlobalPosition.msg
Normal file
@ -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
|
||||
@ -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
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user