Rover: rename control_failsafe to radio_failsafe_check

although this makes the name inconsistent with plane it is more precise because control can also come from rc-overrides which are covered by the GCS failsafe
This commit is contained in:
Randy Mackay 2018-10-31 14:26:19 +09:00
parent 4ae35ee3ea
commit fa5de31cb9
2 changed files with 5 additions and 5 deletions

View File

@ -513,7 +513,7 @@ private:
void init_rc_out(); void init_rc_out();
void rudder_arm_disarm_check(); void rudder_arm_disarm_check();
void read_radio(); void read_radio();
void control_failsafe(uint16_t pwm); void radio_failsafe_check(uint16_t pwm);
bool trim_radio(); bool trim_radio();
// sailboat.cpp // sailboat.cpp

View File

@ -111,22 +111,22 @@ void Rover::read_radio()
{ {
if (!rc().read_input()) { if (!rc().read_input()) {
// check if we lost RC link // check if we lost RC link
control_failsafe(channel_throttle->get_radio_in()); radio_failsafe_check(channel_throttle->get_radio_in());
return; return;
} }
failsafe.last_valid_rc_ms = AP_HAL::millis(); failsafe.last_valid_rc_ms = AP_HAL::millis();
// check that RC value are valid // 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 // check if we try to do RC arm/disarm
rudder_arm_disarm_check(); rudder_arm_disarm_check();
} }
void Rover::control_failsafe(uint16_t pwm) void Rover::radio_failsafe_check(uint16_t pwm)
{ {
if (!g.fs_throttle_enabled) { if (!g.fs_throttle_enabled) {
// no throttle failsafe // radio failsafe disabled
return; return;
} }