diff --git a/ArduCopter/flight_mode.pde b/ArduCopter/flight_mode.pde
index 35af7ca57a2228d02baf9de55ea376d47d7b5588..9caf7eb316c221a3d03d3b39f5346312338dce36 100644
--- a/ArduCopter/flight_mode.pde
+++ b/ArduCopter/flight_mode.pde
@@ -227,6 +227,13 @@ static void exit_mode(uint8_t old_control_mode, uint8_t new_control_mode)
         // this assumes all manual flight modes use get_pilot_desired_throttle to translate pilot input to output throttle
         set_accel_throttle_I_from_pilot_throttle(get_pilot_desired_throttle(g.rc_3.control_in));
     }
+    
+#if FRAME_CONFIG == HELI_FRAME
+    // firmly reset the flybar passthrough to false when exiting acro mode.
+    if (old_control_mode == ACRO) {
+        attitude_control.use_flybar_passthrough(false);
+    }
+#endif //HELI_FRAME
 }
 
 // returns true or false whether mode requires GPS