From 8bf6e8e0cf58c4ef6179f07b1949a6a6af1bf0ac Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 26 Jul 2018 13:39:19 +0900 Subject: [PATCH] AP_OSD: fix compiler warnings --- libraries/AP_OSD/AP_OSD_Screen.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 2d474828f5..9fc98dd13e 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -378,7 +378,7 @@ void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y) uint8_t pct = battery.capacity_remaining_pct(); uint8_t p = (100 - pct) / 16.6; float v = battery.voltage(); - backend->write(x,y, v < osd->warn_batvolt, "%c%2.1f%c", SYM_BATT_FULL + p, v, SYM_VOLT); + backend->write(x,y, v < osd->warn_batvolt, "%c%2.1f%c", SYM_BATT_FULL + p, (double)v, SYM_VOLT); } void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y) @@ -395,7 +395,7 @@ void AP_OSD_Screen::draw_current(uint8_t x, uint8_t y) { AP_BattMonitor &battery = AP_BattMonitor::battery(); float amps = battery.current_amps(); - backend->write(x, y, false, "%2.1f%c", amps, SYM_AMP); + backend->write(x, y, false, "%2.1f%c", (double)amps, SYM_AMP); } void AP_OSD_Screen::draw_fltmode(uint8_t x, uint8_t y) @@ -556,7 +556,7 @@ void AP_OSD_Screen::draw_distance(uint8_t x, uint8_t y, float distance) fmt = "%4.0f%c"; } } - backend->write(x, y, false, fmt, distance_scaled, unit_icon); + backend->write(x, y, false, fmt, (double)distance_scaled, unit_icon); } void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)