Rover: updates for new RCInput API
This commit is contained in:
parent
6eee2421cc
commit
843318f58c
@ -45,7 +45,7 @@ static void init_rc_out()
|
||||
|
||||
static void read_radio()
|
||||
{
|
||||
if (!hal.rcin->valid_channels()) {
|
||||
if (!hal.rcin->new_input()) {
|
||||
control_failsafe(channel_throttle->radio_in);
|
||||
return;
|
||||
}
|
||||
|
@ -104,7 +104,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("CH:");
|
||||
for(int i = 0; i < 8; i++){
|
||||
cliSerial->print(hal.rcin->read(i)); // Print channel values
|
||||
|
Loading…
Reference in New Issue
Block a user