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

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

thanks to Klrill-ka for the suggestion

fixes issue #1302
parent 0f62dbf6
No related branches found
No related tags found
No related merge requests found
...@@ -37,8 +37,14 @@ void failsafe_check(void) ...@@ -37,8 +37,14 @@ void failsafe_check(void)
} }
if (in_failsafe && tnow - last_timestamp > 20000) { if (in_failsafe && tnow - last_timestamp > 20000) {
// pass RC inputs to outputs every 20ms
last_timestamp = tnow; 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(); hal.rcin->clear_overrides();
channel_roll->radio_out = channel_roll->read(); channel_roll->radio_out = channel_roll->read();
channel_pitch->radio_out = channel_pitch->read(); channel_pitch->radio_out = channel_pitch->read();
......
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