Plane: don't do failsafe passthru with no RC input

thanks to Klrill-ka for the suggestion

fixes issue #1302
This commit is contained in:
Andrew Tridgell 2014-08-25 19:45:39 +10:00
parent 0f62dbf6ed
commit cf0741f6fd

View File

@ -37,8 +37,14 @@ void failsafe_check(void)
}
if (in_failsafe && tnow - last_timestamp > 20000) {
// pass RC inputs to outputs every 20ms
last_timestamp = tnow;
if (hal.rcin->num_channels() == 0) {
// we don't have any RC input to pass through
return;
}
// pass RC inputs to outputs every 20ms
hal.rcin->clear_overrides();
channel_roll->radio_out = channel_roll->read();
channel_pitch->radio_out = channel_pitch->read();