Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduCopter/AP_Arming.h
Views: 1798
#pragma once12#include <AP_Arming/AP_Arming.h>34class AP_Arming_Copter : public AP_Arming5{6public:7friend class Copter;8friend class ToyMode;910AP_Arming_Copter() : AP_Arming()11{12// default REQUIRE parameter to 1 (Copter does not have an13// actual ARMING_REQUIRE parameter)14require.set_default((uint8_t)Required::YES_MIN_PWM);15}1617/* Do not allow copies */18CLASS_NO_COPY(AP_Arming_Copter);1920bool rc_calibration_checks(bool display_failure) override;2122bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override;23bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;2425protected:2627bool pre_arm_checks(bool display_failure) override;28bool pre_arm_ekf_attitude_check();29#if HAL_PROXIMITY_ENABLED30bool proximity_checks(bool display_failure) const override;31#endif32bool arm_checks(AP_Arming::Method method) override;3334// mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced35bool mandatory_checks(bool display_failure) override;3637// NOTE! the following check functions *DO* call into AP_Arming:38bool ins_checks(bool display_failure) override;39bool gps_checks(bool display_failure) override;40bool barometer_checks(bool display_failure) override;41bool board_voltage_checks(bool display_failure) override;4243// NOTE! the following check functions *DO NOT* call into AP_Arming!44bool parameter_checks(bool display_failure);45bool oa_checks(bool display_failure);46bool mandatory_gps_checks(bool display_failure);47bool gcs_failsafe_check(bool display_failure);48bool winch_checks(bool display_failure) const;49bool alt_checks(bool display_failure);50bool rc_throttle_failsafe_checks(bool display_failure) const;5152void set_pre_arm_check(bool b);5354// expected to return true if the terrain database is required to have55// all data loaded56bool terrain_database_required() const override;5758private:5960// actually contains the pre-arm checks. This is wrapped so that61// we can store away success/failure of the checks.62bool run_pre_arm_checks(bool display_failure);6364};656667