From b65e564ec97c91a08cca96d27cea52243864bb3c Mon Sep 17 00:00:00 2001 From: Mark Whitehorn Date: Sat, 27 Mar 2021 10:24:03 -0600 Subject: [PATCH] Rover: use deadzone in 2-paddle steering --- Rover/mode.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Rover/mode.cpp b/Rover/mode.cpp index df89734b6e..5d42e31280 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -84,8 +84,8 @@ void Mode::get_pilot_input(float &steering_out, float &throttle_out) // left paddle from steering input channel, right paddle from throttle input channel // steering = left-paddle - right-paddle // throttle = average(left-paddle, right-paddle) - const float left_paddle = rover.channel_steer->norm_input(); - const float right_paddle = rover.channel_throttle->norm_input(); + const float left_paddle = rover.channel_steer->norm_input_dz(); + const float right_paddle = rover.channel_throttle->norm_input_dz(); throttle_out = 0.5f * (left_paddle + right_paddle) * 100.0f; steering_out = (left_paddle - right_paddle) * 0.5f * 4500.0f;