3 #include <AP_Arming/AP_Arming.h>
5 #ifndef AP_PLANE_BLACKBOX_LOGGING
6 #define AP_PLANE_BLACKBOX_LOGGING 0
10 a plane specific arming class
12 class AP_Arming_Plane
: public AP_Arming
18 AP_Param::setup_object_defaults(this, var_info
);
21 /* Do not allow copies */
22 CLASS_NO_COPY(AP_Arming_Plane
);
24 bool pre_arm_checks(bool report
) override
;
25 bool arm_checks(AP_Arming::Method method
) override
;
27 // var_info for holding Parameter information
28 static const struct AP_Param::GroupInfo var_info
[];
30 bool disarm(AP_Arming::Method method
, bool do_disarm_checks
=true) override
;
31 bool arm(AP_Arming::Method method
, bool do_arming_checks
=true) override
;
33 void update_soft_armed();
34 bool get_delay_arming() const { return delay_arming
; };
36 // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced
37 bool mandatory_checks(bool display_failure
) override
;
40 bool ins_checks(bool report
) override
;
41 bool terrain_database_required() const override
;
43 bool quadplane_checks(bool display_failure
);
44 bool mission_checks(bool report
) override
;
46 // Checks rc has been received if it is configured to be used
47 bool rc_received_if_enabled_check(bool display_failure
);
50 void change_arm_state(void);
52 // oneshot with duration AP_ARMING_DELAY_MS used by quadplane to delay spoolup after arming:
53 // ignored unless OPTION_DELAY_ARMING or OPTION_TILT_DISARMED is set
56 #if AP_PLANE_BLACKBOX_LOGGING
57 AP_Float blackbox_speed
;
58 uint32_t last_over_3dspeed_ms
;