From 0830e057e04230444f4db91ace7f293ccbe0027d Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Thu, 3 May 2018 17:58:27 +0900
Subject: [PATCH] Rover: manual mode outputs unscaled steering

---
 APMrover2/mode_manual.cpp | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/APMrover2/mode_manual.cpp b/APMrover2/mode_manual.cpp
index ecb3fbe753..c1bc784d42 100644
--- a/APMrover2/mode_manual.cpp
+++ b/APMrover2/mode_manual.cpp
@@ -8,7 +8,7 @@ void ModeManual::update()
 
     // copy RC scaled inputs to outputs
     g2.motors.set_throttle(desired_throttle);
-    g2.motors.set_steering(desired_steering);
+    g2.motors.set_steering(desired_steering, false);
 
     // mark us as in_reverse when using a negative throttle to stop AHRS getting off
     rover.set_reverse(is_negative(g2.motors.get_throttle()));