mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_OSD: scale xtrack, add precision for distances <10 units
This commit is contained in:
parent
6c734b5006
commit
fb0b92cc94
@ -1143,6 +1143,8 @@ void AP_OSD_Screen::draw_distance(uint8_t x, uint8_t y, float distance)
|
||||
} else {
|
||||
fmt = "%4.0f%c";
|
||||
}
|
||||
} else if (distance_scaled < 10.0f) {
|
||||
fmt = "% 3.1f%c";
|
||||
}
|
||||
backend->write(x, y, false, fmt, (double)distance_scaled, unit_icon);
|
||||
}
|
||||
@ -1400,7 +1402,8 @@ void AP_OSD_Screen::draw_waypoint(uint8_t x, uint8_t y)
|
||||
|
||||
void AP_OSD_Screen::draw_xtrack_error(uint8_t x, uint8_t y)
|
||||
{
|
||||
backend->write(x, y, false, "%c%4d", SYM_XERR, (int)osd->nav_info.wp_xtrack_error);
|
||||
backend->write(x, y, false, "%c", SYM_XERR);
|
||||
draw_distance(x+1, y, osd->nav_info.wp_xtrack_error);
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_stat(uint8_t x, uint8_t y)
|
||||
|
Loading…
Reference in New Issue
Block a user