mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: Fix vertical speed varying length
This commit is contained in:
parent
88b5523d47
commit
eb88e6a37c
|
@ -1457,10 +1457,11 @@ 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 < 10.0f) {
|
||||
backend->write(x, y, false, "%c%2.1f%c", sym, (float)vs_scaled, u_icon(VSPEED));
|
||||
if ((osd->units != AP_OSD::UNITS_AVIATION) && (vs_scaled < 9.95f)) {
|
||||
backend->write(x, y, false, "%c%.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));
|
||||
const char *fmt = osd->units == AP_OSD::UNITS_AVIATION ? "%c%4d%c" : "%c%2d%c";
|
||||
backend->write(x, y, false, fmt, sym, (int)roundf(vs_scaled), u_icon(VSPEED));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue