Browse Source

AP_Param: 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
3f84e0adf6
  1. 2
      libraries/AP_Param/AP_Param.cpp

2
libraries/AP_Param/AP_Param.cpp

@ -1035,7 +1035,7 @@ void AP_Param::show(const AP_Param *ap, const char *s, @@ -1035,7 +1035,7 @@ void AP_Param::show(const AP_Param *ap, const char *s,
port->printf_P(PSTR("%s: %ld\n"), s, (long)((AP_Int32 *)ap)->get());
break;
case AP_PARAM_FLOAT:
port->printf_P(PSTR("%s: %f\n"), s, ((AP_Float *)ap)->get());
port->printf_P(PSTR("%s: %.6f\n"), s, ((AP_Float *)ap)->get());
break;
default:
break;

Loading…
Cancel
Save