From af0b0d5a7f712f5e6a07b3c227f4fcc356e2ed98 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 29 Jan 2012 16:14:56 -0800 Subject: [PATCH] made Loiter over ride exit dependent not on speed, but centered sticks. --- ArduCopter/ArduCopter.pde | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 2279a72a08..ad6f19c6e4 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1686,15 +1686,15 @@ static void update_navigation() // regain hold when the speed goes down to .5m/s if(loiter_override){ // this sets the copter to not try and nav while we control it - wp_control = NO_NAV_MODE; + wp_control = NO_NAV_MODE; // reset LOITER to current position - next_WP.lat = current_loc.lat; - next_WP.lng = current_loc.lng; + next_WP.lat = current_loc.lat; + next_WP.lng = current_loc.lng; - if(g_gps->ground_speed < 50){ - loiter_override = false; - wp_control = LOITER_MODE; + if((g.rc_2.control_in + g.rc_1.control_in) == 0){ + loiter_override = false; + wp_control = LOITER_MODE; } }else{ wp_control = LOITER_MODE;