mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Rover: calc_speed_nudge honours max speed even in reverse
calc_speed_nudge allows the pilot to increase the speed of the vehicle including cases when the vehicle is in reverse. This fixes the nudging code so the pilot-nudged throttle does not surpass the vehicle's maximum speed even in reverse. Thanks to pavloblindnology for finding this!
This commit is contained in:
parent
c2be63b2b9
commit
6ce9b47807
@ -265,7 +265,7 @@ float Mode::calc_speed_nudge(float target_speed, float cruise_speed, float cruis
|
||||
const float vehicle_speed_max = calc_speed_max(cruise_speed, cruise_throttle);
|
||||
|
||||
// return unadjusted target if already over vehicle's projected maximum speed
|
||||
if (target_speed >= vehicle_speed_max) {
|
||||
if (fabsf(target_speed) >= vehicle_speed_max) {
|
||||
return target_speed;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user