From 5e9db462f541ae912ef3a80775fbb607d7b5f7b6 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Wed, 11 Jan 2012 21:45:24 -0800 Subject: [PATCH] attempting to force down without using Manual boost. --- ArduCopter/commands_logic.pde | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 4896d0a5b4..90bfeed52d 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -359,9 +359,12 @@ static bool verify_land() // remenber altitude for climb_rate old_alt = current_loc.alt; - if ((current_loc.alt - home.alt) < 200){ + if ((current_loc.alt - home.alt) < 250){ // don't bank to hold position wp_control = NO_NAV_MODE; + // try and come down faster + // by setting next_WP really low. + set_new_altitude(-1000); } if((current_loc.alt - home.alt) < 100 && velocity_land <= 50){