mirror of https://github.com/ArduPilot/ardupilot
Plane: updates for new RCInput API
This commit is contained in:
parent
e1b9135946
commit
09ed8d5819
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue