From 9841cb0335f1c6734b8552ecaee2f81ff93385da Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 18 Mar 2012 15:16:04 +0900 Subject: [PATCH] ArduCopter - small change to ensure both roll and pitch commands are zero before switching out of loiter_override (loiter override becomes true when roll+pitch command is greater than 5 degrees and switches back to false when both become zero) - remove incorrect comments about when loiter target position is reset. --- ArduCopter/ArduCopter.pde | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 4f7fcd2aa7..78f8ce07c4 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1781,12 +1781,10 @@ static void update_navigation() // go of the sticks if((abs(g.rc_2.control_in) + abs(g.rc_1.control_in)) > 500){ - // flag will reset when speed drops below .5 m/s loiter_override = true; } // Allow the user to take control temporarily, - // 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; @@ -1795,7 +1793,7 @@ static void update_navigation() next_WP.lat = current_loc.lat; next_WP.lng = current_loc.lng; - if((g.rc_2.control_in + g.rc_1.control_in) == 0){ + if( g.rc_2.control_in == 0 && g.rc_1.control_in == 0 ){ loiter_override = false; wp_control = LOITER_MODE; }