From edd3e3c34a5093e550eb326c4ee6bd339726ef5f Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Thu, 18 Feb 2016 02:28:52 -0200 Subject: [PATCH] Filter: silence warning about unused function MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ../../libraries/Filter/examples/Derivative/Derivative.cpp:16:14: warning: ‘float noise()’ defined but not used [-Wunused-function] static float noise(void) ^ --- libraries/Filter/examples/Derivative/Derivative.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/Filter/examples/Derivative/Derivative.cpp b/libraries/Filter/examples/Derivative/Derivative.cpp index 962e9fc222..20de02e97e 100644 --- a/libraries/Filter/examples/Derivative/Derivative.cpp +++ b/libraries/Filter/examples/Derivative/Derivative.cpp @@ -8,6 +8,8 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +#define USE_NOISE 0 + DerivativeFilter derivative; // setup routine @@ -15,7 +17,11 @@ void setup(){} static float noise(void) { +#if USE_NOISE return ((random() % 100)-50) * 0.001f; +#else + return 0; +#endif } //Main loop where the action takes place @@ -24,7 +30,7 @@ void loop() hal.scheduler->delay(50); float t = AP_HAL::millis()*1.0e-3f; float s = sinf(t); - //s += noise(); + s += noise(); uint32_t t1 = AP_HAL::micros(); derivative.update(s, t1); float output = derivative.slope() * 1.0e6f;