AP_OSD: fixed vertical speed item

This commit is contained in:
Alexander Malishev 2018-07-04 10:14:04 +04:00 committed by Andrew Tridgell
parent e2b431f69f
commit 64cfa3beef

View File

@ -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);
} }