3 #include <AP_Arming/AP_Arming.h> 11 const AP_BattMonitor &battery,
const AP_InertialNav_NavEKF &inav)
12 : AP_Arming(ahrs_ref, compass, battery)
14 , _ahrs_navekf(ahrs_ref)
33 bool arm_checks(
bool display_failure,
bool arming_from_gcs);
36 bool ins_checks(
bool display_failure)
override;
38 bool gps_checks(
bool display_failure)
override;
52 const AP_InertialNav_NavEKF &_inav;
53 const AP_AHRS_NavEKF &_ahrs_navekf;
55 void parameter_checks_pid_warning_message(
bool display_failure,
const char *error_msg);
bool pre_arm_proximity_check(bool display_failure)
Definition: AP_Arming.cpp:508
bool rc_calibration_checks(bool display_failure) override
Definition: AP_Arming.cpp:349
bool compass_checks(bool display_failure) override
Definition: AP_Arming.cpp:92
void update(void)
Definition: AP_Arming.cpp:4
bool gps_checks(bool display_failure) override
Definition: AP_Arming.cpp:365
bool arm_checks(bool display_failure, bool arming_from_gcs)
Definition: AP_Arming.cpp:548
AP_Arming_Copter & operator=(const AP_Arming_Copter &)=delete
bool pre_arm_checks(bool display_failure) override
Definition: AP_Arming.cpp:28
bool all_checks_passing(bool arming_from_gcs)
Definition: AP_Arming.cpp:19
bool pre_arm_ekf_attitude_check()
Definition: AP_Arming.cpp:469
bool fence_checks(bool display_failure)
Definition: AP_Arming.cpp:110
bool parameter_checks(bool display_failure)
Definition: AP_Arming.cpp:167
bool pilot_throttle_checks(bool display_failure)
Definition: AP_Arming.cpp:329
bool barometer_checks(bool display_failure) override
Definition: AP_Arming.cpp:66
bool ins_checks(bool display_failure) override
Definition: AP_Arming.cpp:125
void set_pre_arm_check(bool b)
Definition: AP_Arming.cpp:697
bool board_voltage_checks(bool display_failure) override
Definition: AP_Arming.cpp:143
AP_Arming_Copter(const AP_AHRS_NavEKF &ahrs_ref, Compass &compass, const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav)
Definition: AP_Arming.h:10
bool pre_arm_terrain_check(bool display_failure)
Definition: AP_Arming.cpp:478
Definition: AP_Arming.h:5
bool motor_checks(bool display_failure)
Definition: AP_Arming.cpp:317