Rover: use throttle rather than steering to determine target speed

This commit is contained in:
Peter Barker 2017-11-30 16:07:51 +11:00 committed by Randy Mackay
parent b1b1c0218f
commit 1a59b38204

View File

@ -7,7 +7,7 @@ void ModeSteering::update()
get_pilot_desired_steering_and_throttle(desired_steering, desired_throttle);
// convert pilot throttle input to desired speed (up to twice the cruise speed)
float target_speed = desired_steering * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);
const float target_speed = desired_throttle * 0.01f * calc_speed_max(g.speed_cruise, g.throttle_cruise * 0.01f);
// get speed forward
float speed;