From 651a0182a743dc9885bba20279ca85999845c020 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 14 Jan 2015 12:49:39 +0900 Subject: [PATCH] Copter: move land_detector to separate file --- ArduCopter/control_land.pde | 41 ---------------------------------- ArduCopter/land_detector.pde | 43 ++++++++++++++++++++++++++++++++++++ 2 files changed, 43 insertions(+), 41 deletions(-) create mode 100644 ArduCopter/land_detector.pde diff --git a/ArduCopter/control_land.pde b/ArduCopter/control_land.pde index 9547cc707a..c1c64efd2b 100644 --- a/ArduCopter/control_land.pde +++ b/ArduCopter/control_land.pde @@ -1,7 +1,5 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -// counter to verify landings -static uint16_t land_detector = LAND_DETECTOR_TRIGGER; // we assume we are landed static bool land_with_gps; static uint32_t land_start_time; @@ -192,45 +190,6 @@ static float get_throttle_land() } } -// land_complete_maybe - return true if we may have landed (used to reset loiter targets during landing) -static bool land_complete_maybe() -{ - return (ap.land_complete || ap.land_complete_maybe); -} - -// update_land_detector - checks if we have landed and updates the ap.land_complete flag -// called at 50hz -static void update_land_detector() -{ - bool climb_rate_small = 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 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; - - if (climb_rate_small && target_climb_rate_low && motor_at_lower_limit && throttle_low && not_rotating_fast) { - if (!ap.land_complete) { - // increase counter until we hit the trigger then set land complete flag - if( land_detector < LAND_DETECTOR_TRIGGER) { - land_detector++; - }else{ - set_land_complete(true); - land_detector = LAND_DETECTOR_TRIGGER; - } - } - } else { - // we've sensed movement up or down so reset land_detector - land_detector = 0; - // if throttle output is high then clear landing flag - if (motors.get_throttle_out() > get_non_takeoff_throttle()) { - set_land_complete(false); - } - } - - // set land maybe flag - set_land_complete_maybe(land_detector >= LAND_DETECTOR_MAYBE_TRIGGER); -} - // land_do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch // called during GPS failsafe to ensure that if we were already in LAND mode that we do not use the GPS // has no effect if we are not already in LAND mode diff --git a/ArduCopter/land_detector.pde b/ArduCopter/land_detector.pde new file mode 100644 index 0000000000..8ac512d78d --- /dev/null +++ b/ArduCopter/land_detector.pde @@ -0,0 +1,43 @@ +/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +// counter to verify landings +static uint16_t land_detector = LAND_DETECTOR_TRIGGER; // we assume we are landed + +// land_complete_maybe - return true if we may have landed (used to reset loiter targets during landing) +static bool land_complete_maybe() +{ + return (ap.land_complete || ap.land_complete_maybe); +} + +// update_land_detector - checks if we have landed and updates the ap.land_complete flag +// called at 50hz +static void update_land_detector() +{ + bool climb_rate_small = 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 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; + + if (climb_rate_small && target_climb_rate_low && motor_at_lower_limit && throttle_low && not_rotating_fast) { + if (!ap.land_complete) { + // increase counter until we hit the trigger then set land complete flag + if( land_detector < LAND_DETECTOR_TRIGGER) { + land_detector++; + }else{ + set_land_complete(true); + land_detector = LAND_DETECTOR_TRIGGER; + } + } + } else { + // we've sensed movement up or down so reset land_detector + land_detector = 0; + // if throttle output is high then clear landing flag + if (motors.get_throttle_out() > get_non_takeoff_throttle()) { + set_land_complete(false); + } + } + + // set land maybe flag + set_land_complete_maybe(land_detector >= LAND_DETECTOR_MAYBE_TRIGGER); +}