From c8a1e48f0cb9a75f33e801d76b1456a8162ee037 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Tue, 26 May 2015 20:16:52 -0400 Subject: [PATCH] Copter: Tradheli fix Land Detector. Tradheli does not use throttle_mix. --- ArduCopter/land_detector.pde | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduCopter/land_detector.pde b/ArduCopter/land_detector.pde index 78238d4eec..1bedbb21a3 100644 --- a/ArduCopter/land_detector.pde +++ b/ArduCopter/land_detector.pde @@ -21,8 +21,14 @@ static void update_land_detector() // range finder : tend to be problematic at very short distances // input throttle : in slow land the input throttle may be only slightly less than hover + +#if FRAME_CONFIG == HELI_FRAME + // check that collective pitch is on lower limit (should be constrained by LAND_COL_MIN) + bool motor_at_lower_limit = motors.limit.throttle_lower; +#else // check that the average throttle output is near minimum (less than 12.5% hover throttle) bool motor_at_lower_limit = motors.limit.throttle_lower && motors.is_throttle_mix_min(); +#endif Vector3f accel_ef = ahrs.get_accel_ef_blended(); accel_ef.z += GRAVITY_MSS;