mirror of https://github.com/ArduPilot/ardupilot
APM: fixed altitude_filter for new LowPassFilter syntax
This commit is contained in:
parent
8d1905a40b
commit
7b733cd12b
|
@ -1,16 +1,20 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
|
// filter altitude from the barometer with a low pass filter
|
||||||
|
static LowPassFilterInt32 altitude_filter;
|
||||||
|
|
||||||
|
|
||||||
static void init_barometer(void)
|
static void init_barometer(void)
|
||||||
{
|
{
|
||||||
barometer.calibrate(mavlink_delay);
|
barometer.calibrate(mavlink_delay);
|
||||||
|
|
||||||
|
// filter at 100ms sampling, with 0.7Hz cutoff frequency
|
||||||
|
altitude_filter.set_cutoff_frequency(0.1, 0.7);
|
||||||
|
|
||||||
ahrs.set_barometer(&barometer);
|
ahrs.set_barometer(&barometer);
|
||||||
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
|
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
|
||||||
}
|
}
|
||||||
|
|
||||||
// filter altitude from the barometer with a 0.3 low pass
|
|
||||||
// filter
|
|
||||||
static LowPassFilterInt32 altitude_filter(0.3);
|
|
||||||
|
|
||||||
// read the barometer and return the updated altitude in centimeters
|
// read the barometer and return the updated altitude in centimeters
|
||||||
// above the calibration altitude
|
// above the calibration altitude
|
||||||
static int32_t read_barometer(void)
|
static int32_t read_barometer(void)
|
||||||
|
|
Loading…
Reference in New Issue