#include #include #include #include #include #include #include "AP_Compass.h" const extern AP_HAL::HAL& hal; #if COMPASS_CAL_ENABLED void Compass::cal_update() { if (hal.util->get_soft_armed()) { return; } bool running = false; for (Priority i(0); idelay(1000); hal.scheduler->reboot(false); } } bool Compass::_start_calibration(uint8_t i, bool retry, float delay) { if (!healthy(i)) { return false; } if (!use_for_yaw(i)) { return false; } Priority prio = Priority(i); if (_priority_did_list[prio] != _priority_did_stored_list[prio]) { gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change"); return false; } if (_options.get() & uint16_t(Option::CAL_REQUIRE_GPS)) { if (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) { gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires GPS lock"); return false; } } if (!is_calibrating()) { AP_Notify::events.initiated_compass_cal = 1; } if (i == 0 && _get_state(prio).external != 0) { _calibrator[prio].set_tolerance(_calibration_threshold); } else { // internal compasses or secondary compasses get twice the // threshold. This is because internal compasses tend to be a // lot noisier _calibrator[prio].set_tolerance(_calibration_threshold*2); } if (_rotate_auto) { enum Rotation r = _get_state(prio).external?(enum Rotation)_get_state(prio).orientation.get():ROTATION_NONE; if (r != ROTATION_CUSTOM) { _calibrator[prio].set_orientation(r, _get_state(prio).external, _rotate_auto>=2); } } _cal_saved[prio] = false; _calibrator[prio].start(retry, delay, get_offsets_max(), i); // disable compass learning both for calibration and after completion _learn.set_and_save(0); return true; } bool Compass::_start_calibration_mask(uint8_t mask, bool retry, bool autosave, float delay, bool autoreboot) { _cal_autosave = autosave; _compass_cal_autoreboot = autoreboot; for (uint8_t i=0; i= 2) { set_and_save_orientation(i, cal.get_orientation()); } if (!is_calibrating()) { AP_Notify::events.compass_cal_saved = 1; } return true; } else { return false; } } bool Compass::_accept_calibration_mask(uint8_t mask) { bool success = true; for (Priority i(0); iget_soft_armed()) { gcs().send_text(MAV_SEVERITY_NOTICE, "Disarm to allow compass calibration"); result = MAV_RESULT_FAILED; break; } if (packet.param1 < 0 || packet.param1 > 255) { result = MAV_RESULT_FAILED; break; } uint8_t mag_mask = packet.param1; bool retry = !is_zero(packet.param2); bool autosave = !is_zero(packet.param3); float delay = packet.param4; bool autoreboot = !is_zero(packet.param5); if (mag_mask == 0) { // 0 means all _reset_compass_id(); start_calibration_all(retry, autosave, delay, autoreboot); } else { if (!_start_calibration_mask(mag_mask, retry, autosave, delay, autoreboot)) { result = MAV_RESULT_FAILED; } } break; } case MAV_CMD_DO_ACCEPT_MAG_CAL: { result = MAV_RESULT_ACCEPTED; if (packet.param1 < 0 || packet.param1 > 255) { result = MAV_RESULT_FAILED; break; } uint8_t mag_mask = packet.param1; if (mag_mask == 0) { // 0 means all mag_mask = 0xFF; } if (!_accept_calibration_mask(mag_mask)) { result = MAV_RESULT_FAILED; } break; } case MAV_CMD_DO_CANCEL_MAG_CAL: { result = MAV_RESULT_ACCEPTED; if (packet.param1 < 0 || packet.param1 > 255) { result = MAV_RESULT_FAILED; break; } uint8_t mag_mask = packet.param1; if (mag_mask == 0) { // 0 means all cancel_calibration_all(); break; } _cancel_calibration_mask(mag_mask); break; } } return result; } /* get mag field with the effects of offsets, diagonals and off-diagonals removed */ bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) { // form eliptical correction matrix and invert it. This is // needed to remove the effects of the eliptical correction // when calculating new offsets const Vector3f &diagonals = get_diagonals(instance); const Vector3f &offdiagonals = get_offdiagonals(instance); Matrix3f mat { diagonals.x, offdiagonals.x, offdiagonals.y, offdiagonals.x, diagonals.y, offdiagonals.z, offdiagonals.y, offdiagonals.z, diagonals.z }; if (!mat.invert()) { return false; } // get corrected field field = get_field(instance); // remove impact of diagonals and off-diagonals field = mat * field; // remove impact of offsets field -= get_offsets(instance); return true; } /* fast compass calibration given vehicle position and yaw. This results in zero diagonal and off-diagonal elements, so is only suitable for vehicles where the field is close to spherical. It is useful for large vehicles where moving the vehicle to calibrate it is difficult. The offsets of the selected compasses are set to values to bring them into consistency with the WMM tables at the given latitude and longitude. If compass_mask is zero then all enabled compasses are calibrated. This assumes that the compass is correctly scaled in milliGauss */ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask, float lat_deg, float lon_deg) { _reset_compass_id(); if (is_zero(lat_deg) && is_zero(lon_deg)) { Location loc; // get AHRS position. If unavailable then try GPS location if (!AP::ahrs().get_position(loc)) { if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) { gcs().send_text(MAV_SEVERITY_ERROR, "Mag: no position available"); return MAV_RESULT_FAILED; } loc = AP::gps().location(); } lat_deg = loc.lat * 1.0e-7; lon_deg = loc.lng * 1.0e-7; } // get the magnetic field intensity and orientation float intensity; float declination; float inclination; if (!AP_Declination::get_mag_field_ef(lat_deg, lon_deg, intensity, declination, inclination)) { gcs().send_text(MAV_SEVERITY_ERROR, "Mag: WMM table error"); return MAV_RESULT_FAILED; } // create a field vector and rotate to the required orientation Vector3f field(1e3f * intensity, 0.0f, 0.0f); Matrix3f R; R.from_euler(0.0f, -ToRad(inclination), ToRad(declination)); field = R * field; Matrix3f dcm; dcm.from_euler(AP::ahrs().roll, AP::ahrs().pitch, radians(yaw_deg)); // Rotate into body frame using provided yaw field = dcm.transposed() * field; for (uint8_t i=0; i