AP_Arming.cpp 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include "AP_Arming.h"
  14. #include <AP_HAL/AP_HAL.h>
  15. #include <AP_BoardConfig/AP_BoardConfig.h>
  16. #include <AP_BattMonitor/AP_BattMonitor.h>
  17. #include <AP_Notify/AP_Notify.h>
  18. #include <GCS_MAVLink/GCS.h>
  19. #include <GCS_MAVLink/GCS_MAVLink.h>
  20. #include <AP_Mission/AP_Mission.h>
  21. #include <AP_Proximity/AP_Proximity.h>
  22. #include <AP_Rally/AP_Rally.h>
  23. #include <SRV_Channel/SRV_Channel.h>
  24. #include <AC_Fence/AC_Fence.h>
  25. #include <AP_InternalError/AP_InternalError.h>
  26. #include <AP_GPS/AP_GPS.h>
  27. #include <AP_Airspeed/AP_Airspeed.h>
  28. #include <AP_AHRS/AP_AHRS.h>
  29. #include <AP_Baro/AP_Baro.h>
  30. #include <AP_RangeFinder/AP_RangeFinder.h>
  31. #if HAL_WITH_UAVCAN
  32. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  33. #include <AP_Common/AP_Common.h>
  34. #include <AP_Vehicle/AP_Vehicle.h>
  35. // To be replaced with macro saying if KDECAN library is included
  36. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  37. #include <AP_KDECAN/AP_KDECAN.h>
  38. #endif
  39. #endif
  40. #include <AP_Logger/AP_Logger.h>
  41. #define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 530
  42. #define AP_ARMING_COMPASS_MAGFIELD_MIN 185 // 0.35 * 530 milligauss
  43. #define AP_ARMING_COMPASS_MAGFIELD_MAX 875 // 1.65 * 530 milligauss
  44. #define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f
  45. #define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f
  46. #define AP_ARMING_AHRS_GPS_ERROR_MAX 10 // accept up to 10m difference between AHRS and GPS
  47. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  48. #define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMONLY
  49. #else
  50. #define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM
  51. #endif
  52. extern const AP_HAL::HAL& hal;
  53. const AP_Param::GroupInfo AP_Arming::var_info[] = {
  54. // @Param: REQUIRE
  55. // @DisplayName: Require Arming Motors
  56. // @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure.
  57. // @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed
  58. // @User: Advanced
  59. AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, 1,
  60. AP_PARAM_NO_SHIFT,
  61. AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),
  62. // 2 was the CHECK paramter stored in a AP_Int16
  63. // @Param: ACCTHRESH
  64. // @DisplayName: Accelerometer error threshold
  65. // @Description: Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
  66. // @Units: m/s/s
  67. // @Range: 0.25 3.0
  68. // @User: Advanced
  69. AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),
  70. // index 4 was VOLT_MIN, moved to AP_BattMonitor
  71. // index 5 was VOLT2_MIN, moved to AP_BattMonitor
  72. // @Param: RUDDER
  73. // @DisplayName: Arming with Rudder enable/disable
  74. // @Description: Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero +- deadzone (RCx_DZ)
  75. // @Values: 0:Disabled,1:ArmingOnly,2:ArmOrDisarm
  76. // @User: Advanced
  77. AP_GROUPINFO_FRAME("RUDDER", 6, AP_Arming, _rudder_arming, ARMING_RUDDER_DEFAULT, AP_PARAM_FRAME_PLANE |
  78. AP_PARAM_FRAME_ROVER |
  79. AP_PARAM_FRAME_COPTER |
  80. AP_PARAM_FRAME_TRICOPTER |
  81. AP_PARAM_FRAME_HELI),
  82. // @Param: MIS_ITEMS
  83. // @DisplayName: Required mission items
  84. // @Description: Bitmask of mission items that are required to be planned in order to arm the aircraft
  85. // @Bitmask: 0:Land,1:VTOL Land,2:DO_LAND_START,3:Takeoff,4:VTOL Takeoff,5:Rallypoint
  86. // @User: Advanced
  87. AP_GROUPINFO("MIS_ITEMS", 7, AP_Arming, _required_mission_items, 0),
  88. // @Param: CHECK
  89. // @DisplayName: Arm Checks to Peform (bitmask)
  90. // @Description: Checks prior to arming motor. This is a bitmask of checks that will be performed before allowing arming. The default is no checks, allowing arming at any time. You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72. For most users it is recommended that you set this to 1 to enable all checks.
  91. // @Values: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration,8192:System
  92. // @Values{Plane}: 0:None,1:All,2:Barometer,4:Compass,8:GPS Lock,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Channels,128:Board voltage,256:Battery Level,512:Airspeed,1024:LoggingAvailable,2048:Hardware safety switch,4096:GPS configuration,8192:System
  93. // @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder
  94. // @Bitmask{Plane}: 0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System,14:Mission,15:Rangefinder
  95. // @User: Standard
  96. AP_GROUPINFO("CHECK", 8, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
  97. AP_GROUPEND
  98. };
  99. #if HAL_WITH_IO_MCU
  100. #include <AP_IOMCU/AP_IOMCU.h>
  101. extern AP_IOMCU iomcu;
  102. #endif
  103. AP_Arming::AP_Arming()
  104. {
  105. if (_singleton) {
  106. AP_HAL::panic("Too many AP_Arming instances");
  107. }
  108. _singleton = this;
  109. AP_Param::setup_object_defaults(this, var_info);
  110. }
  111. uint16_t AP_Arming::compass_magfield_expected() const
  112. {
  113. return AP_ARMING_COMPASS_MAGFIELD_EXPECTED;
  114. }
  115. bool AP_Arming::is_armed()
  116. {
  117. return (Required)require.get() == Required::NO || armed;
  118. }
  119. uint16_t AP_Arming::get_enabled_checks()
  120. {
  121. return checks_to_perform;
  122. }
  123. bool AP_Arming::check_enabled(const enum AP_Arming::ArmingChecks check) const
  124. {
  125. if (checks_to_perform & ARMING_CHECK_ALL) {
  126. return true;
  127. }
  128. return (checks_to_perform & check);
  129. }
  130. MAV_SEVERITY AP_Arming::check_severity(const enum AP_Arming::ArmingChecks check) const
  131. {
  132. // A check value of ARMING_CHECK_NONE means that the check is always run
  133. if (check_enabled(check) || check == ARMING_CHECK_NONE) {
  134. return MAV_SEVERITY_CRITICAL;
  135. }
  136. return MAV_SEVERITY_DEBUG; // technically should be NOTICE, but will annoy users at that level
  137. }
  138. void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const
  139. {
  140. if (!report) {
  141. return;
  142. }
  143. char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
  144. hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt);
  145. MAV_SEVERITY severity = check_severity(check);
  146. va_list arg_list;
  147. va_start(arg_list, fmt);
  148. gcs().send_textv(severity, taggedfmt, arg_list);
  149. va_end(arg_list);
  150. }
  151. bool AP_Arming::barometer_checks(bool report)
  152. {
  153. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  154. (checks_to_perform & ARMING_CHECK_BARO)) {
  155. if (!AP::baro().all_healthy()) {
  156. check_failed(ARMING_CHECK_BARO, report, "Barometer not healthy");
  157. return false;
  158. }
  159. }
  160. return true;
  161. }
  162. bool AP_Arming::airspeed_checks(bool report)
  163. {
  164. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  165. (checks_to_perform & ARMING_CHECK_AIRSPEED)) {
  166. const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  167. if (airspeed == nullptr) {
  168. // not an airspeed capable vehicle
  169. return true;
  170. }
  171. for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
  172. if (airspeed->enabled(i) && airspeed->use(i) && !airspeed->healthy(i)) {
  173. check_failed(ARMING_CHECK_AIRSPEED, report, "Airspeed %d not healthy", i + 1);
  174. return false;
  175. }
  176. }
  177. }
  178. return true;
  179. }
  180. bool AP_Arming::logging_checks(bool report)
  181. {
  182. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  183. (checks_to_perform & ARMING_CHECK_LOGGING)) {
  184. if (!AP::logger().logging_present()) {
  185. // Logging is disabled, so nothing to check.
  186. return true;
  187. }
  188. if (AP::logger().logging_failed()) {
  189. check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");
  190. return false;
  191. }
  192. if (!AP::logger().CardInserted()) {
  193. check_failed(ARMING_CHECK_LOGGING, report, "No SD card");
  194. return false;
  195. }
  196. }
  197. return true;
  198. }
  199. bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins)
  200. {
  201. const uint8_t accel_count = ins.get_accel_count();
  202. if (accel_count <= 1) {
  203. return true;
  204. }
  205. const Vector3f &prime_accel_vec = ins.get_accel();
  206. const uint32_t now = AP_HAL::millis();
  207. for(uint8_t i=0; i<accel_count; i++) {
  208. if (!ins.use_accel(i)) {
  209. continue;
  210. }
  211. // get next accel vector
  212. const Vector3f &accel_vec = ins.get_accel(i);
  213. Vector3f vec_diff = accel_vec - prime_accel_vec;
  214. // allow for user-defined difference, typically 0.75 m/s/s. Has to pass in last 10 seconds
  215. float threshold = accel_error_threshold;
  216. if (i >= 2) {
  217. /*
  218. we allow for a higher threshold for IMU3 as it
  219. runs at a different temperature to IMU1/IMU2,
  220. and is not used for accel data in the EKF
  221. */
  222. threshold *= 3;
  223. }
  224. // EKF is less sensitive to Z-axis error
  225. vec_diff.z *= 0.5f;
  226. if (vec_diff.length() <= threshold) {
  227. last_accel_pass_ms[i] = now;
  228. }
  229. if (now - last_accel_pass_ms[i] > 10000) {
  230. return false;
  231. }
  232. }
  233. return true;
  234. }
  235. bool AP_Arming::ins_gyros_consistent(const AP_InertialSensor &ins)
  236. {
  237. const uint8_t gyro_count = ins.get_gyro_count();
  238. if (gyro_count <= 1) {
  239. return true;
  240. }
  241. const Vector3f &prime_gyro_vec = ins.get_gyro();
  242. const uint32_t now = AP_HAL::millis();
  243. for(uint8_t i=0; i<gyro_count; i++) {
  244. if (!ins.use_gyro(i)) {
  245. continue;
  246. }
  247. // get next gyro vector
  248. const Vector3f &gyro_vec = ins.get_gyro(i);
  249. const Vector3f vec_diff = gyro_vec - prime_gyro_vec;
  250. // allow for up to 5 degrees/s difference. Pass if it has
  251. // been OK in last 10 seconds
  252. if (vec_diff.length() <= radians(5)) {
  253. last_gyro_pass_ms[i] = now;
  254. }
  255. if (now - last_gyro_pass_ms[i] > 10000) {
  256. return false;
  257. }
  258. }
  259. return true;
  260. }
  261. bool AP_Arming::ins_checks(bool report)
  262. {
  263. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  264. (checks_to_perform & ARMING_CHECK_INS)) {
  265. const AP_InertialSensor &ins = AP::ins();
  266. if (!ins.get_gyro_health_all()) {
  267. check_failed(ARMING_CHECK_INS, report, "Gyros not healthy");
  268. return false;
  269. }
  270. if (!ins.gyro_calibrated_ok_all()) {
  271. check_failed(ARMING_CHECK_INS, report, "Gyros not calibrated");
  272. return false;
  273. }
  274. if (!ins.get_accel_health_all()) {
  275. check_failed(ARMING_CHECK_INS, report, "Accels not healthy");
  276. return false;
  277. }
  278. if (!ins.accel_calibrated_ok_all()) {
  279. check_failed(ARMING_CHECK_INS, report, "3D Accel calibration needed");
  280. return false;
  281. }
  282. //check if accelerometers have calibrated and require reboot
  283. if (ins.accel_cal_requires_reboot()) {
  284. check_failed(ARMING_CHECK_INS, report, "Accels calibrated requires reboot");
  285. return false;
  286. }
  287. // check all accelerometers point in roughly same direction
  288. if (!ins_accels_consistent(ins)) {
  289. check_failed(ARMING_CHECK_INS, report, "Accels inconsistent");
  290. return false;
  291. }
  292. // check all gyros are giving consistent readings
  293. if (!ins_gyros_consistent(ins)) {
  294. check_failed(ARMING_CHECK_INS, report, "Gyros inconsistent");
  295. return false;
  296. }
  297. // check AHRS attitudes are consistent
  298. char failure_msg[50] = {};
  299. if (!AP::ahrs().attitudes_consistent(failure_msg, ARRAY_SIZE(failure_msg))) {
  300. check_failed(ARMING_CHECK_INS, report, "%s", failure_msg);
  301. return false;
  302. }
  303. }
  304. return true;
  305. }
  306. bool AP_Arming::compass_checks(bool report)
  307. {
  308. Compass &_compass = AP::compass();
  309. // check if compass is calibrating
  310. if (_compass.is_calibrating()) {
  311. check_failed(ARMING_CHECK_NONE, report, "Compass calibration running");
  312. return false;
  313. }
  314. // check if compass has calibrated and requires reboot
  315. if (_compass.compass_cal_requires_reboot()) {
  316. check_failed(ARMING_CHECK_NONE, report, "Compass calibrated requires reboot");
  317. return false;
  318. }
  319. if ((checks_to_perform) & ARMING_CHECK_ALL ||
  320. (checks_to_perform) & ARMING_CHECK_COMPASS) {
  321. // avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
  322. // incorrectly skip the remaining checks, pass the primary instance directly
  323. if (!_compass.use_for_yaw(_compass.get_primary())) {
  324. // compass use is disabled
  325. return true;
  326. }
  327. if (!_compass.healthy()) {
  328. check_failed(ARMING_CHECK_COMPASS, report, "Compass not healthy");
  329. return false;
  330. }
  331. // check compass learning is on or offsets have been set
  332. if (!_compass.learn_offsets_enabled() && !_compass.configured()) {
  333. check_failed(ARMING_CHECK_COMPASS, report, "Compass not calibrated");
  334. return false;
  335. }
  336. // check for unreasonable compass offsets
  337. const Vector3f offsets = _compass.get_offsets();
  338. if (offsets.length() > _compass.get_offsets_max()) {
  339. check_failed(ARMING_CHECK_COMPASS, report, "Compass offsets too high");
  340. return false;
  341. }
  342. // check for unreasonable mag field length
  343. const float mag_field = _compass.get_field().length();
  344. if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {
  345. check_failed(ARMING_CHECK_COMPASS, report, "Check mag field");
  346. return false;
  347. }
  348. // check all compasses point in roughly same direction
  349. if (!_compass.consistent()) {
  350. check_failed(ARMING_CHECK_COMPASS, report, "Compasses inconsistent");
  351. return false;
  352. }
  353. }
  354. return true;
  355. }
  356. bool AP_Arming::gps_checks(bool report)
  357. {
  358. const AP_GPS &gps = AP::gps();
  359. if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {
  360. //GPS OK?
  361. if (!AP::ahrs().home_is_set() ||
  362. gps.status() < AP_GPS::GPS_OK_FIX_3D) {
  363. check_failed(ARMING_CHECK_GPS, report, "Bad GPS Position");
  364. return false;
  365. }
  366. //GPS update rate acceptable
  367. if (!gps.is_healthy()) {
  368. check_failed(ARMING_CHECK_GPS, report, "GPS is not healthy");
  369. return false;
  370. }
  371. // check GPSs are within 50m of each other and that blending is healthy
  372. float distance_m;
  373. if (!gps.all_consistent(distance_m)) {
  374. check_failed(ARMING_CHECK_GPS, report, "GPS positions differ by %4.1fm",
  375. (double)distance_m);
  376. return false;
  377. }
  378. if (!gps.blend_health_check()) {
  379. check_failed(ARMING_CHECK_GPS, report, "GPS blending unhealthy");
  380. return false;
  381. }
  382. // check AHRS and GPS are within 10m of each other
  383. const Location gps_loc = gps.location();
  384. Location ahrs_loc;
  385. if (AP::ahrs().get_position(ahrs_loc)) {
  386. const float distance = gps_loc.get_distance(ahrs_loc);
  387. if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {
  388. check_failed(ARMING_CHECK_GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance);
  389. return false;
  390. }
  391. }
  392. }
  393. if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
  394. uint8_t first_unconfigured;
  395. if (gps.first_unconfigured_gps(first_unconfigured)) {
  396. check_failed(ARMING_CHECK_GPS_CONFIG,
  397. report,
  398. "GPS %d failing configuration checks",
  399. first_unconfigured + 1);
  400. if (report) {
  401. gps.broadcast_first_configuration_failure_reason();
  402. }
  403. return false;
  404. }
  405. }
  406. return true;
  407. }
  408. bool AP_Arming::battery_checks(bool report)
  409. {
  410. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  411. (checks_to_perform & ARMING_CHECK_BATTERY)) {
  412. char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
  413. if (!AP::battery().arming_checks(sizeof(buffer), buffer)) {
  414. check_failed(ARMING_CHECK_BATTERY, report, "%s", buffer);
  415. return false;
  416. }
  417. }
  418. return true;
  419. }
  420. bool AP_Arming::hardware_safety_check(bool report)
  421. {
  422. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  423. (checks_to_perform & ARMING_CHECK_SWITCH)) {
  424. // check if safety switch has been pushed
  425. if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
  426. check_failed(ARMING_CHECK_SWITCH, report, "Hardware safety switch");
  427. return false;
  428. }
  429. }
  430. return true;
  431. }
  432. bool AP_Arming::rc_calibration_checks(bool report)
  433. {
  434. bool check_passed = true;
  435. const uint8_t num_channels = RC_Channels::get_valid_channel_count();
  436. for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
  437. const RC_Channel *c = rc().channel(i);
  438. if (c == nullptr) {
  439. continue;
  440. }
  441. if (i >= num_channels && !(c->has_override())) {
  442. continue;
  443. }
  444. const uint16_t trim = c->get_radio_trim();
  445. if (c->get_radio_min() > trim) {
  446. check_failed(ARMING_CHECK_RC, report, "RC%d minimum is greater than trim", i + 1);
  447. check_passed = false;
  448. }
  449. if (c->get_radio_max() < trim) {
  450. check_failed(ARMING_CHECK_RC, report, "RC%d maximum is less than trim", i + 1);
  451. check_passed = false;
  452. }
  453. }
  454. return check_passed;
  455. }
  456. bool AP_Arming::manual_transmitter_checks(bool report)
  457. {
  458. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  459. (checks_to_perform & ARMING_CHECK_RC)) {
  460. if (AP_Notify::flags.failsafe_radio) {
  461. check_failed(ARMING_CHECK_RC, report, "Radio failsafe on");
  462. return false;
  463. }
  464. if (!rc_calibration_checks(report)) {
  465. return false;
  466. }
  467. }
  468. return true;
  469. }
  470. bool AP_Arming::mission_checks(bool report)
  471. {
  472. if (((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_MISSION)) &&
  473. _required_mission_items) {
  474. AP_Mission *mission = AP::mission();
  475. if (mission == nullptr) {
  476. check_failed(ARMING_CHECK_MISSION, report, "No mission library present");
  477. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  478. AP_HAL::panic("Mission checks requested, but no mission was allocated");
  479. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
  480. return false;
  481. }
  482. AP_Rally *rally = AP::rally();
  483. if (rally == nullptr) {
  484. check_failed(ARMING_CHECK_MISSION, report, "No rally library present");
  485. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  486. AP_HAL::panic("Mission checks requested, but no rally was allocated");
  487. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL
  488. return false;
  489. }
  490. const struct MisItemTable {
  491. MIS_ITEM_CHECK check;
  492. MAV_CMD mis_item_type;
  493. const char *type;
  494. } misChecks[5] = {
  495. {MIS_ITEM_CHECK_LAND, MAV_CMD_NAV_LAND, "land"},
  496. {MIS_ITEM_CHECK_VTOL_LAND, MAV_CMD_NAV_VTOL_LAND, "vtol land"},
  497. {MIS_ITEM_CHECK_DO_LAND_START, MAV_CMD_DO_LAND_START, "do land start"},
  498. {MIS_ITEM_CHECK_TAKEOFF, MAV_CMD_NAV_TAKEOFF, "takeoff"},
  499. {MIS_ITEM_CHECK_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_TAKEOFF, "vtol takeoff"},
  500. };
  501. for (uint8_t i = 0; i < ARRAY_SIZE(misChecks); i++) {
  502. if (_required_mission_items & misChecks[i].check) {
  503. if (!mission->contains_item(misChecks[i].mis_item_type)) {
  504. check_failed(ARMING_CHECK_MISSION, report, "Missing mission item: %s", misChecks[i].type);
  505. return false;
  506. }
  507. }
  508. }
  509. if (_required_mission_items & MIS_ITEM_CHECK_RALLY) {
  510. Location ahrs_loc;
  511. if (!AP::ahrs().get_position(ahrs_loc)) {
  512. check_failed(ARMING_CHECK_MISSION, report, "Can't check rally without position");
  513. return false;
  514. }
  515. RallyLocation rally_loc = {};
  516. if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) {
  517. check_failed(ARMING_CHECK_MISSION, report, "No sufficently close rally point located");
  518. return false;
  519. }
  520. }
  521. }
  522. return true;
  523. }
  524. bool AP_Arming::rangefinder_checks(bool report)
  525. {
  526. if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RANGEFINDER)) {
  527. RangeFinder *range = RangeFinder::get_singleton();
  528. if (range == nullptr) {
  529. return true;
  530. }
  531. char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
  532. if (!range->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {
  533. check_failed(ARMING_CHECK_RANGEFINDER, report, "%s", buffer);
  534. return false;
  535. }
  536. }
  537. return true;
  538. }
  539. bool AP_Arming::servo_checks(bool report) const
  540. {
  541. bool check_passed = true;
  542. for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
  543. const SRV_Channel *c = SRV_Channels::srv_channel(i);
  544. if (c == nullptr || c->get_function() == SRV_Channel::k_none) {
  545. continue;
  546. }
  547. const uint16_t trim = c->get_trim();
  548. if (c->get_output_min() > trim) {
  549. check_failed(ARMING_CHECK_NONE, report, "SERVO%d minimum is greater than trim", i + 1);
  550. check_passed = false;
  551. }
  552. if (c->get_output_max() < trim) {
  553. check_failed(ARMING_CHECK_NONE, report, "SERVO%d maximum is less than trim", i + 1);
  554. check_passed = false;
  555. }
  556. }
  557. #if HAL_WITH_IO_MCU
  558. if (!iomcu.healthy()) {
  559. check_failed(ARMING_CHECK_NONE, report, "IOMCU is unhealthy");
  560. check_passed = false;
  561. }
  562. #endif
  563. return check_passed;
  564. }
  565. bool AP_Arming::board_voltage_checks(bool report)
  566. {
  567. // check board voltage
  568. if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_VOLTAGE)) {
  569. #if HAL_HAVE_BOARD_VOLTAGE
  570. const float bus_voltage = hal.analogin->board_voltage();
  571. const float vbus_min = AP_BoardConfig::get_minimum_board_voltage();
  572. if(((bus_voltage < vbus_min) || (bus_voltage > AP_ARMING_BOARD_VOLTAGE_MAX))) {
  573. check_failed(ARMING_CHECK_VOLTAGE, report, "Board (%1.1fv) out of range %1.1f-%1.1fv", (double)bus_voltage, (double)vbus_min, (double)AP_ARMING_BOARD_VOLTAGE_MAX);
  574. return false;
  575. }
  576. #endif // HAL_HAVE_BOARD_VOLTAGE
  577. #if HAL_HAVE_SERVO_VOLTAGE
  578. const float vservo_min = AP_BoardConfig::get_minimum_servo_voltage();
  579. if (is_positive(vservo_min)) {
  580. const float servo_voltage = hal.analogin->servorail_voltage();
  581. if (servo_voltage < vservo_min) {
  582. check_failed(ARMING_CHECK_VOLTAGE, report, "Servo voltage to low (%1.2fv < %1.2fv)", (double)servo_voltage, (double)vservo_min);
  583. return false;
  584. }
  585. }
  586. #endif // HAL_HAVE_SERVO_VOLTAGE
  587. }
  588. return true;
  589. }
  590. /*
  591. check base system operations
  592. */
  593. bool AP_Arming::system_checks(bool report)
  594. {
  595. if (check_enabled(ARMING_CHECK_SYSTEM)) {
  596. if (!hal.storage->healthy()) {
  597. check_failed(ARMING_CHECK_SYSTEM, report, "Param storage failed");
  598. return false;
  599. }
  600. }
  601. if (AP::internalerror().errors() != 0) {
  602. check_failed(ARMING_CHECK_NONE, report, "Internal errors (0x%x)", (unsigned int)AP::internalerror().errors());
  603. return false;
  604. }
  605. return true;
  606. }
  607. // check nothing is too close to vehicle
  608. bool AP_Arming::proximity_checks(bool report) const
  609. {
  610. const AP_Proximity *proximity = AP::proximity();
  611. // return true immediately if no sensor present
  612. if (proximity == nullptr) {
  613. return true;
  614. }
  615. if (proximity->get_status() == AP_Proximity::Proximity_NotConnected) {
  616. return true;
  617. }
  618. // return false if proximity sensor unhealthy
  619. if (proximity->get_status() < AP_Proximity::Proximity_Good) {
  620. check_failed(ARMING_CHECK_NONE, report, "check proximity sensor");
  621. return false;
  622. }
  623. return true;
  624. }
  625. bool AP_Arming::can_checks(bool report)
  626. {
  627. #if HAL_WITH_UAVCAN
  628. if (check_enabled(ARMING_CHECK_SYSTEM)) {
  629. const char *fail_msg = nullptr;
  630. uint8_t num_drivers = AP::can().get_num_drivers();
  631. for (uint8_t i = 0; i < num_drivers; i++) {
  632. switch (AP::can().get_protocol_type(i)) {
  633. case AP_BoardConfig_CAN::Protocol_Type_KDECAN: {
  634. // To be replaced with macro saying if KDECAN library is included
  635. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  636. AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
  637. if (ap_kdecan != nullptr && !ap_kdecan->pre_arm_check(fail_msg)) {
  638. if (fail_msg == nullptr) {
  639. check_failed(ARMING_CHECK_SYSTEM, report, "KDECAN failed");
  640. } else {
  641. check_failed(ARMING_CHECK_SYSTEM, report, "%s", fail_msg);
  642. }
  643. return false;
  644. }
  645. break;
  646. #else
  647. UNUSED_RESULT(fail_msg); // prevent unused variable error
  648. #endif
  649. }
  650. case AP_BoardConfig_CAN::Protocol_Type_UAVCAN:
  651. case AP_BoardConfig_CAN::Protocol_Type_None:
  652. default:
  653. break;
  654. }
  655. }
  656. }
  657. #endif
  658. return true;
  659. }
  660. bool AP_Arming::fence_checks(bool display_failure)
  661. {
  662. const AC_Fence *fence = AP::fence();
  663. if (fence == nullptr) {
  664. return true;
  665. }
  666. // check fence is ready
  667. const char *fail_msg = nullptr;
  668. if (fence->pre_arm_check(fail_msg)) {
  669. return true;
  670. }
  671. if (fail_msg == nullptr) {
  672. check_failed(ARMING_CHECK_NONE, display_failure, "Check fence");
  673. } else {
  674. check_failed(ARMING_CHECK_NONE, display_failure, "%s", fail_msg);
  675. }
  676. return false;
  677. }
  678. bool AP_Arming::pre_arm_checks(bool report)
  679. {
  680. #if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
  681. if (armed || require == (uint8_t)Required::NO) {
  682. // if we are already armed or don't need any arming checks
  683. // then skip the checks
  684. return true;
  685. }
  686. #endif
  687. return hardware_safety_check(report)
  688. & barometer_checks(report)
  689. & ins_checks(report)
  690. & compass_checks(report)
  691. & gps_checks(report)
  692. & battery_checks(report)
  693. & logging_checks(report)
  694. & manual_transmitter_checks(report)
  695. & mission_checks(report)
  696. & rangefinder_checks(report)
  697. & servo_checks(report)
  698. & board_voltage_checks(report)
  699. & system_checks(report)
  700. & can_checks(report)
  701. & proximity_checks(report);
  702. }
  703. bool AP_Arming::arm_checks(AP_Arming::Method method)
  704. {
  705. // ensure the GPS drivers are ready on any final changes
  706. if ((checks_to_perform & ARMING_CHECK_ALL) ||
  707. (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
  708. if (!AP::gps().prepare_for_arming()) {
  709. return false;
  710. }
  711. }
  712. // note that this will prepare AP_Logger to start logging
  713. // so should be the last check to be done before arming
  714. // Note also that we need to PrepForArming() regardless of whether
  715. // the arming check flag is set - disabling the arming check
  716. // should not stop logging from working.
  717. AP_Logger *logger = AP_Logger::get_singleton();
  718. if (logger->logging_present()) {
  719. // If we're configured to log, prep it
  720. logger->PrepForArming();
  721. if (!logger->logging_started() &&
  722. ((checks_to_perform & ARMING_CHECK_ALL) ||
  723. (checks_to_perform & ARMING_CHECK_LOGGING))) {
  724. check_failed(ARMING_CHECK_LOGGING, true, "Logging not started");
  725. return false;
  726. }
  727. }
  728. return true;
  729. }
  730. //returns true if arming occurred successfully
  731. bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
  732. {
  733. if (armed) { //already armed
  734. return false;
  735. }
  736. if (!do_arming_checks || (pre_arm_checks(true) && arm_checks(method))) {
  737. armed = true;
  738. //TODO: Log motor arming
  739. //Can't do this from this class until there is a unified logging library
  740. } else {
  741. AP::logger().arming_failure();
  742. armed = false;
  743. }
  744. return armed;
  745. }
  746. //returns true if disarming occurred successfully
  747. bool AP_Arming::disarm()
  748. {
  749. if (!armed) { // already disarmed
  750. return false;
  751. }
  752. armed = false;
  753. #if HAL_HAVE_SAFETY_SWITCH
  754. AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();
  755. if ((board_cfg != nullptr) &&
  756. (board_cfg->get_safety_button_options() & AP_BoardConfig::BOARD_SAFETY_OPTION_SAFETY_ON_DISARM)) {
  757. hal.rcout->force_safety_on();
  758. }
  759. #endif // HAL_HAVE_SAFETY_SWITCH
  760. //TODO: Log motor disarming to the logger
  761. //Can't do this from this class until there is a unified logging library.
  762. return true;
  763. }
  764. AP_Arming::Required AP_Arming::arming_required()
  765. {
  766. return (AP_Arming::Required)require.get();
  767. }
  768. // Copter and sub share the same RC input limits
  769. // Copter checks that min and max have been configured by default, Sub does not
  770. bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const
  771. {
  772. // set rc-checks to success if RC checks are disabled
  773. if ((checks_to_perform != ARMING_CHECK_ALL) && !(checks_to_perform & ARMING_CHECK_RC)) {
  774. return true;
  775. }
  776. bool ret = true;
  777. const char *channel_names[] = { "Roll", "Pitch", "Throttle", "Yaw" };
  778. for (uint8_t i=0; i<ARRAY_SIZE(channel_names);i++) {
  779. const RC_Channel *channel = channels[i];
  780. const char *channel_name = channel_names[i];
  781. // check if radio has been calibrated
  782. if (channel->get_radio_min() > 1300) {
  783. check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
  784. ret = false;
  785. }
  786. if (channel->get_radio_max() < 1700) {
  787. check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);
  788. ret = false;
  789. }
  790. bool fail = true;
  791. if (i == 2) {
  792. // skip checking trim for throttle as older code did not check it
  793. fail = false;
  794. }
  795. if (channel->get_radio_trim() < channel->get_radio_min()) {
  796. check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim below min", channel_name);
  797. if (fail) {
  798. ret = false;
  799. }
  800. }
  801. if (channel->get_radio_trim() > channel->get_radio_max()) {
  802. check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim above max", channel_name);
  803. if (fail) {
  804. ret = false;
  805. }
  806. }
  807. }
  808. return ret;
  809. }
  810. void AP_Arming::Log_Write_Arm_Disarm()
  811. {
  812. struct log_Arm_Disarm pkt = {
  813. LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
  814. time_us : AP_HAL::micros64(),
  815. arm_state : is_armed(),
  816. arm_checks : get_enabled_checks()
  817. };
  818. AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
  819. }
  820. AP_Arming *AP_Arming::_singleton = nullptr;
  821. /*
  822. * Get the AP_InertialSensor singleton
  823. */
  824. AP_Arming *AP_Arming::get_singleton()
  825. {
  826. return AP_Arming::_singleton;
  827. }
  828. namespace AP {
  829. AP_Arming &arming()
  830. {
  831. return *AP_Arming::get_singleton();
  832. }
  833. };