From 3aac281c5ab75cfd2326343a197d0c201620167e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 31 Jan 2015 17:23:43 +0900 Subject: [PATCH] Copter: land detector requires desired climb rate be < -20cm/s --- ArduCopter/config.h | 3 +++ ArduCopter/land_detector.pde | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index b24d572a9d..1e56b8f640 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -459,6 +459,9 @@ #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_DESIRED_CLIMBRATE_MAX +# define LAND_DETECTOR_DESIRED_CLIMBRATE_MAX -20 // vehicle desired climb rate must be below -20cm/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 diff --git a/ArduCopter/land_detector.pde b/ArduCopter/land_detector.pde index e8aeccb591..461737dd01 100644 --- a/ArduCopter/land_detector.pde +++ b/ArduCopter/land_detector.pde @@ -14,7 +14,7 @@ static bool land_complete_maybe() static void update_land_detector() { bool climb_rate_low = (abs(climb_rate) < LAND_DETECTOR_CLIMBRATE_MAX); - bool target_climb_rate_low = !pos_control.is_active_z() || (pos_control.get_desired_velocity().z < LAND_SPEED); + bool target_climb_rate_low = !pos_control.is_active_z() || (pos_control.get_desired_velocity().z <= LAND_DETECTOR_DESIRED_CLIMBRATE_MAX); bool motor_at_lower_limit = motors.limit.throttle_lower; bool throttle_low = (FRAME_CONFIG == HELI_FRAME) || (motors.get_throttle_out() < get_non_takeoff_throttle()); bool not_rotating_fast = (ahrs.get_gyro().length() < LAND_DETECTOR_ROTATION_MAX);