mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Rover: disable slew limit by default on mode
This commit is contained in:
parent
809a9e5894
commit
b9644c4ec7
@ -54,13 +54,10 @@ bool Rover::in_stationary_loiter()
|
||||
void Rover::set_servos(void) {
|
||||
// Apply slew rate limit on non Manual modes
|
||||
if (control_mode == &mode_manual || control_mode == &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
|
||||
|
@ -25,6 +25,7 @@ void Mode::exit()
|
||||
|
||||
bool Mode::enter()
|
||||
{
|
||||
g2.motors.slew_limit_throttle(false);
|
||||
return _enter();
|
||||
}
|
||||
|
||||
|
@ -12,6 +12,7 @@ bool ModeAuto::_enter()
|
||||
auto_triggered = false;
|
||||
rover.restart_nav();
|
||||
rover.loiter_start_time = 0;
|
||||
g2.motors.slew_limit_throttle(true);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -9,6 +9,7 @@ bool ModeGuided::_enter()
|
||||
*/
|
||||
lateral_acceleration = 0.0f;
|
||||
rover.set_guided_WP(rover.current_loc);
|
||||
g2.motors.slew_limit_throttle(true);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -4,6 +4,7 @@
|
||||
bool ModeRTL::_enter()
|
||||
{
|
||||
rover.do_RTL();
|
||||
g2.motors.slew_limit_throttle(true);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user