AP_Arming: remove unused set_enabled_checks
This commit is contained in:
parent
34a850e1a5
commit
d35a208dae
@ -115,11 +115,6 @@ uint16_t AP_Arming::get_enabled_checks()
|
|||||||
return checks_to_perform;
|
return checks_to_perform;
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Arming::set_enabled_checks(uint16_t ap)
|
|
||||||
{
|
|
||||||
checks_to_perform = ap;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool AP_Arming::barometer_checks(bool report)
|
bool AP_Arming::barometer_checks(bool report)
|
||||||
{
|
{
|
||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
|
@ -82,8 +82,6 @@ protected:
|
|||||||
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
|
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
|
||||||
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
|
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
|
||||||
|
|
||||||
void set_enabled_checks(uint16_t);
|
|
||||||
|
|
||||||
bool barometer_checks(bool report);
|
bool barometer_checks(bool report);
|
||||||
|
|
||||||
bool airspeed_checks(bool report);
|
bool airspeed_checks(bool report);
|
||||||
|
Loading…
Reference in New Issue
Block a user