From ccc5ba3cbde1f8253c8ca8565af51c3c99797af4 Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Sat, 17 Dec 2022 15:36:35 +0900 Subject: [PATCH] SITL: change HDOP from 2.0 to 1.2 --- libraries/SITL/SIM_GPS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index f53acbc8da..1c23225405 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -538,7 +538,7 @@ void GPS::update_nmea(const struct gps_data *d) lng_string, d->have_lock?1:0, d->have_lock?_sitl->gps_numsats[instance]:3, - 2.0, + 1.2, d->altitude); const float speed_mps = norm(d->speedN, d->speedE); const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS;