Copter: land check gets overall throttle and rotation rate check

add check that overall throttle level is below the non-takeoff throttle
instead of just checking that it's motors have hit their lower limits
because low limits can also be caused by high yaw rotation requests.
Absolute climb rate requirement reduced to 30cm/s
This commit is contained in:
Randy Mackay 2014-09-03 20:43:51 +09:00
parent b214b8ba15
commit dbb0283dba
2 changed files with 9 additions and 2 deletions

View File

@ -452,6 +452,12 @@
#ifndef LAND_DETECTOR_TRIGGER
# define LAND_DETECTOR_TRIGGER 50 // number of 50hz iterations with near zero climb rate and low throttle that triggers landing complete.
#endif
#ifndef LAND_DETECTOR_CLIMBRATE_MAX
# define LAND_DETECTOR_CLIMBRATE_MAX 30 // vehicle climb rate must be between -30 and +30 cm/s
#endif
#ifndef LAND_DETECTOR_ROTATION_MAX
# define LAND_DETECTOR_ROTATION_MAX 0.50f // vehicle rotation must be below 0.5 rad/sec (=30deg/sec for) vehicle to consider itself landed
#endif
#ifndef LAND_REQUIRE_MIN_THROTTLE_TO_DISARM // require pilot to reduce throttle to minimum before vehicle will disarm
# define LAND_REQUIRE_MIN_THROTTLE_TO_DISARM ENABLED
#endif

View File

@ -191,8 +191,9 @@ static float get_throttle_land()
// called at 50hz
static void update_land_detector()
{
// detect whether we have landed by watching for low climb rate and minimum throttle
if (abs(climb_rate) < 40 && motors.limit.throttle_lower) {
// detect whether we have landed by watching for low climb rate, motors hitting their lower limit, overall low throttle and low rotation rate
if ((abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX) && motors.limit.throttle_lower &&
(motors.get_throttle_out() < get_non_takeoff_throttle()) && (ahrs.get_gyro().length() < LAND_DETECTOR_ROTATION_MAX)) {
if (!ap.land_complete) {
// increase counter until we hit the trigger then set land complete flag
if( land_detector < LAND_DETECTOR_TRIGGER) {