mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_OSD: display --- when no airspeed available
This commit is contained in:
parent
43ab8d88bf
commit
d280dbf119
@ -431,6 +431,8 @@ void AP_OSD_Screen::draw_aspeed(uint8_t x, uint8_t y)
|
||||
float aspd = 0.0f;
|
||||
if (AP::ahrs().airspeed_estimate(&aspd)) {
|
||||
backend->write(x, y, false, "A%4.0f%c", aspd * 3.6, SYM_KMH);
|
||||
} else {
|
||||
backend->write(x, y, false, "A ---%c", SYM_KMH);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user