Rover: use deadzone in 2-paddle steering

This commit is contained in:
Mark Whitehorn 2021-03-27 10:24:03 -06:00 committed by Randy Mackay
parent 0190a42e47
commit b65e564ec9
1 changed files with 2 additions and 2 deletions

View File

@ -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;