mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Rover: steering mode reversing fix
This commit is contained in:
parent
916fe80000
commit
072b5187a3
@ -52,7 +52,7 @@ void ModeSteering::update()
|
|||||||
stop_vehicle();
|
stop_vehicle();
|
||||||
} else {
|
} else {
|
||||||
// run lateral acceleration to steering controller
|
// run lateral acceleration to steering controller
|
||||||
calc_steering_from_lateral_acceleration(desired_lat_accel, false);
|
calc_steering_from_lateral_acceleration(desired_lat_accel, reversed);
|
||||||
calc_throttle(target_speed, false);
|
calc_throttle(target_speed, false);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user