mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: remove unused GPS and baro filters
Saves 24bytes of RAM Removing the baro filter leads to noisier Baro Alt appearing in the log so we should make the inertial nav altitude appear in the CTUN message
This commit is contained in:
parent
232bdca4e2
commit
f263e81ed7
@ -92,7 +92,6 @@
|
||||
#include <AP_OpticalFlow.h> // Optical Flow library
|
||||
#include <Filter.h> // Filter library
|
||||
#include <AP_Buffer.h> // APM FIFO Buffer
|
||||
#include <AP_LeadFilter.h> // GPS Lead filter
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
@ -557,17 +556,12 @@ int32_t roll_axis;
|
||||
int32_t pitch_axis;
|
||||
|
||||
// Filters
|
||||
AP_LeadFilter xLeadFilter; // Long GPS lag filter
|
||||
AP_LeadFilter yLeadFilter; // Lat GPS lag filter
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
LowPassFilterFloat rate_roll_filter; // Rate Roll filter
|
||||
LowPassFilterFloat rate_pitch_filter; // Rate Pitch filter
|
||||
// LowPassFilterFloat rate_yaw_filter; // Rate Yaw filter
|
||||
#endif // HELI_FRAME
|
||||
|
||||
// Barometer filter
|
||||
AverageFilterInt32_Size5 baro_filter;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Circle Mode / Loiter control
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -28,7 +28,7 @@ static void init_barometer(void)
|
||||
static int32_t read_barometer(void)
|
||||
{
|
||||
barometer.read();
|
||||
return baro_filter.apply(barometer.get_altitude() * 100.0f);
|
||||
return barometer.get_altitude() * 100.0f;
|
||||
}
|
||||
|
||||
// return sonar altitude in centimeters
|
||||
|
Loading…
Reference in New Issue
Block a user