From 11c633be324a09f53f920e9c597edb68f11ce46f Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 26 Sep 2019 11:59:41 -0500 Subject: [PATCH] AP_OSD: distance total fix for slow vehicles --- libraries/AP_OSD/AP_OSD.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index cd32ecdcd3..90016d0be7 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -251,7 +251,7 @@ void AP_OSD::stats() AP_AHRS &ahrs = AP::ahrs(); Vector2f v = ahrs.groundspeed_vector(); float speed = v.length(); - if (speed < 2.0) { + if (speed < 0.178) { speed = 0.0; } float dist_m = (speed * delta_ms)*0.001;