mirror of https://github.com/ArduPilot/ardupilot
Rover: fixed bug when reverse throttle would increase speed in AUTO
Fixed this bug https://github.com/diydrones/ardupilot/issues/840 If a Rover was in AUTO and the user moved the throttle stick into reverse past 50% the rover would increase. Basically the throttle nudge behaviour was the same regardless of whether you moved the throttle forward or backward.
This commit is contained in:
parent
c24ba83fb1
commit
103119fe9a
|
@ -55,8 +55,13 @@ void Rover::read_radio()
|
|||
|
||||
channel_throttle->servo_out = channel_throttle->control_in;
|
||||
|
||||
if (abs(channel_throttle->servo_out) > 50) {
|
||||
throttle_nudge = (g.throttle_max - g.throttle_cruise) * ((fabsf(channel_throttle->norm_input())-0.5f) / 0.5f);
|
||||
// Check if the throttle value is above 50% and we need to nudge
|
||||
// Make sure its above 50% in the direction we are travelling
|
||||
if ((abs(channel_throttle->servo_out) > 50) &&
|
||||
(((channel_throttle->servo_out < 0) && in_reverse) ||
|
||||
((channel_throttle->servo_out > 0) && !in_reverse))) {
|
||||
throttle_nudge = (g.throttle_max - g.throttle_cruise) *
|
||||
((fabsf(channel_throttle->norm_input())-0.5f) / 0.5f);
|
||||
} else {
|
||||
throttle_nudge = 0;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue