mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: remove the unused test function get_failsafe
This commit is contained in:
parent
a1b96f659b
commit
122e88dbed
|
@ -197,13 +197,6 @@ RC_Channel::control_mix(float value)
|
|||
return (1 - abs(control_in / _high)) * value + control_in;
|
||||
}
|
||||
|
||||
// are we below a threshold?
|
||||
bool
|
||||
RC_Channel::get_failsafe(void)
|
||||
{
|
||||
return (radio_in < (radio_min - 50));
|
||||
}
|
||||
|
||||
// returns just the PWM without the offset from radio_min
|
||||
void
|
||||
RC_Channel::calc_pwm(void)
|
||||
|
|
|
@ -78,9 +78,6 @@ public:
|
|||
// call after first set_pwm
|
||||
void trim();
|
||||
|
||||
// did our read come in 50µs below the min?
|
||||
bool get_failsafe(void);
|
||||
|
||||
// value generated from PWM
|
||||
int16_t control_in;
|
||||
|
||||
|
|
Loading…
Reference in New Issue