mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: use throttle rather than steering to determine target speed
This commit is contained in:
parent
b1b1c0218f
commit
1a59b38204
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user