mirror of https://github.com/ArduPilot/ardupilot
Rover: support disabling rudder arming
This commit is contained in:
parent
b61b25e5bf
commit
b1a4cd55fd
|
@ -47,6 +47,12 @@ void Rover::init_rc_out()
|
||||||
*/
|
*/
|
||||||
void Rover::rudder_arm_disarm_check()
|
void Rover::rudder_arm_disarm_check()
|
||||||
{
|
{
|
||||||
|
// check if arming/disarm using rudder is allowed
|
||||||
|
AP_Arming::ArmingRudder arming_rudder = arming.rudder_arming();
|
||||||
|
if (arming_rudder == AP_Arming::ARMING_RUDDER_DISABLED) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
// In Rover we need to check that its set to the throttle trim and within the DZ
|
// In Rover we need to check that its set to the throttle trim and within the DZ
|
||||||
// if throttle is not within trim dz, then pilot cannot rudder arm/disarm
|
// if throttle is not within trim dz, then pilot cannot rudder arm/disarm
|
||||||
if (!channel_throttle->in_trim_dz()) {
|
if (!channel_throttle->in_trim_dz()) {
|
||||||
|
@ -79,7 +85,7 @@ void Rover::rudder_arm_disarm_check()
|
||||||
// not at full right rudder
|
// not at full right rudder
|
||||||
rudder_arm_timer = 0;
|
rudder_arm_timer = 0;
|
||||||
}
|
}
|
||||||
} else if (!g2.motors.active()) {
|
} else if ((arming_rudder == AP_Arming::ARMING_RUDDER_ARMDISARM) && !g2.motors.active()) {
|
||||||
// when armed and motor not active (not moving), full left rudder starts disarming counter
|
// when armed and motor not active (not moving), full left rudder starts disarming counter
|
||||||
if (channel_steer->get_control_in() < -4000) {
|
if (channel_steer->get_control_in() < -4000) {
|
||||||
const uint32_t now = millis();
|
const uint32_t now = millis();
|
||||||
|
|
Loading…
Reference in New Issue