From d19f8c594b00bf6721aa400f6aa88d9338bb0b23 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 12 Mar 2018 14:39:01 +0900 Subject: [PATCH] Rover: fix two-paddle input decoding steering output was twice what it should be. full steering (i.e. 4500 or -4500) should occur when one paddle is up and the other is completely down --- APMrover2/mode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index 4d3dd899da..7cc480d8bf 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -78,7 +78,7 @@ void Mode::get_pilot_desired_steering_and_throttle(float &steering_out, float &t throttle_out = 0.5f * (left_paddle + right_paddle) * 100.0f; const float steering_dir = is_negative(throttle_out) ? -1 : 1; - steering_out = steering_dir * (left_paddle - right_paddle) * 4500.0f; + steering_out = steering_dir * (left_paddle - right_paddle) * 0.5f * 4500.0f; break; }