Plane: fixed handling of OVERRIDE_CHAN on arming
When arming we need to ensure that we don't enable any channels otherwise PX4IO will think that FMU is active and will stop running the internal RC mixer
This commit is contained in:
parent
c44ab01be8
commit
bc6a52f8db
@ -72,9 +72,6 @@ void Plane::read_control_switch()
|
||||
if (hal.util->get_soft_armed() || setup_failsafe_mixing()) {
|
||||
px4io_override_enabled = true;
|
||||
// disable output channels to force PX4IO override
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
hal.rcout->disable_ch(i);
|
||||
}
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("PX4IO Override enabled"));
|
||||
} else {
|
||||
// we'll try again next loop. The PX4IO code sometimes
|
||||
@ -98,6 +95,17 @@ void Plane::read_control_switch()
|
||||
// re-arm and take manual control
|
||||
hal.rcout->force_safety_off();
|
||||
}
|
||||
if (px4io_override_enabled) {
|
||||
/*
|
||||
ensure that all channels are disabled from the FMU. If
|
||||
PX4IO receives any channel input from the FMU then it
|
||||
will think the FMU is still active and won't enable the
|
||||
internal mixer.
|
||||
*/
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
hal.rcout->disable_ch(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
}
|
||||
|
@ -748,7 +748,9 @@ bool Plane::arm_motors(AP_Arming::ArmingMethod method)
|
||||
}
|
||||
|
||||
//only log if arming was successful
|
||||
channel_throttle->enable_out();
|
||||
if (!px4io_override_enabled) {
|
||||
channel_throttle->enable_out();
|
||||
}
|
||||
change_arm_state();
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user