uncrustify libraries/Filter/examples/LowPassFilter/LowPassFilter.pde

This commit is contained in:
uncrustify 2012-08-16 23:22:10 -07:00 committed by Pat Hickey
parent 0d5ea8cd7f
commit e742a26bd5

View File

@ -1,13 +1,13 @@
/*
Example sketch to demonstrate use of LowPassFilter library.
Code by Randy Mackay. DIYDrones.com
*/
* Example sketch to demonstrate use of LowPassFilter library.
* Code by Randy Mackay. DIYDrones.com
*/
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <Filter.h> // Filter library
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <Filter.h> // Filter library
#include <LowPassFilter.h> // LowPassFilter class (inherits from Filter class)
////////////////////////////////////////////////////////////////////////////////
// Serial ports
@ -20,41 +20,41 @@ LowPassFilterInt16 low_pass_filter(0.02); // simple low pass filter which appli
// setup routine
void setup()
{
// Open up a serial connection
Serial.begin(115200);
// introduction
Serial.printf("ArduPilot LowPassFilter test ver 1.0\n\n");
// Open up a serial connection
Serial.begin(115200);
// Wait for the serial connection
delay(500);
// introduction
Serial.printf("ArduPilot LowPassFilter test ver 1.0\n\n");
// Wait for the serial connection
delay(500);
}
//Main loop where the action takes place
void loop()
{
int16_t i;
int16_t new_value;
int16_t filtered_value;
int16_t i;
int16_t new_value;
int16_t filtered_value;
// reset value to 100. If not reset the filter will start at the first value entered
low_pass_filter.reset(100);
// reset value to 100. If not reset the filter will start at the first value entered
low_pass_filter.reset(100);
for( i=0; i<210; i++ ) {
for( i=0; i<210; i++ ) {
// new data value
new_value = 105;
// new data value
new_value = 105;
// output to user
Serial.printf("applying: %d",(int)new_value);
// output to user
Serial.printf("applying: %d",(int)new_value);
// apply new value and retrieved filtered result
filtered_value = low_pass_filter.apply(new_value);
// apply new value and retrieved filtered result
filtered_value = low_pass_filter.apply(new_value);
// display results
Serial.printf("\toutput: %d\n\n",(int)filtered_value);
}
delay(10000);
// display results
Serial.printf("\toutput: %d\n\n",(int)filtered_value);
}
delay(10000);
}