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;
const AP_AHRS_NavEKF & _ahrs_navekf
bool arm_checks(bool display_failure, bool arming_from_gcs)
const AP_InertialNav_NavEKF & _inav
bool barometer_checks(bool display_failure) override
AP_Arming_Copter(const AP_AHRS_NavEKF &ahrs_ref, Compass &compass, const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav)
bool board_voltage_checks(bool display_failure) override
AP_Arming_Copter & operator=(const AP_Arming_Copter &)=delete
struct _USB_OTG_GOTGCTL_TypeDef::@51 b
bool all_checks_passing(bool arming_from_gcs)
bool rc_calibration_checks(bool display_failure) override
bool parameter_checks(bool display_failure)
bool ins_checks(bool display_failure) override
bool pilot_throttle_checks(bool display_failure)
bool pre_arm_proximity_check(bool display_failure)
bool pre_arm_terrain_check(bool display_failure)
void set_pre_arm_check(bool b)
bool pre_arm_checks(bool display_failure) override
bool motor_checks(bool display_failure)
bool fence_checks(bool display_failure)
bool pre_arm_ekf_attitude_check()
void parameter_checks_pid_warning_message(bool display_failure, const char *error_msg)
bool compass_checks(bool display_failure) override
bool gps_checks(bool display_failure) override