123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960 |
- #include "AP_Arming.h"
- #include <AP_HAL/AP_HAL.h>
- #include <AP_BoardConfig/AP_BoardConfig.h>
- #include <AP_BattMonitor/AP_BattMonitor.h>
- #include <AP_Notify/AP_Notify.h>
- #include <GCS_MAVLink/GCS.h>
- #include <GCS_MAVLink/GCS_MAVLink.h>
- #include <AP_Mission/AP_Mission.h>
- #include <AP_Proximity/AP_Proximity.h>
- #include <AP_Rally/AP_Rally.h>
- #include <SRV_Channel/SRV_Channel.h>
- #include <AC_Fence/AC_Fence.h>
- #include <AP_InternalError/AP_InternalError.h>
- #include <AP_GPS/AP_GPS.h>
- #include <AP_Airspeed/AP_Airspeed.h>
- #include <AP_AHRS/AP_AHRS.h>
- #include <AP_Baro/AP_Baro.h>
- #include <AP_RangeFinder/AP_RangeFinder.h>
- #if HAL_WITH_UAVCAN
- #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
- #include <AP_Common/AP_Common.h>
- #include <AP_Vehicle/AP_Vehicle.h>
-
- #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
- #include <AP_KDECAN/AP_KDECAN.h>
- #endif
- #endif
- #include <AP_Logger/AP_Logger.h>
- #define AP_ARMING_COMPASS_MAGFIELD_EXPECTED 530
- #define AP_ARMING_COMPASS_MAGFIELD_MIN 185
- #define AP_ARMING_COMPASS_MAGFIELD_MAX 875
- #define AP_ARMING_BOARD_VOLTAGE_MAX 5.8f
- #define AP_ARMING_ACCEL_ERROR_THRESHOLD 0.75f
- #define AP_ARMING_AHRS_GPS_ERROR_MAX 10
- #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
- #define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMONLY
- #else
- #define ARMING_RUDDER_DEFAULT (uint8_t)RudderArming::ARMDISARM
- #endif
- extern const AP_HAL::HAL& hal;
- const AP_Param::GroupInfo AP_Arming::var_info[] = {
-
-
-
-
-
- AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, 1,
- AP_PARAM_NO_SHIFT,
- AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),
-
-
-
-
-
-
-
- AP_GROUPINFO("ACCTHRESH", 3, AP_Arming, accel_error_threshold, AP_ARMING_ACCEL_ERROR_THRESHOLD),
-
-
-
-
-
-
-
- AP_GROUPINFO_FRAME("RUDDER", 6, AP_Arming, _rudder_arming, ARMING_RUDDER_DEFAULT, AP_PARAM_FRAME_PLANE |
- AP_PARAM_FRAME_ROVER |
- AP_PARAM_FRAME_COPTER |
- AP_PARAM_FRAME_TRICOPTER |
- AP_PARAM_FRAME_HELI),
-
-
-
-
-
- AP_GROUPINFO("MIS_ITEMS", 7, AP_Arming, _required_mission_items, 0),
-
-
-
-
-
-
-
-
- AP_GROUPINFO("CHECK", 8, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
- AP_GROUPEND
- };
- #if HAL_WITH_IO_MCU
- #include <AP_IOMCU/AP_IOMCU.h>
- extern AP_IOMCU iomcu;
- #endif
- AP_Arming::AP_Arming()
- {
- if (_singleton) {
- AP_HAL::panic("Too many AP_Arming instances");
- }
- _singleton = this;
- AP_Param::setup_object_defaults(this, var_info);
- }
- uint16_t AP_Arming::compass_magfield_expected() const
- {
- return AP_ARMING_COMPASS_MAGFIELD_EXPECTED;
- }
- bool AP_Arming::is_armed()
- {
- return (Required)require.get() == Required::NO || armed;
- }
- uint16_t AP_Arming::get_enabled_checks()
- {
- return checks_to_perform;
- }
- bool AP_Arming::check_enabled(const enum AP_Arming::ArmingChecks check) const
- {
- if (checks_to_perform & ARMING_CHECK_ALL) {
- return true;
- }
- return (checks_to_perform & check);
- }
- MAV_SEVERITY AP_Arming::check_severity(const enum AP_Arming::ArmingChecks check) const
- {
-
- if (check_enabled(check) || check == ARMING_CHECK_NONE) {
- return MAV_SEVERITY_CRITICAL;
- }
- return MAV_SEVERITY_DEBUG;
- }
- void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool report, const char *fmt, ...) const
- {
- if (!report) {
- return;
- }
- char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
- hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "PreArm: %s", fmt);
- MAV_SEVERITY severity = check_severity(check);
- va_list arg_list;
- va_start(arg_list, fmt);
- gcs().send_textv(severity, taggedfmt, arg_list);
- va_end(arg_list);
- }
- bool AP_Arming::barometer_checks(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_BARO)) {
- if (!AP::baro().all_healthy()) {
- check_failed(ARMING_CHECK_BARO, report, "Barometer not healthy");
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::airspeed_checks(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_AIRSPEED)) {
- const AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
- if (airspeed == nullptr) {
-
- return true;
- }
- for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
- if (airspeed->enabled(i) && airspeed->use(i) && !airspeed->healthy(i)) {
- check_failed(ARMING_CHECK_AIRSPEED, report, "Airspeed %d not healthy", i + 1);
- return false;
- }
- }
- }
- return true;
- }
- bool AP_Arming::logging_checks(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_LOGGING)) {
- if (!AP::logger().logging_present()) {
-
- return true;
- }
- if (AP::logger().logging_failed()) {
- check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");
- return false;
- }
- if (!AP::logger().CardInserted()) {
- check_failed(ARMING_CHECK_LOGGING, report, "No SD card");
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins)
- {
- const uint8_t accel_count = ins.get_accel_count();
- if (accel_count <= 1) {
- return true;
- }
- const Vector3f &prime_accel_vec = ins.get_accel();
- const uint32_t now = AP_HAL::millis();
- for(uint8_t i=0; i<accel_count; i++) {
- if (!ins.use_accel(i)) {
- continue;
- }
-
- const Vector3f &accel_vec = ins.get_accel(i);
- Vector3f vec_diff = accel_vec - prime_accel_vec;
-
- float threshold = accel_error_threshold;
- if (i >= 2) {
-
- threshold *= 3;
- }
-
- vec_diff.z *= 0.5f;
- if (vec_diff.length() <= threshold) {
- last_accel_pass_ms[i] = now;
- }
- if (now - last_accel_pass_ms[i] > 10000) {
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::ins_gyros_consistent(const AP_InertialSensor &ins)
- {
- const uint8_t gyro_count = ins.get_gyro_count();
- if (gyro_count <= 1) {
- return true;
- }
- const Vector3f &prime_gyro_vec = ins.get_gyro();
- const uint32_t now = AP_HAL::millis();
- for(uint8_t i=0; i<gyro_count; i++) {
- if (!ins.use_gyro(i)) {
- continue;
- }
-
- const Vector3f &gyro_vec = ins.get_gyro(i);
- const Vector3f vec_diff = gyro_vec - prime_gyro_vec;
-
-
- if (vec_diff.length() <= radians(5)) {
- last_gyro_pass_ms[i] = now;
- }
- if (now - last_gyro_pass_ms[i] > 10000) {
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::ins_checks(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_INS)) {
- const AP_InertialSensor &ins = AP::ins();
- if (!ins.get_gyro_health_all()) {
- check_failed(ARMING_CHECK_INS, report, "Gyros not healthy");
- return false;
- }
- if (!ins.gyro_calibrated_ok_all()) {
- check_failed(ARMING_CHECK_INS, report, "Gyros not calibrated");
- return false;
- }
- if (!ins.get_accel_health_all()) {
- check_failed(ARMING_CHECK_INS, report, "Accels not healthy");
- return false;
- }
- if (!ins.accel_calibrated_ok_all()) {
- check_failed(ARMING_CHECK_INS, report, "3D Accel calibration needed");
- return false;
- }
-
-
- if (ins.accel_cal_requires_reboot()) {
- check_failed(ARMING_CHECK_INS, report, "Accels calibrated requires reboot");
- return false;
- }
-
- if (!ins_accels_consistent(ins)) {
- check_failed(ARMING_CHECK_INS, report, "Accels inconsistent");
- return false;
- }
-
- if (!ins_gyros_consistent(ins)) {
- check_failed(ARMING_CHECK_INS, report, "Gyros inconsistent");
- return false;
- }
-
- char failure_msg[50] = {};
- if (!AP::ahrs().attitudes_consistent(failure_msg, ARRAY_SIZE(failure_msg))) {
- check_failed(ARMING_CHECK_INS, report, "%s", failure_msg);
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::compass_checks(bool report)
- {
- Compass &_compass = AP::compass();
-
- if (_compass.is_calibrating()) {
- check_failed(ARMING_CHECK_NONE, report, "Compass calibration running");
- return false;
- }
-
- if (_compass.compass_cal_requires_reboot()) {
- check_failed(ARMING_CHECK_NONE, report, "Compass calibrated requires reboot");
- return false;
- }
- if ((checks_to_perform) & ARMING_CHECK_ALL ||
- (checks_to_perform) & ARMING_CHECK_COMPASS) {
-
-
- if (!_compass.use_for_yaw(_compass.get_primary())) {
-
- return true;
- }
- if (!_compass.healthy()) {
- check_failed(ARMING_CHECK_COMPASS, report, "Compass not healthy");
- return false;
- }
-
- if (!_compass.learn_offsets_enabled() && !_compass.configured()) {
- check_failed(ARMING_CHECK_COMPASS, report, "Compass not calibrated");
- return false;
- }
-
- const Vector3f offsets = _compass.get_offsets();
- if (offsets.length() > _compass.get_offsets_max()) {
- check_failed(ARMING_CHECK_COMPASS, report, "Compass offsets too high");
- return false;
- }
-
- const float mag_field = _compass.get_field().length();
- if (mag_field > AP_ARMING_COMPASS_MAGFIELD_MAX || mag_field < AP_ARMING_COMPASS_MAGFIELD_MIN) {
- check_failed(ARMING_CHECK_COMPASS, report, "Check mag field");
- return false;
- }
-
- if (!_compass.consistent()) {
- check_failed(ARMING_CHECK_COMPASS, report, "Compasses inconsistent");
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::gps_checks(bool report)
- {
- const AP_GPS &gps = AP::gps();
- if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {
-
- if (!AP::ahrs().home_is_set() ||
- gps.status() < AP_GPS::GPS_OK_FIX_3D) {
- check_failed(ARMING_CHECK_GPS, report, "Bad GPS Position");
- return false;
- }
-
- if (!gps.is_healthy()) {
- check_failed(ARMING_CHECK_GPS, report, "GPS is not healthy");
- return false;
- }
-
- float distance_m;
- if (!gps.all_consistent(distance_m)) {
- check_failed(ARMING_CHECK_GPS, report, "GPS positions differ by %4.1fm",
- (double)distance_m);
- return false;
- }
- if (!gps.blend_health_check()) {
- check_failed(ARMING_CHECK_GPS, report, "GPS blending unhealthy");
- return false;
- }
-
- const Location gps_loc = gps.location();
- Location ahrs_loc;
- if (AP::ahrs().get_position(ahrs_loc)) {
- const float distance = gps_loc.get_distance(ahrs_loc);
- if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) {
- check_failed(ARMING_CHECK_GPS, report, "GPS and AHRS differ by %4.1fm", (double)distance);
- return false;
- }
- }
- }
- if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
- uint8_t first_unconfigured;
- if (gps.first_unconfigured_gps(first_unconfigured)) {
- check_failed(ARMING_CHECK_GPS_CONFIG,
- report,
- "GPS %d failing configuration checks",
- first_unconfigured + 1);
- if (report) {
- gps.broadcast_first_configuration_failure_reason();
- }
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::battery_checks(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_BATTERY)) {
- char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
- if (!AP::battery().arming_checks(sizeof(buffer), buffer)) {
- check_failed(ARMING_CHECK_BATTERY, report, "%s", buffer);
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::hardware_safety_check(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_SWITCH)) {
-
- if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
- check_failed(ARMING_CHECK_SWITCH, report, "Hardware safety switch");
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::rc_calibration_checks(bool report)
- {
- bool check_passed = true;
- const uint8_t num_channels = RC_Channels::get_valid_channel_count();
- for (uint8_t i = 0; i < NUM_RC_CHANNELS; i++) {
- const RC_Channel *c = rc().channel(i);
- if (c == nullptr) {
- continue;
- }
- if (i >= num_channels && !(c->has_override())) {
- continue;
- }
- const uint16_t trim = c->get_radio_trim();
- if (c->get_radio_min() > trim) {
- check_failed(ARMING_CHECK_RC, report, "RC%d minimum is greater than trim", i + 1);
- check_passed = false;
- }
- if (c->get_radio_max() < trim) {
- check_failed(ARMING_CHECK_RC, report, "RC%d maximum is less than trim", i + 1);
- check_passed = false;
- }
- }
- return check_passed;
- }
- bool AP_Arming::manual_transmitter_checks(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_RC)) {
- if (AP_Notify::flags.failsafe_radio) {
- check_failed(ARMING_CHECK_RC, report, "Radio failsafe on");
- return false;
- }
- if (!rc_calibration_checks(report)) {
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::mission_checks(bool report)
- {
- if (((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_MISSION)) &&
- _required_mission_items) {
- AP_Mission *mission = AP::mission();
- if (mission == nullptr) {
- check_failed(ARMING_CHECK_MISSION, report, "No mission library present");
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- AP_HAL::panic("Mission checks requested, but no mission was allocated");
- #endif
- return false;
- }
- AP_Rally *rally = AP::rally();
- if (rally == nullptr) {
- check_failed(ARMING_CHECK_MISSION, report, "No rally library present");
- #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
- AP_HAL::panic("Mission checks requested, but no rally was allocated");
- #endif
- return false;
- }
- const struct MisItemTable {
- MIS_ITEM_CHECK check;
- MAV_CMD mis_item_type;
- const char *type;
- } misChecks[5] = {
- {MIS_ITEM_CHECK_LAND, MAV_CMD_NAV_LAND, "land"},
- {MIS_ITEM_CHECK_VTOL_LAND, MAV_CMD_NAV_VTOL_LAND, "vtol land"},
- {MIS_ITEM_CHECK_DO_LAND_START, MAV_CMD_DO_LAND_START, "do land start"},
- {MIS_ITEM_CHECK_TAKEOFF, MAV_CMD_NAV_TAKEOFF, "takeoff"},
- {MIS_ITEM_CHECK_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_TAKEOFF, "vtol takeoff"},
- };
- for (uint8_t i = 0; i < ARRAY_SIZE(misChecks); i++) {
- if (_required_mission_items & misChecks[i].check) {
- if (!mission->contains_item(misChecks[i].mis_item_type)) {
- check_failed(ARMING_CHECK_MISSION, report, "Missing mission item: %s", misChecks[i].type);
- return false;
- }
- }
- }
- if (_required_mission_items & MIS_ITEM_CHECK_RALLY) {
- Location ahrs_loc;
- if (!AP::ahrs().get_position(ahrs_loc)) {
- check_failed(ARMING_CHECK_MISSION, report, "Can't check rally without position");
- return false;
- }
- RallyLocation rally_loc = {};
- if (!rally->find_nearest_rally_point(ahrs_loc, rally_loc)) {
- check_failed(ARMING_CHECK_MISSION, report, "No sufficently close rally point located");
- return false;
- }
- }
- }
- return true;
- }
- bool AP_Arming::rangefinder_checks(bool report)
- {
- if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_RANGEFINDER)) {
- RangeFinder *range = RangeFinder::get_singleton();
- if (range == nullptr) {
- return true;
- }
- char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
- if (!range->prearm_healthy(buffer, ARRAY_SIZE(buffer))) {
- check_failed(ARMING_CHECK_RANGEFINDER, report, "%s", buffer);
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::servo_checks(bool report) const
- {
- bool check_passed = true;
- for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
- const SRV_Channel *c = SRV_Channels::srv_channel(i);
- if (c == nullptr || c->get_function() == SRV_Channel::k_none) {
- continue;
- }
- const uint16_t trim = c->get_trim();
- if (c->get_output_min() > trim) {
- check_failed(ARMING_CHECK_NONE, report, "SERVO%d minimum is greater than trim", i + 1);
- check_passed = false;
- }
- if (c->get_output_max() < trim) {
- check_failed(ARMING_CHECK_NONE, report, "SERVO%d maximum is less than trim", i + 1);
- check_passed = false;
- }
- }
- #if HAL_WITH_IO_MCU
- if (!iomcu.healthy()) {
- check_failed(ARMING_CHECK_NONE, report, "IOMCU is unhealthy");
- check_passed = false;
- }
- #endif
- return check_passed;
- }
- bool AP_Arming::board_voltage_checks(bool report)
- {
-
- if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_VOLTAGE)) {
- #if HAL_HAVE_BOARD_VOLTAGE
- const float bus_voltage = hal.analogin->board_voltage();
- const float vbus_min = AP_BoardConfig::get_minimum_board_voltage();
- if(((bus_voltage < vbus_min) || (bus_voltage > AP_ARMING_BOARD_VOLTAGE_MAX))) {
- 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);
- return false;
- }
- #endif
- #if HAL_HAVE_SERVO_VOLTAGE
- const float vservo_min = AP_BoardConfig::get_minimum_servo_voltage();
- if (is_positive(vservo_min)) {
- const float servo_voltage = hal.analogin->servorail_voltage();
- if (servo_voltage < vservo_min) {
- check_failed(ARMING_CHECK_VOLTAGE, report, "Servo voltage to low (%1.2fv < %1.2fv)", (double)servo_voltage, (double)vservo_min);
- return false;
- }
- }
- #endif
- }
- return true;
- }
- bool AP_Arming::system_checks(bool report)
- {
- if (check_enabled(ARMING_CHECK_SYSTEM)) {
- if (!hal.storage->healthy()) {
- check_failed(ARMING_CHECK_SYSTEM, report, "Param storage failed");
- return false;
- }
- }
- if (AP::internalerror().errors() != 0) {
- check_failed(ARMING_CHECK_NONE, report, "Internal errors (0x%x)", (unsigned int)AP::internalerror().errors());
- return false;
- }
- return true;
- }
- bool AP_Arming::proximity_checks(bool report) const
- {
- const AP_Proximity *proximity = AP::proximity();
-
- if (proximity == nullptr) {
- return true;
- }
- if (proximity->get_status() == AP_Proximity::Proximity_NotConnected) {
- return true;
- }
-
- if (proximity->get_status() < AP_Proximity::Proximity_Good) {
- check_failed(ARMING_CHECK_NONE, report, "check proximity sensor");
- return false;
- }
- return true;
- }
- bool AP_Arming::can_checks(bool report)
- {
- #if HAL_WITH_UAVCAN
- if (check_enabled(ARMING_CHECK_SYSTEM)) {
- const char *fail_msg = nullptr;
- uint8_t num_drivers = AP::can().get_num_drivers();
- for (uint8_t i = 0; i < num_drivers; i++) {
- switch (AP::can().get_protocol_type(i)) {
- case AP_BoardConfig_CAN::Protocol_Type_KDECAN: {
- #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
- AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
- if (ap_kdecan != nullptr && !ap_kdecan->pre_arm_check(fail_msg)) {
- if (fail_msg == nullptr) {
- check_failed(ARMING_CHECK_SYSTEM, report, "KDECAN failed");
- } else {
- check_failed(ARMING_CHECK_SYSTEM, report, "%s", fail_msg);
- }
- return false;
- }
- break;
- #else
- UNUSED_RESULT(fail_msg);
- #endif
- }
- case AP_BoardConfig_CAN::Protocol_Type_UAVCAN:
- case AP_BoardConfig_CAN::Protocol_Type_None:
- default:
- break;
- }
- }
- }
- #endif
- return true;
- }
- bool AP_Arming::fence_checks(bool display_failure)
- {
- const AC_Fence *fence = AP::fence();
- if (fence == nullptr) {
- return true;
- }
-
- const char *fail_msg = nullptr;
- if (fence->pre_arm_check(fail_msg)) {
- return true;
- }
- if (fail_msg == nullptr) {
- check_failed(ARMING_CHECK_NONE, display_failure, "Check fence");
- } else {
- check_failed(ARMING_CHECK_NONE, display_failure, "%s", fail_msg);
- }
- return false;
- }
- bool AP_Arming::pre_arm_checks(bool report)
- {
- #if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
- if (armed || require == (uint8_t)Required::NO) {
-
-
- return true;
- }
- #endif
- return hardware_safety_check(report)
- & barometer_checks(report)
- & ins_checks(report)
- & compass_checks(report)
- & gps_checks(report)
- & battery_checks(report)
- & logging_checks(report)
- & manual_transmitter_checks(report)
- & mission_checks(report)
- & rangefinder_checks(report)
- & servo_checks(report)
- & board_voltage_checks(report)
- & system_checks(report)
- & can_checks(report)
- & proximity_checks(report);
- }
- bool AP_Arming::arm_checks(AP_Arming::Method method)
- {
-
- if ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_GPS_CONFIG)) {
- if (!AP::gps().prepare_for_arming()) {
- return false;
- }
- }
-
-
-
-
-
-
- AP_Logger *logger = AP_Logger::get_singleton();
- if (logger->logging_present()) {
-
- logger->PrepForArming();
- if (!logger->logging_started() &&
- ((checks_to_perform & ARMING_CHECK_ALL) ||
- (checks_to_perform & ARMING_CHECK_LOGGING))) {
- check_failed(ARMING_CHECK_LOGGING, true, "Logging not started");
- return false;
- }
- }
- return true;
- }
- bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks)
- {
- if (armed) {
- return false;
- }
- if (!do_arming_checks || (pre_arm_checks(true) && arm_checks(method))) {
- armed = true;
-
-
- } else {
- AP::logger().arming_failure();
- armed = false;
- }
- return armed;
- }
- bool AP_Arming::disarm()
- {
- if (!armed) {
- return false;
- }
- armed = false;
- #if HAL_HAVE_SAFETY_SWITCH
- AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton();
- if ((board_cfg != nullptr) &&
- (board_cfg->get_safety_button_options() & AP_BoardConfig::BOARD_SAFETY_OPTION_SAFETY_ON_DISARM)) {
- hal.rcout->force_safety_on();
- }
- #endif
-
-
- return true;
- }
- AP_Arming::Required AP_Arming::arming_required()
- {
- return (AP_Arming::Required)require.get();
- }
- bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const
- {
-
- if ((checks_to_perform != ARMING_CHECK_ALL) && !(checks_to_perform & ARMING_CHECK_RC)) {
- return true;
- }
- bool ret = true;
- const char *channel_names[] = { "Roll", "Pitch", "Throttle", "Yaw" };
- for (uint8_t i=0; i<ARRAY_SIZE(channel_names);i++) {
- const RC_Channel *channel = channels[i];
- const char *channel_name = channel_names[i];
-
- if (channel->get_radio_min() > 1300) {
- check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
- ret = false;
- }
- if (channel->get_radio_max() < 1700) {
- check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);
- ret = false;
- }
- bool fail = true;
- if (i == 2) {
-
- fail = false;
- }
- if (channel->get_radio_trim() < channel->get_radio_min()) {
- check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim below min", channel_name);
- if (fail) {
- ret = false;
- }
- }
- if (channel->get_radio_trim() > channel->get_radio_max()) {
- check_failed(ARMING_CHECK_RC, display_failure, "%s radio trim above max", channel_name);
- if (fail) {
- ret = false;
- }
- }
- }
- return ret;
- }
- void AP_Arming::Log_Write_Arm_Disarm()
- {
- struct log_Arm_Disarm pkt = {
- LOG_PACKET_HEADER_INIT(LOG_ARM_DISARM_MSG),
- time_us : AP_HAL::micros64(),
- arm_state : is_armed(),
- arm_checks : get_enabled_checks()
- };
- AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
- }
- AP_Arming *AP_Arming::_singleton = nullptr;
- AP_Arming *AP_Arming::get_singleton()
- {
- return AP_Arming::_singleton;
- }
- namespace AP {
- AP_Arming &arming()
- {
- return *AP_Arming::get_singleton();
- }
- };
|