mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
APM: only copy manual channels in failsafe
this prevents non-manual channels changing value away from the trim value on startup
This commit is contained in:
parent
08cf9823fd
commit
8e656a60f2
@ -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…
Reference in New Issue
Block a user