Rover: allow disarming from transmitter on skid-steering vehicles

This commit is contained in:
Randy Mackay 2017-11-22 17:39:16 +09:00
parent ada7d700c2
commit 14d9e932ab
2 changed files with 15 additions and 8 deletions

View File

@ -186,13 +186,22 @@ void Rover::read_aux_switch()
}
}
// return true if motors are moving
bool Rover::motor_active()
{
// Check if armed and output throttle servo is not neutral
if (hal.util->get_soft_armed()) {
// if soft disarmed, motors not active
if (!hal.util->get_soft_armed()) {
return false;
}
// check throttle is active
if (!is_zero(g2.motors.get_throttle())) {
return true;
}
// skid-steering vehicles active when steering
if (g2.motors.have_skid_steering() && !is_zero(g2.motors.get_steering())) {
return true;
}
return false;

View File

@ -77,10 +77,8 @@ void Rover::rudder_arm_disarm_check()
// not at full right rudder
rudder_arm_timer = 0;
}
} else if (!motor_active() && !g2.motors.have_skid_steering()) {
} else if (!motor_active()) {
// when armed and motor not active (not moving), full left rudder starts disarming counter
// This is disabled for skid steering otherwise when tring to turn a skid steering rover around
// the rover would disarm
if (channel_steer->get_control_in() < -4000) {
const uint32_t now = millis();