mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: wrap things in P_INERTIALSENSOR_ENABLED
This commit is contained in:
parent
217253b58f
commit
5cbb776951
|
@ -326,6 +326,7 @@ bool AP_Arming::logging_checks(bool report)
|
|||
return true;
|
||||
}
|
||||
|
||||
#if AP_INERTIALSENSOR_ENABLED
|
||||
bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins)
|
||||
{
|
||||
const uint8_t accel_count = ins.get_accel_count();
|
||||
|
@ -488,6 +489,7 @@ bool AP_Arming::ins_checks(bool report)
|
|||
|
||||
return true;
|
||||
}
|
||||
#endif // AP_INERTIALSENSOR_ENABLED
|
||||
|
||||
bool AP_Arming::compass_checks(bool report)
|
||||
{
|
||||
|
@ -1495,7 +1497,9 @@ bool AP_Arming::pre_arm_checks(bool report)
|
|||
& heater_min_temperature_checks(report)
|
||||
#endif
|
||||
& barometer_checks(report)
|
||||
#if AP_INERTIALSENSOR_ENABLED
|
||||
& ins_checks(report)
|
||||
#endif
|
||||
& compass_checks(report)
|
||||
& gps_checks(report)
|
||||
& battery_checks(report)
|
||||
|
@ -1827,7 +1831,7 @@ void AP_Arming::check_forced_logging(const AP_Arming::Method method)
|
|||
AP_Arming *AP_Arming::_singleton = nullptr;
|
||||
|
||||
/*
|
||||
* Get the AP_InertialSensor singleton
|
||||
* Get the AP_Arming singleton
|
||||
*/
|
||||
AP_Arming *AP_Arming::get_singleton()
|
||||
{
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
#include "AP_Arming_config.h"
|
||||
#include "AP_InertialSensor/AP_InertialSensor_config.h"
|
||||
|
||||
class AP_Arming {
|
||||
public:
|
||||
|
@ -163,7 +164,9 @@ protected:
|
|||
|
||||
bool logging_checks(bool report);
|
||||
|
||||
#if AP_INERTIALSENSOR_ENABLED
|
||||
virtual bool ins_checks(bool report);
|
||||
#endif
|
||||
|
||||
bool compass_checks(bool report);
|
||||
|
||||
|
@ -249,8 +252,10 @@ private:
|
|||
|
||||
static AP_Arming *_singleton;
|
||||
|
||||
#if AP_INERTIALSENSOR_ENABLED
|
||||
bool ins_accels_consistent(const class AP_InertialSensor &ins);
|
||||
bool ins_gyros_consistent(const class AP_InertialSensor &ins);
|
||||
#endif
|
||||
|
||||
// check if we should keep logging after disarming
|
||||
void check_forced_logging(const AP_Arming::Method method);
|
||||
|
|
Loading…
Reference in New Issue