AP_GPS: hdop and vdop are unitless

This commit is contained in:
Willian Galvani 2024-06-27 10:39:58 -03:00 committed by Peter Barker
parent a3ea80a1f2
commit ef9763fdd7
1 changed files with 2 additions and 2 deletions

View File

@ -201,8 +201,8 @@ public:
float gps_yaw; ///< GPS derived yaw information, if available (degrees) float gps_yaw; ///< GPS derived yaw information, if available (degrees)
uint32_t gps_yaw_time_ms; ///< timestamp of last GPS yaw reading uint32_t gps_yaw_time_ms; ///< timestamp of last GPS yaw reading
bool gps_yaw_configured; ///< GPS is configured to provide yaw bool gps_yaw_configured; ///< GPS is configured to provide yaw
uint16_t hdop; ///< horizontal dilution of precision in cm uint16_t hdop; ///< horizontal dilution of precision, scaled by a factor of 100 (155 means the HDOP value is 1.55)
uint16_t vdop; ///< vertical dilution of precision in cm uint16_t vdop; ///< vertical dilution of precision, scaled by a factor of 100 (155 means the VDOP value is 1.55)
uint8_t num_sats; ///< Number of visible satellites uint8_t num_sats; ///< Number of visible satellites
Vector3f velocity; ///< 3D velocity in m/s, in NED format Vector3f velocity; ///< 3D velocity in m/s, in NED format
float speed_accuracy; ///< 3D velocity RMS accuracy estimate in m/s float speed_accuracy; ///< 3D velocity RMS accuracy estimate in m/s