Browse Source

APM: only copy manual channels in failsafe

this prevents non-manual channels changing value away from the trim
value on startup
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
c0798730a8
  1. 3
      ArduPlane/failsafe.pde

3
ArduPlane/failsafe.pde

@ -39,8 +39,9 @@ void failsafe_check(uint32_t tnow) @@ -39,8 +39,9 @@ void failsafe_check(uint32_t tnow)
// pass RC inputs to outputs every 20ms
last_timestamp = tnow;
APM_RC.clearOverride();
for (uint8_t ch=0; ch<8; ch++) {
for (uint8_t ch=0; ch<4; ch++) {
APM_RC.OutputCh(ch, APM_RC.InputCh(ch));
}
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual);
}
}

Loading…
Cancel
Save