diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 84af5cb6ff..241e9f0994 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -513,7 +513,7 @@ private: void init_rc_out(); void rudder_arm_disarm_check(); void read_radio(); - void control_failsafe(uint16_t pwm); + void radio_failsafe_check(uint16_t pwm); bool trim_radio(); // sailboat.cpp diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 1f8c92cc74..dda0b0a8c2 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -111,22 +111,22 @@ void Rover::read_radio() { if (!rc().read_input()) { // check if we lost RC link - control_failsafe(channel_throttle->get_radio_in()); + radio_failsafe_check(channel_throttle->get_radio_in()); return; } failsafe.last_valid_rc_ms = AP_HAL::millis(); // check that RC value are valid - control_failsafe(channel_throttle->get_radio_in()); + radio_failsafe_check(channel_throttle->get_radio_in()); // check if we try to do RC arm/disarm rudder_arm_disarm_check(); } -void Rover::control_failsafe(uint16_t pwm) +void Rover::radio_failsafe_check(uint16_t pwm) { if (!g.fs_throttle_enabled) { - // no throttle failsafe + // radio failsafe disabled return; }