mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_OSD: fixed vertical speed item
This commit is contained in:
parent
e2b431f69f
commit
64cfa3beef
@ -422,11 +422,10 @@ void AP_OSD_Screen::draw_vspeed(uint8_t x, uint8_t y)
|
|||||||
sym = SYM_UP;
|
sym = SYM_UP;
|
||||||
} else if (vspd >= -3.0f) {
|
} else if (vspd >= -3.0f) {
|
||||||
sym = SYM_DOWN;
|
sym = SYM_DOWN;
|
||||||
vspd = -vspd;
|
|
||||||
} else {
|
} else {
|
||||||
sym = SYM_DOWN_DOWN;
|
sym = SYM_DOWN_DOWN;
|
||||||
vspd = -vspd;
|
|
||||||
}
|
}
|
||||||
|
vspd = fabsf(vspd);
|
||||||
backend->write(x, y, false, "%c%2.0f%c", sym, vspd, SYM_MS);
|
backend->write(x, y, false, "%c%2.0f%c", sym, vspd, SYM_MS);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user