mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Blimp: remove land_acel_ef_filter
Landing is for wimps
This commit is contained in:
parent
adf9c21d48
commit
6ac68c5875
@ -289,7 +289,6 @@ Blimp::Blimp(void)
|
|||||||
: logger(g.log_bitmask),
|
: logger(g.log_bitmask),
|
||||||
flight_modes(&g.flight_mode1),
|
flight_modes(&g.flight_mode1),
|
||||||
control_mode(Mode::Number::MANUAL),
|
control_mode(Mode::Number::MANUAL),
|
||||||
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),
|
|
||||||
rc_throttle_control_in_filter(1.0f),
|
rc_throttle_control_in_filter(1.0f),
|
||||||
inertial_nav(ahrs),
|
inertial_nav(ahrs),
|
||||||
param_loader(var_info),
|
param_loader(var_info),
|
||||||
|
@ -209,7 +209,6 @@ private:
|
|||||||
|
|
||||||
// Altitude
|
// Altitude
|
||||||
int32_t baro_alt; // barometer altitude in cm above home
|
int32_t baro_alt; // barometer altitude in cm above home
|
||||||
LowPassFilterVector3f land_accel_ef_filter; // accelerations for land and crash detector tests
|
|
||||||
|
|
||||||
// filtered pilot's throttle input used to cancel landing if throttle held high
|
// filtered pilot's throttle input used to cancel landing if throttle held high
|
||||||
LowPassFilterFloat rc_throttle_control_in_filter;
|
LowPassFilterFloat rc_throttle_control_in_filter;
|
||||||
|
Loading…
Reference in New Issue
Block a user