diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index 2a4ba4fb4a..c5c8729348 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -21,7 +21,6 @@ void Mode::exit() bool Mode::enter() { - g2.motors.slew_limit_throttle(false); return _enter(); } diff --git a/APMrover2/mode_auto.cpp b/APMrover2/mode_auto.cpp index 696eda7aa0..49b1a2bf70 100644 --- a/APMrover2/mode_auto.cpp +++ b/APMrover2/mode_auto.cpp @@ -20,7 +20,6 @@ bool ModeAuto::_enter() // other initialisation auto_triggered = false; - g2.motors.slew_limit_throttle(true); // initialise reversed to be false set_reversed(false); diff --git a/APMrover2/mode_guided.cpp b/APMrover2/mode_guided.cpp index d6ea771168..b7301465f6 100644 --- a/APMrover2/mode_guided.cpp +++ b/APMrover2/mode_guided.cpp @@ -13,7 +13,6 @@ bool ModeGuided::_enter() // guided mode never travels in reverse rover.set_reverse(false); - g2.motors.slew_limit_throttle(true); return true; } diff --git a/APMrover2/mode_rtl.cpp b/APMrover2/mode_rtl.cpp index 1de35c9fd6..58c7e902a6 100644 --- a/APMrover2/mode_rtl.cpp +++ b/APMrover2/mode_rtl.cpp @@ -14,7 +14,6 @@ bool ModeRTL::_enter() // RTL never reverses rover.set_reverse(false); - g2.motors.slew_limit_throttle(true); return true; }