AP_OSD: Change from division to multiplication

This commit is contained in:
murata 2022-03-12 02:35:26 +09:00 committed by Andrew Tridgell
parent 6d4a923cce
commit e977f85647
2 changed files with 3 additions and 3 deletions

View File

@ -380,7 +380,7 @@ void AP_OSD_ParamSetting::guess_ranges(bool force)
float floatp = p->get();
if (digits < 1) {
if (!is_zero(floatp)) {
incr = floatp / 100.0f; // move in 1% increments
incr = floatp * 0.01f; // move in 1% increments
} else {
incr = 0.01f; // move in absolute 1% increments
}
@ -388,7 +388,7 @@ void AP_OSD_ParamSetting::guess_ranges(bool force)
min = 0.0f;
} else {
if (!is_zero(floatp)) {
incr = floatp / 100.0f; // move in 1% increments
incr = floatp * 0.01f; // move in 1% increments
} else {
incr = MAX(1, powf(10, digits - 2));
}

View File

@ -1862,7 +1862,7 @@ void AP_OSD_Screen::draw_temp(uint8_t x, uint8_t y)
void AP_OSD_Screen::draw_hdop(uint8_t x, uint8_t y)
{
AP_GPS & gps = AP::gps();
float hdp = gps.get_hdop() / 100.0f;
float hdp = gps.get_hdop() * 0.01f;
backend->write(x, y, false, "%c%c%3.2f", SYMBOL(SYM_HDOP_L), SYMBOL(SYM_HDOP_R), (double)hdp);
}