#include #include #include #include "AP_Compass.h" extern AP_HAL::HAL& hal; #if COMPASS_CAL_ENABLED void Compass::cal_update() { if (hal.util->get_soft_armed()) { return; } bool running = false; for (uint8_t 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; } if (!is_calibrating()) { AP_Notify::events.initiated_compass_cal = 1; } if (i == get_primary() && _state[i].external != 0) { _calibrator[i].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[i].set_tolerance(_calibration_threshold*2); } if (_rotate_auto) { enum Rotation r = _state[i].external?(enum Rotation)_state[i].orientation.get():ROTATION_NONE; if (r != ROTATION_CUSTOM) { _calibrator[i].set_orientation(r, _state[i].external, _rotate_auto>=2); } } _cal_saved[i] = false; _calibrator[i].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) { _state[i].orientation.set_and_save_ifchanged(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 (uint8_t i=0; iget_soft_armed()) { hal.console->printf("Disarm for compass calibration\n"); 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 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; } #endif // COMPASS_CAL_ENABLED