mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Rover: remove unused throttle_failsafe_active method
This commit is contained in:
parent
415cb41c7f
commit
82e61d7198
@ -510,7 +510,6 @@ private:
|
||||
void rudder_arm_disarm_check();
|
||||
void read_radio();
|
||||
void control_failsafe(uint16_t pwm);
|
||||
bool throttle_failsafe_active();
|
||||
void trim_control_surfaces();
|
||||
void trim_radio();
|
||||
|
||||
|
@ -175,25 +175,6 @@ void Rover::control_failsafe(uint16_t pwm)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
return true if throttle level is below throttle failsafe threshold
|
||||
or RC input is invalid
|
||||
*/
|
||||
bool Rover::throttle_failsafe_active(void)
|
||||
{
|
||||
if (!g.fs_throttle_enabled) {
|
||||
return false;
|
||||
}
|
||||
if (millis() - failsafe.last_valid_rc_ms > 1000) {
|
||||
// we haven't had a valid RC frame for 1 seconds
|
||||
return true;
|
||||
}
|
||||
if (channel_throttle->get_reverse()) {
|
||||
return channel_throttle->get_radio_in() >= g.fs_throttle_value;
|
||||
}
|
||||
return channel_throttle->get_radio_in() <= g.fs_throttle_value;
|
||||
}
|
||||
|
||||
void Rover::trim_control_surfaces()
|
||||
{
|
||||
read_radio();
|
||||
|
Loading…
Reference in New Issue
Block a user