Browse Source

DataFlash: explicitly print floats to 6 dec places

C++ default is to print 6 decimal places but nuttx displays none by
default
mission-4.1.18
Randy Mackay 12 years ago
parent
commit
4b18c670e3
  1. 2
      libraries/DataFlash/LogFile.cpp

2
libraries/DataFlash/LogFile.cpp

@ -316,7 +316,7 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type, @@ -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;
}

Loading…
Cancel
Save