DataFlash: explicitly print floats to 6 dec places

C++ default is to print 6 decimal places but nuttx displays none by
default
This commit is contained in:
Randy Mackay 2013-09-20 22:13:02 +09:00
parent 3f84e0adf6
commit 4b18c670e3
1 changed files with 1 additions and 1 deletions

View File

@ -316,7 +316,7 @@ 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("%.6f"), v);
ofs += sizeof(v);
break;
}