From ac2f3da5ca16fe68a003cefc0fe4647272a47fad Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 21 Dec 2013 23:29:44 +1100 Subject: [PATCH] Rover: ensure fly_forward is set in AUTO --- APMrover2/APMrover2.pde | 2 ++ 1 file changed, 2 insertions(+) diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde index 2903d37dd8..12a5b38dec 100644 --- a/APMrover2/APMrover2.pde +++ b/APMrover2/APMrover2.pde @@ -852,6 +852,7 @@ static void update_current_mode(void) case AUTO: case RTL: case GUIDED: + set_reverse(false); calc_lateral_acceleration(); calc_nav_steer(); calc_throttle(g.speed_cruise); @@ -906,6 +907,7 @@ static void update_current_mode(void) // hold position - stop motors and center steering channel_throttle->servo_out = 0; channel_steer->servo_out = 0; + set_reverse(false); break; case INITIALISING: