mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_OSD: distance total fix for slow vehicles
This commit is contained in:
parent
2b0773c18b
commit
11c633be32
@ -251,7 +251,7 @@ void AP_OSD::stats()
|
|||||||
AP_AHRS &ahrs = AP::ahrs();
|
AP_AHRS &ahrs = AP::ahrs();
|
||||||
Vector2f v = ahrs.groundspeed_vector();
|
Vector2f v = ahrs.groundspeed_vector();
|
||||||
float speed = v.length();
|
float speed = v.length();
|
||||||
if (speed < 2.0) {
|
if (speed < 0.178) {
|
||||||
speed = 0.0;
|
speed = 0.0;
|
||||||
}
|
}
|
||||||
float dist_m = (speed * delta_ms)*0.001;
|
float dist_m = (speed * delta_ms)*0.001;
|
||||||
|
Loading…
Reference in New Issue
Block a user