mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: fix error in stats screen introduced in #18396
This commit is contained in:
parent
1f4f8df30f
commit
3e7c1ca88b
|
@ -1906,7 +1906,7 @@ void AP_OSD_Screen::draw_stat(uint8_t x, uint8_t y)
|
|||
backend->write(x+2, y, false, "%c%c%c", 0x4d,0x41,0x58);
|
||||
backend->write(x, y+1, false, "%c",SYMBOL(SYM_GSPD));
|
||||
backend->write(x+1, y+1, false, "%4d%c", (int)u_scale(SPEED, osd->_stats.max_speed_mps), u_icon(SPEED));
|
||||
backend->write(x, y+2, false, "%5.1f%c", (double)osd->_stats.max_current_a, SYM_AMP);
|
||||
backend->write(x, y+2, false, "%5.1f%c", (double)osd->_stats.max_current_a, SYMBOL(SYM_AMP));
|
||||
backend->write(x, y+3, false, "%5d%c", (int)u_scale(ALTITUDE, osd->_stats.max_alt_m), u_icon(ALTITUDE));
|
||||
backend->write(x, y+4, false, "%c", SYMBOL(SYM_HOME));
|
||||
draw_distance(x+1, y+4, osd->_stats.max_dist_m);
|
||||
|
|
Loading…
Reference in New Issue