Skip to content
Snippets Groups Projects
Commit a0f69e06 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

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
parent c299f721
No related branches found
No related tags found
No related merge requests found
...@@ -65,7 +65,10 @@ static void read_control_switch() ...@@ -65,7 +65,10 @@ static void read_control_switch()
// if the user has configured an override channel then check it // if the user has configured an override channel then check it
bool override = (hal.rcin->read(g.override_channel-1) >= PX4IO_OVERRIDE_PWM); bool override = (hal.rcin->read(g.override_channel-1) >= PX4IO_OVERRIDE_PWM);
if (override && !px4io_override_enabled) { 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; px4io_override_enabled = true;
// disable output channels to force PX4IO override // disable output channels to force PX4IO override
for (uint8_t i=0; i<16; i++) { for (uint8_t i=0; i<16; i++) {
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment