diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 23261f6e38..a2c4dc528b 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -130,7 +130,7 @@ static void rudder_arm_check() static void read_radio() { - if (!hal.rcin->valid_channels()) { + if (!hal.rcin->new_input()) { control_failsafe(channel_throttle->radio_in); return; } diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index 2b54bf1202..539b5da357 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -140,7 +140,7 @@ test_passthru(uint8_t argc, const Menu::arg *argv) delay(20); // New radio frame? (we could use also if((millis()- timer) > 20) - if (hal.rcin->valid_channels() > 0) { + if (hal.rcin->new_input()) { cliSerial->print_P(PSTR("CH:")); for(int16_t i = 0; i < 8; i++) { cliSerial->print(hal.rcin->read(i)); // Print channel values