From 40c649a27b8aebf6b2183b508b082ac035a52d24 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 3 Jan 2012 23:29:28 -0800 Subject: [PATCH] Made landing disarm the motors --- ArduCopter/commands_logic.pde | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 3a7da1770f..b2e7835296 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -356,13 +356,16 @@ static bool verify_land() if (velocity_land == -1) velocity_land = 2000; - // a LP filter used to tell if we have landed - // will drive to 0 if we are on the ground - maybe, the baro is noisy - velocity_land = ((velocity_land * 7) + (old_alt - current_loc.alt)) / 8; + if (current_loc.alt < 500){ + // a LP filter used to tell if we have landed + // will drive to 0 if we are on the ground - maybe, the baro is noisy + velocity_land = ((velocity_land * 7) + (old_alt - current_loc.alt)) / 8; + } old_alt = current_loc.alt; if (current_loc.alt < 300){ + wp_control = NO_NAV_MODE; // Update by JLN for a safe AUTO landing @@ -381,12 +384,12 @@ static bool verify_land() } } - if(velocity_land <= 0){ + if(current_loc.alt < 300 && velocity_land <= 100){ land_complete = true; // reset old_alt old_alt == 0; - // commented out to prevent tragedy - //return true; + init_disarm_motors(); + return true; } //Serial.printf("N, %d\n", velocity_land); //Serial.printf("N_alt, %ld\n", next_WP.alt);