mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Rover: fix failsafe throttle
This commit is contained in:
parent
9b97ad0fc0
commit
ba8664193a
@ -243,10 +243,14 @@ void Rover::calc_nav_steer() {
|
||||
*****************************************/
|
||||
void Rover::set_servos(void) {
|
||||
// Apply slew rate limit on non Manual modes
|
||||
if (control_mode != MANUAL && control_mode != LEARNING) {
|
||||
g2.motors.slew_limit_throttle(true);
|
||||
} else {
|
||||
if (control_mode == MANUAL || control_mode == LEARNING) {
|
||||
g2.motors.slew_limit_throttle(false);
|
||||
if (failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
|
||||
g2.motors.set_throttle(0.0f);
|
||||
g2.motors.set_steering(0.0f);
|
||||
}
|
||||
} else {
|
||||
g2.motors.slew_limit_throttle(true);
|
||||
}
|
||||
|
||||
// send output signals to motors
|
||||
|
Loading…
Reference in New Issue
Block a user