mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: remove duplicate fail-safe time check
This commit is contained in:
parent
62354527d4
commit
cd46c5006a
|
@ -252,7 +252,7 @@ int16_t Plane::rudder_input(void)
|
|||
|
||||
void Plane::control_failsafe()
|
||||
{
|
||||
if (millis() - failsafe.last_valid_rc_ms > 1000 || rc_failsafe_active()) {
|
||||
if (rc_failsafe_active()) {
|
||||
// we do not have valid RC input. Set all primary channel
|
||||
// control inputs to the trim value and throttle to min
|
||||
channel_roll->set_radio_in(channel_roll->get_radio_trim());
|
||||
|
|
Loading…
Reference in New Issue