diff --git a/libraries/Filter/examples/Filter/Filter.pde b/libraries/Filter/examples/Filter/Filter.pde index 36add58027..1c51300bce 100644 --- a/libraries/Filter/examples/Filter/Filter.pde +++ b/libraries/Filter/examples/Filter/Filter.pde @@ -7,7 +7,8 @@ #include #include #include - +#include +#include #include #include // ArduPilot Mega Vector/Matrix math Library #include // Filter library @@ -24,6 +25,8 @@ ModeFilterInt16_Size5 mfilter(2); // buffer of 5 values, result will be from bu AverageFilterUInt16_Size4 _temp_filter; +butter50hz8_0 butter; + void setup() { // introduction @@ -50,7 +53,11 @@ void readTemp() raw_temp = _temp_filter.apply(_temp_sensor); - hal.console->printf("RT: %ld\n", raw_temp); + // use a butter filter on the result, just so we have a + // butterworth filter example + butter.filter(raw_temp); + + hal.console->printf("RT: %lu\n", (unsigned long)raw_temp); } //Main loop where the action takes place