mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: prevent baro reset from OVERRIDE_CHAN
using OVERRIDE_CHAN would cause a baro reset as it would mean we are temporarily disarmed, and the "reset baro and GPS when disarmed" check would reset the baro Now we only do the mixer update if disarmed
This commit is contained in:
parent
c299f721b1
commit
a0f69e06a7
@ -65,7 +65,10 @@ static void read_control_switch()
|
||||
// if the user has configured an override channel then check it
|
||||
bool override = (hal.rcin->read(g.override_channel-1) >= PX4IO_OVERRIDE_PWM);
|
||||
if (override && !px4io_override_enabled) {
|
||||
if (setup_failsafe_mixing()) {
|
||||
// we only update the mixer if we are not armed. This is
|
||||
// important as otherwise we will need to temporarily
|
||||
// disarm to change the mixer
|
||||
if (ahrs.get_armed() || setup_failsafe_mixing()) {
|
||||
px4io_override_enabled = true;
|
||||
// disable output channels to force PX4IO override
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
|
Loading…
Reference in New Issue
Block a user