Rover: move manual mode failsafe handling to mode class

This commit is contained in:
Randy Mackay 2017-07-19 17:00:13 +09:00
parent 6626c2e12e
commit 2321cefdc2
2 changed files with 11 additions and 12 deletions

View File

@ -51,15 +51,8 @@ bool Rover::in_stationary_loiter()
/*****************************************
Set the flight control servos based on the current calculated values
*****************************************/
void Rover::set_servos(void) {
// Apply slew rate limit on non Manual modes
if (control_mode == &mode_manual || control_mode == &mode_learning) {
if (failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
g2.motors.set_throttle(0.0f);
g2.motors.set_steering(0.0f);
}
}
void Rover::set_servos(void)
{
// send output signals to motors
if (motor_test) {
g2.motors.slew_limit_throttle(false);

View File

@ -3,9 +3,15 @@
void ModeManual::update()
{
// check for radio failsafe
if (rover.failsafe.bits & FAILSAFE_EVENT_THROTTLE) {
g2.motors.set_throttle(0.0f);
g2.motors.set_steering(0.0f);
} else {
// copy RC scaled inputs to outputs
g2.motors.set_throttle(channel_throttle->get_control_in());
g2.motors.set_steering(channel_steer->get_control_in());
}
// mark us as in_reverse when using a negative throttle to stop AHRS getting off
rover.set_reverse(is_negative(g2.motors.get_throttle()));