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:
Randy Mackay 2018-01-19 09:23:33 +09:00
parent c2be63b2b9
commit 6ce9b47807
1 changed files with 1 additions and 1 deletions

View File

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