mirror of https://github.com/ArduPilot/ardupilot
Copter: use rangefinder to prevent auto-disarm in the air
only consider the vehicle to be landed if either no rangefinder or rangefinder shows an altitude below 2m
This commit is contained in:
parent
7ce7eb5a60
commit
06154fc4ab
|
@ -370,6 +370,9 @@
|
|||
#ifndef LAND_CANCEL_TRIGGER_THR
|
||||
# define LAND_CANCEL_TRIGGER_THR 700 // land is cancelled by input throttle above 700
|
||||
#endif
|
||||
#ifndef LAND_RANGEFINDER_MIN_ALT_CM
|
||||
#define LAND_RANGEFINDER_MIN_ALT_CM 200
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Landing Detector
|
||||
|
|
|
@ -71,7 +71,10 @@ void Copter::update_land_detector()
|
|||
// check that vertical speed is within 1m/s of zero
|
||||
bool descent_rate_low = fabsf(inertial_nav.get_velocity_z()) < 100;
|
||||
|
||||
if (motor_at_lower_limit && accel_stationary && descent_rate_low) {
|
||||
// if we have a healthy rangefinder only allow landing detection below 2 meters
|
||||
bool rangefinder_check = (!rangefinder_alt_ok() || rangefinder_state.alt_cm_filt.get() < LAND_RANGEFINDER_MIN_ALT_CM);
|
||||
|
||||
if (motor_at_lower_limit && accel_stationary && descent_rate_low && rangefinder_check) {
|
||||
// landed criteria met - increment the counter and check if we've triggered
|
||||
if( land_detector_count < ((float)LAND_DETECTOR_TRIGGER_SEC)*scheduler.get_loop_rate_hz()) {
|
||||
land_detector_count++;
|
||||
|
|
Loading…
Reference in New Issue