mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_OSD_Screen: move vspeed decimal switch to 10 m/s
This commit is contained in:
parent
6bf7f9e864
commit
e830494f0f
@ -1457,7 +1457,7 @@ void AP_OSD_Screen::draw_vspeed(uint8_t x, uint8_t y)
|
||||
sym = SYM_DOWN_DOWN;
|
||||
}
|
||||
vs_scaled = u_scale(VSPEED, fabsf(vspd));
|
||||
if (vs_scaled < 5.0f) {
|
||||
if (vs_scaled < 10.0f) {
|
||||
backend->write(x, y, false, "%c%2.1f%c", sym, (float)vs_scaled, u_icon(VSPEED));
|
||||
} else {
|
||||
backend->write(x, y, false, "%c%3d%c", sym, (int)vs_scaled, u_icon(VSPEED));
|
||||
|
Loading…
Reference in New Issue
Block a user