mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: Support new RC_Channels::read_input()
This commit is contained in:
parent
6642b9e585
commit
da9053655b
@ -101,15 +101,13 @@ void Rover::rudder_arm_disarm_check()
|
||||
|
||||
void Rover::read_radio()
|
||||
{
|
||||
if (!RC_Channels::has_new_input()) {
|
||||
if (!RC_Channels::read_input()) {
|
||||
// check if we lost RC link
|
||||
control_failsafe(channel_throttle->get_radio_in());
|
||||
return;
|
||||
}
|
||||
|
||||
failsafe.last_valid_rc_ms = AP_HAL::millis();
|
||||
// read the RC value
|
||||
RC_Channels::set_pwm_all();
|
||||
// check that RC value are valid
|
||||
control_failsafe(channel_throttle->get_radio_in());
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user