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
This commit is contained in:
Randy Mackay 2018-03-12 14:39:01 +09:00
parent 128f982351
commit d19f8c594b

View File

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