2017-01-09 03:56:56 -04:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Arming/AP_Arming.h>
|
|
|
|
|
2023-05-10 22:05:34 -03:00
|
|
|
#ifndef AP_PLANE_BLACKBOX_LOGGING
|
|
|
|
#define AP_PLANE_BLACKBOX_LOGGING 0
|
|
|
|
#endif
|
|
|
|
|
2017-01-09 03:56:56 -04:00
|
|
|
/*
|
|
|
|
a plane specific arming class
|
|
|
|
*/
|
|
|
|
class AP_Arming_Plane : public AP_Arming
|
|
|
|
{
|
|
|
|
public:
|
2018-06-25 02:44:04 -03:00
|
|
|
AP_Arming_Plane()
|
|
|
|
: AP_Arming()
|
2017-12-12 21:06:15 -04:00
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
|
|
|
|
2017-08-30 16:48:12 -03:00
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_Arming_Plane);
|
2017-08-30 16:48:12 -03:00
|
|
|
|
2019-04-21 22:12:12 -03:00
|
|
|
bool pre_arm_checks(bool report) override;
|
|
|
|
bool arm_checks(AP_Arming::Method method) override;
|
2017-01-09 03:56:56 -04:00
|
|
|
|
|
|
|
// var_info for holding Parameter information
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
2021-01-05 20:15:48 -04:00
|
|
|
bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override;
|
2019-05-03 20:35:12 -03:00
|
|
|
bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;
|
|
|
|
|
|
|
|
void update_soft_armed();
|
2021-02-01 12:26:22 -04:00
|
|
|
bool get_delay_arming() const { return delay_arming; };
|
2019-05-03 20:35:12 -03:00
|
|
|
|
2023-04-30 20:30:35 -03:00
|
|
|
// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced
|
|
|
|
bool mandatory_checks(bool display_failure) override;
|
|
|
|
|
2017-01-09 03:56:56 -04:00
|
|
|
protected:
|
2019-04-21 22:12:12 -03:00
|
|
|
bool ins_checks(bool report) override;
|
2022-08-03 09:59:38 -03:00
|
|
|
bool terrain_database_required() const override;
|
2017-01-09 03:56:56 -04:00
|
|
|
|
2021-11-06 13:42:40 -03:00
|
|
|
bool quadplane_checks(bool display_failure);
|
2022-03-12 02:53:58 -04:00
|
|
|
bool mission_checks(bool report) override;
|
2021-11-06 13:42:40 -03:00
|
|
|
|
2023-04-30 20:30:35 -03:00
|
|
|
// Checks rc has been received if it is configured to be used
|
|
|
|
bool rc_received_if_enabled_check(bool display_failure);
|
|
|
|
|
2019-05-03 20:35:12 -03:00
|
|
|
private:
|
|
|
|
void change_arm_state(void);
|
2020-06-16 15:52:26 -03:00
|
|
|
|
|
|
|
// oneshot with duration AP_ARMING_DELAY_MS used by quadplane to delay spoolup after arming:
|
|
|
|
// ignored unless OPTION_DELAY_ARMING or OPTION_TILT_DISARMED is set
|
|
|
|
bool delay_arming;
|
2023-05-10 22:05:34 -03:00
|
|
|
|
|
|
|
#if AP_PLANE_BLACKBOX_LOGGING
|
|
|
|
AP_Float blackbox_speed;
|
|
|
|
uint32_t last_over_3dspeed_ms;
|
|
|
|
#endif
|
2017-01-09 03:56:56 -04:00
|
|
|
};
|