From d24bbcd1ff484fd3b45c5b80d965ae0b10d088f7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 5 May 2016 11:40:07 +1000 Subject: [PATCH] AP_GPS: convert vdop to cm --- libraries/AP_GPS/AP_GPS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index ab870fad87..5368860693 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -495,7 +495,7 @@ AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms, void AP_GPS::setHIL_Accuracy(uint8_t instance, float vdop, float hacc, float vacc, float sacc, bool _have_vertical_velocity) { GPS_State &istate = state[instance]; - istate.vdop = vdop; + istate.vdop = vdop * 100; istate.horizontal_accuracy = hacc; istate.vertical_accuracy = vacc; istate.speed_accuracy = sacc;