AP_DataFlash: compiler warnings: float to double

This commit is contained in:
Tom Pittenger 2015-05-02 02:27:44 -07:00 committed by Andrew Tridgell
parent 4ac1f8a2fa
commit 98ca790cb9

View File

@ -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;
}