mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 19:07:45 +08:00
Add HDOP / VDOP fields
This commit is contained in:
@@ -13,6 +13,9 @@ uint8 fix_type # 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: RTCM code differential, 5
|
|||||||
float32 eph # GPS horizontal position accuracy (metres)
|
float32 eph # GPS horizontal position accuracy (metres)
|
||||||
float32 epv # GPS vertical position accuracy (metres)
|
float32 epv # GPS vertical position accuracy (metres)
|
||||||
|
|
||||||
|
float32 hdop # Horizontal dilution of precision
|
||||||
|
float32 vdop # Vertical dilution of precision
|
||||||
|
|
||||||
int32 noise_per_ms # GPS noise per millisecond
|
int32 noise_per_ms # GPS noise per millisecond
|
||||||
int32 jamming_indicator # indicates jamming is occurring
|
int32 jamming_indicator # indicates jamming is occurring
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user