mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
uncrustify libraries/Filter/examples/Derivative/Derivative.pde
This commit is contained in:
parent
70d18ec87c
commit
e5b317cb42
@ -1,6 +1,6 @@
|
|||||||
/*
|
/*
|
||||||
Example sketch to demonstrate use of DerivativeFilter library.
|
* Example sketch to demonstrate use of DerivativeFilter library.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
#include <AP_Common.h>
|
#include <AP_Common.h>
|
||||||
@ -10,23 +10,23 @@
|
|||||||
|
|
||||||
#ifdef DESKTOP_BUILD
|
#ifdef DESKTOP_BUILD
|
||||||
// all of this is needed to build with SITL
|
// all of this is needed to build with SITL
|
||||||
#include <DataFlash.h>
|
#include <DataFlash.h>
|
||||||
#include <APM_RC.h>
|
#include <APM_RC.h>
|
||||||
#include <GCS_MAVLink.h>
|
#include <GCS_MAVLink.h>
|
||||||
#include <Arduino_Mega_ISR_Registry.h>
|
#include <Arduino_Mega_ISR_Registry.h>
|
||||||
#include <AP_PeriodicProcess.h>
|
#include <AP_PeriodicProcess.h>
|
||||||
#include <AP_ADC.h>
|
#include <AP_ADC.h>
|
||||||
#include <AP_Baro.h>
|
#include <AP_Baro.h>
|
||||||
#include <AP_Compass.h>
|
#include <AP_Compass.h>
|
||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
#include <Filter.h>
|
#include <Filter.h>
|
||||||
#include <SITL.h>
|
#include <SITL.h>
|
||||||
#include <I2C.h>
|
#include <I2C.h>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#include <AP_Declination.h>
|
#include <AP_Declination.h>
|
||||||
Arduino_Mega_ISR_Registry isr_registry;
|
Arduino_Mega_ISR_Registry isr_registry;
|
||||||
AP_Baro_BMP085_HIL barometer;
|
AP_Baro_BMP085_HIL barometer;
|
||||||
AP_Compass_HIL compass;
|
AP_Compass_HIL compass;
|
||||||
SITL sitl;
|
SITL sitl;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -37,25 +37,25 @@ DerivativeFilter<float,11> derivative;
|
|||||||
// setup routine
|
// setup routine
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
// Open up a serial connection
|
// Open up a serial connection
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
}
|
}
|
||||||
|
|
||||||
static float noise(void)
|
static float noise(void)
|
||||||
{
|
{
|
||||||
return ((random() % 100)-50) * 0.001;
|
return ((random() % 100)-50) * 0.001;
|
||||||
}
|
}
|
||||||
|
|
||||||
//Main loop where the action takes place
|
//Main loop where the action takes place
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
delay(50);
|
delay(50);
|
||||||
float t = millis()*1.0e-3;
|
float t = millis()*1.0e-3;
|
||||||
float s = sin(t);
|
float s = sin(t);
|
||||||
//s += noise();
|
//s += noise();
|
||||||
uint32_t t1 = micros();
|
uint32_t t1 = micros();
|
||||||
derivative.update(s, t1);
|
derivative.update(s, t1);
|
||||||
float output = derivative.slope() * 1.0e6;
|
float output = derivative.slope() * 1.0e6;
|
||||||
uint32_t t2 = micros();
|
uint32_t t2 = micros();
|
||||||
Serial.printf("%f %f %f %f\n", t, output, s, cos(t));
|
Serial.printf("%f %f %f %f\n", t, output, s, cos(t));
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user