Plane: updates for new RCInput API

This commit is contained in:
Andrew Tridgell 2014-03-25 14:41:14 +11:00
parent e1b9135946
commit 09ed8d5819
2 changed files with 2 additions and 2 deletions

View File

@ -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;
}

View File

@ -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