From 98ca790cb93e6bf016282068899a9a115b495a04 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sat, 2 May 2015 02:27:44 -0700 Subject: [PATCH] AP_DataFlash: compiler warnings: float to double --- libraries/DataFlash/LogFile.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 7e7c9262fc..5737efe7be 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -338,35 +338,35 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type, case 'f': { float v; memcpy(&v, &pkt[ofs], sizeof(v)); - port->printf_P(PSTR("%f"), v); + port->printf_P(PSTR("%f"), (double)v); ofs += sizeof(v); break; } case 'c': { int16_t v; memcpy(&v, &pkt[ofs], sizeof(v)); - port->printf_P(PSTR("%.2f"), 0.01f*v); + port->printf_P(PSTR("%.2f"), (double)(0.01f*v)); ofs += sizeof(v); break; } case 'C': { uint16_t v; memcpy(&v, &pkt[ofs], sizeof(v)); - port->printf_P(PSTR("%.2f"), 0.01f*v); + port->printf_P(PSTR("%.2f"), (double)(0.01f*v)); ofs += sizeof(v); break; } case 'e': { int32_t v; memcpy(&v, &pkt[ofs], sizeof(v)); - port->printf_P(PSTR("%.2f"), 0.01f*v); + port->printf_P(PSTR("%.2f"), (double)(0.01f*v)); ofs += sizeof(v); break; } case 'E': { uint32_t v; memcpy(&v, &pkt[ofs], sizeof(v)); - port->printf_P(PSTR("%.2f"), 0.01f*v); + port->printf_P(PSTR("%.2f"), (double)(0.01f*v)); ofs += sizeof(v); break; }