AP_Arming.h 4.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_Param/AP_Param.h>
  4. #include <AP_InertialSensor/AP_InertialSensor.h>
  5. #include <RC_Channel/RC_Channel.h>
  6. class AP_Arming {
  7. public:
  8. AP_Arming();
  9. /* Do not allow copies */
  10. AP_Arming(const AP_Arming &other) = delete;
  11. AP_Arming &operator=(const AP_Arming&) = delete;
  12. static AP_Arming *get_singleton();
  13. enum ArmingChecks {
  14. ARMING_CHECK_NONE = 0x0000,
  15. ARMING_CHECK_ALL = (1U << 0),
  16. ARMING_CHECK_BARO = (1U << 1),
  17. ARMING_CHECK_COMPASS = (1U << 2),
  18. ARMING_CHECK_GPS = (1U << 3),
  19. ARMING_CHECK_INS = (1U << 4),
  20. ARMING_CHECK_PARAMETERS = (1U << 5),
  21. ARMING_CHECK_RC = (1U << 6),
  22. ARMING_CHECK_VOLTAGE = (1U << 7),
  23. ARMING_CHECK_BATTERY = (1U << 8),
  24. ARMING_CHECK_AIRSPEED = (1U << 9),
  25. ARMING_CHECK_LOGGING = (1U << 10),
  26. ARMING_CHECK_SWITCH = (1U << 11),
  27. ARMING_CHECK_GPS_CONFIG = (1U << 12),
  28. ARMING_CHECK_SYSTEM = (1U << 13),
  29. ARMING_CHECK_MISSION = (1U << 14),
  30. ARMING_CHECK_RANGEFINDER = (1U << 15),
  31. };
  32. enum class Method {
  33. RUDDER,
  34. MAVLINK,
  35. AUXSWITCH,
  36. MOTORTEST,
  37. SCRIPTING,
  38. };
  39. enum class Required {
  40. NO = 0,
  41. YES_MIN_PWM = 1,
  42. YES_ZERO_PWM = 2
  43. };
  44. void init(void);
  45. // these functions should not be used by Copter which holds the armed state in the motors library
  46. Required arming_required();
  47. virtual bool arm(AP_Arming::Method method, bool do_arming_checks=true);
  48. virtual bool disarm();
  49. bool is_armed();
  50. // get bitmask of enabled checks
  51. uint16_t get_enabled_checks();
  52. // pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass
  53. virtual bool pre_arm_checks(bool report);
  54. // some arming checks have side-effects, or require some form of state
  55. // change to have occurred, and thus should not be done as pre-arm
  56. // checks. Those go here:
  57. virtual bool arm_checks(AP_Arming::Method method);
  58. // get expected magnetic field strength
  59. uint16_t compass_magfield_expected() const;
  60. // rudder arming support
  61. enum class RudderArming {
  62. IS_DISABLED = 0, // DISABLED leaks in from vehicle defines.h
  63. ARMONLY = 1,
  64. ARMDISARM = 2
  65. };
  66. RudderArming get_rudder_arming_type() const { return (RudderArming)_rudder_arming.get(); }
  67. static const struct AP_Param::GroupInfo var_info[];
  68. protected:
  69. // Parameters
  70. AP_Int8 require;
  71. AP_Int32 checks_to_perform; // bitmask for which checks are required
  72. AP_Float accel_error_threshold;
  73. AP_Int8 _rudder_arming;
  74. AP_Int32 _required_mission_items;
  75. // internal members
  76. bool armed;
  77. uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
  78. uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];
  79. virtual bool barometer_checks(bool report);
  80. bool airspeed_checks(bool report);
  81. bool logging_checks(bool report);
  82. virtual bool ins_checks(bool report);
  83. virtual bool compass_checks(bool report);
  84. virtual bool gps_checks(bool report);
  85. bool battery_checks(bool report);
  86. bool hardware_safety_check(bool report);
  87. virtual bool board_voltage_checks(bool report);
  88. virtual bool rc_calibration_checks(bool report);
  89. bool manual_transmitter_checks(bool report);
  90. bool mission_checks(bool report);
  91. bool rangefinder_checks(bool report);
  92. bool fence_checks(bool report);
  93. virtual bool system_checks(bool report);
  94. bool can_checks(bool report);
  95. virtual bool proximity_checks(bool report) const;
  96. bool servo_checks(bool report) const;
  97. bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4]) const;
  98. // returns true if a particular check is enabled
  99. bool check_enabled(const enum AP_Arming::ArmingChecks check) const;
  100. // returns a mavlink severity which should be used if a specific check fails
  101. MAV_SEVERITY check_severity(const enum AP_Arming::ArmingChecks check) const;
  102. // handle the case where a check fails
  103. void check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const FMT_PRINTF(4, 5);
  104. void Log_Write_Arm_Disarm();
  105. private:
  106. static AP_Arming *_singleton;
  107. bool ins_accels_consistent(const AP_InertialSensor &ins);
  108. bool ins_gyros_consistent(const AP_InertialSensor &ins);
  109. enum MIS_ITEM_CHECK {
  110. MIS_ITEM_CHECK_LAND = (1 << 0),
  111. MIS_ITEM_CHECK_VTOL_LAND = (1 << 1),
  112. MIS_ITEM_CHECK_DO_LAND_START = (1 << 2),
  113. MIS_ITEM_CHECK_TAKEOFF = (1 << 3),
  114. MIS_ITEM_CHECK_VTOL_TAKEOFF = (1 << 4),
  115. MIS_ITEM_CHECK_RALLY = (1 << 5),
  116. MIS_ITEM_CHECK_MAX
  117. };
  118. };
  119. namespace AP {
  120. AP_Arming &arming();
  121. };