diff --git a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp index ff2a65a7eb..283ad99687 100644 --- a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp +++ b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp @@ -21,6 +21,9 @@ #include #include +void setup(); +void loop(); + const AP_HAL::HAL& hal = AP_HAL::get_HAL(); static AP_RPM RPM; @@ -39,7 +42,7 @@ void loop(void) { RPM.update(); - for (uint8_t ii = 0; iiprintf("%u - (%c) RPM: %8.2f Quality: %.2f ", - ii, sensor_state, RPM.get_rpm(ii), RPM.get_signal_quality(ii)); + ii, sensor_state, + (double)RPM.get_rpm(ii), + (double)RPM.get_signal_quality(ii)); - if (ii+1printf("| "); }