From 4b18c670e372da96299813b2e33991bb17a76a3b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 20 Sep 2013 22:13:02 +0900 Subject: [PATCH] DataFlash: explicitly print floats to 6 dec places C++ default is to print 6 decimal places but nuttx displays none by default --- libraries/DataFlash/LogFile.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 3ecf8940ef..fa8e136829 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -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; }