mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
AP_DataFlash: compiler warnings: float to double
This commit is contained in:
parent
4ac1f8a2fa
commit
98ca790cb9
@ -338,35 +338,35 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
|||||||
case 'f': {
|
case 'f': {
|
||||||
float v;
|
float v;
|
||||||
memcpy(&v, &pkt[ofs], sizeof(v));
|
memcpy(&v, &pkt[ofs], sizeof(v));
|
||||||
port->printf_P(PSTR("%f"), v);
|
port->printf_P(PSTR("%f"), (double)v);
|
||||||
ofs += sizeof(v);
|
ofs += sizeof(v);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case 'c': {
|
case 'c': {
|
||||||
int16_t v;
|
int16_t v;
|
||||||
memcpy(&v, &pkt[ofs], sizeof(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);
|
ofs += sizeof(v);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case 'C': {
|
case 'C': {
|
||||||
uint16_t v;
|
uint16_t v;
|
||||||
memcpy(&v, &pkt[ofs], sizeof(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);
|
ofs += sizeof(v);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case 'e': {
|
case 'e': {
|
||||||
int32_t v;
|
int32_t v;
|
||||||
memcpy(&v, &pkt[ofs], sizeof(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);
|
ofs += sizeof(v);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case 'E': {
|
case 'E': {
|
||||||
uint32_t v;
|
uint32_t v;
|
||||||
memcpy(&v, &pkt[ofs], sizeof(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);
|
ofs += sizeof(v);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user