2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Notify/AP_Notify.h>
|
2015-09-06 19:58:11 -03:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2015-03-18 20:42:30 -03:00
|
|
|
|
2016-03-10 20:41:18 -04:00
|
|
|
#include "AP_Compass.h"
|
|
|
|
|
2015-08-28 18:03:09 -03:00
|
|
|
extern AP_HAL::HAL& hal;
|
|
|
|
|
2015-03-18 20:42:30 -03:00
|
|
|
void
|
|
|
|
Compass::compass_cal_update()
|
|
|
|
{
|
2015-09-02 15:19:15 -03:00
|
|
|
bool running = false;
|
2015-03-18 20:42:30 -03:00
|
|
|
|
2015-03-18 21:49:08 -03:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
|
|
bool failure;
|
|
|
|
_calibrator[i].update(failure);
|
|
|
|
if (failure) {
|
|
|
|
AP_Notify::events.compass_cal_failed = 1;
|
|
|
|
}
|
2015-03-18 20:42:30 -03:00
|
|
|
|
2015-03-18 21:49:08 -03:00
|
|
|
if (_calibrator[i].check_for_timeout()) {
|
|
|
|
AP_Notify::events.compass_cal_failed = 1;
|
2015-03-18 20:42:30 -03:00
|
|
|
cancel_calibration_all();
|
|
|
|
}
|
|
|
|
|
2015-03-18 21:49:08 -03:00
|
|
|
if (_calibrator[i].running()) {
|
2015-09-02 15:19:15 -03:00
|
|
|
running = true;
|
2016-10-25 02:16:11 -03:00
|
|
|
} else if (_cal_autosave && !_cal_saved[i] && _calibrator[i].get_status() == COMPASS_CAL_SUCCESS) {
|
|
|
|
_accept_calibration(i);
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
}
|
2015-09-02 15:19:15 -03:00
|
|
|
|
|
|
|
AP_Notify::flags.compass_cal_running = running;
|
|
|
|
|
2015-08-27 23:44:33 -03:00
|
|
|
if (is_calibrating()) {
|
|
|
|
_cal_has_run = true;
|
|
|
|
return;
|
2016-10-25 02:16:11 -03:00
|
|
|
} else if (_cal_has_run && _auto_reboot()) {
|
2015-08-27 23:44:33 -03:00
|
|
|
hal.scheduler->delay(1000);
|
|
|
|
hal.scheduler->reboot(false);
|
|
|
|
}
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2016-10-25 02:16:11 -03:00
|
|
|
Compass::_start_calibration(uint8_t i, bool retry, float delay)
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
2015-09-02 18:58:05 -03:00
|
|
|
if (!healthy(i)) {
|
2015-03-18 20:42:30 -03:00
|
|
|
return false;
|
|
|
|
}
|
2016-10-25 02:16:11 -03:00
|
|
|
if (!use_for_yaw(i)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (!is_calibrating()) {
|
2015-09-02 18:58:05 -03:00
|
|
|
AP_Notify::events.initiated_compass_cal = 1;
|
|
|
|
}
|
2016-05-18 03:32:32 -03:00
|
|
|
if (i == get_primary() && _state[i].external != 0) {
|
2015-09-14 04:01:14 -03:00
|
|
|
_calibrator[i].set_tolerance(_calibration_threshold);
|
2015-09-02 18:58:05 -03:00
|
|
|
} else {
|
2016-05-18 03:32:32 -03:00
|
|
|
// internal compasses or secondary compasses get twice the
|
|
|
|
// threshold. This is because internal compasses tend to be a
|
|
|
|
// lot noisier
|
2015-09-14 04:01:14 -03:00
|
|
|
_calibrator[i].set_tolerance(_calibration_threshold*2);
|
2015-09-02 18:58:05 -03:00
|
|
|
}
|
2016-10-25 02:16:11 -03:00
|
|
|
_cal_saved[i] = false;
|
2017-04-03 19:38:14 -03:00
|
|
|
_calibrator[i].start(retry, delay, get_offsets_max());
|
2015-09-06 19:07:07 -03:00
|
|
|
|
|
|
|
// disable compass learning both for calibration and after completion
|
|
|
|
_learn.set_and_save(0);
|
|
|
|
|
2015-09-02 18:58:05 -03:00
|
|
|
return true;
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2016-10-25 02:16:11 -03:00
|
|
|
Compass::_start_calibration_mask(uint8_t mask, bool retry, bool autosave, float delay, bool autoreboot)
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
2016-10-25 02:16:11 -03:00
|
|
|
_cal_autosave = autosave;
|
|
|
|
_compass_cal_autoreboot = autoreboot;
|
|
|
|
|
2015-03-18 21:49:39 -03:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
|
|
if ((1<<i) & mask) {
|
2016-10-25 02:16:11 -03:00
|
|
|
if (!_start_calibration(i,retry,delay)) {
|
|
|
|
_cancel_calibration_mask(mask);
|
2015-03-18 20:42:30 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-10-25 02:16:11 -03:00
|
|
|
void
|
2015-08-27 23:44:33 -03:00
|
|
|
Compass::start_calibration_all(bool retry, bool autosave, float delay, bool autoreboot)
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
2016-10-25 02:16:11 -03:00
|
|
|
_cal_autosave = autosave;
|
|
|
|
_compass_cal_autoreboot = autoreboot;
|
|
|
|
|
2015-03-18 21:49:39 -03:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
2016-10-25 02:16:11 -03:00
|
|
|
// ignore any compasses that fail to start calibrating
|
|
|
|
// start all should only calibrate compasses that are being used
|
|
|
|
_start_calibration(i,retry,delay);
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void
|
2016-10-25 02:16:11 -03:00
|
|
|
Compass::_cancel_calibration(uint8_t i)
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
|
|
|
AP_Notify::events.initiated_compass_cal = 0;
|
2015-09-02 15:20:15 -03:00
|
|
|
|
|
|
|
if (_calibrator[i].running() || _calibrator[i].get_status() == COMPASS_CAL_WAITING_TO_START) {
|
|
|
|
AP_Notify::events.compass_cal_canceled = 1;
|
|
|
|
}
|
2016-10-25 02:16:11 -03:00
|
|
|
_cal_saved[i] = false;
|
2015-09-02 15:20:15 -03:00
|
|
|
_calibrator[i].clear();
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void
|
2016-10-25 02:16:11 -03:00
|
|
|
Compass::_cancel_calibration_mask(uint8_t mask)
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
|
|
|
for(uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
|
|
if((1<<i) & mask) {
|
2016-10-25 02:16:11 -03:00
|
|
|
_cancel_calibration(i);
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void
|
|
|
|
Compass::cancel_calibration_all()
|
|
|
|
{
|
2016-10-25 02:16:11 -03:00
|
|
|
_cancel_calibration_mask(0xFF);
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2016-10-25 02:16:11 -03:00
|
|
|
Compass::_accept_calibration(uint8_t i)
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
|
|
|
CompassCalibrator& cal = _calibrator[i];
|
|
|
|
uint8_t cal_status = cal.get_status();
|
|
|
|
|
2016-10-25 02:16:11 -03:00
|
|
|
if (_cal_saved[i] || cal_status == COMPASS_CAL_NOT_STARTED) {
|
|
|
|
return true;
|
|
|
|
} else if (cal_status == COMPASS_CAL_SUCCESS) {
|
2015-08-27 23:44:33 -03:00
|
|
|
_cal_complete_requires_reboot = true;
|
2016-10-25 02:16:11 -03:00
|
|
|
_cal_saved[i] = true;
|
|
|
|
|
2015-03-18 20:42:30 -03:00
|
|
|
Vector3f ofs, diag, offdiag;
|
|
|
|
cal.get_calibration(ofs, diag, offdiag);
|
|
|
|
|
|
|
|
set_and_save_offsets(i, ofs);
|
|
|
|
set_and_save_diagonals(i,diag);
|
|
|
|
set_and_save_offdiagonals(i,offdiag);
|
|
|
|
|
2015-03-18 21:49:39 -03:00
|
|
|
if (!is_calibrating()) {
|
2015-03-18 20:42:30 -03:00
|
|
|
AP_Notify::events.compass_cal_saved = 1;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
} else {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
2016-10-25 02:16:11 -03:00
|
|
|
Compass::_accept_calibration_mask(uint8_t mask)
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
|
|
|
bool success = true;
|
2015-03-18 21:49:39 -03:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
|
|
if ((1<<i) & mask) {
|
2016-10-25 02:16:11 -03:00
|
|
|
if (!_accept_calibration(i)) {
|
2015-03-18 20:42:30 -03:00
|
|
|
success = false;
|
|
|
|
}
|
2016-10-25 02:16:11 -03:00
|
|
|
_calibrator[i].clear();
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return success;
|
|
|
|
}
|
|
|
|
|
|
|
|
void
|
|
|
|
Compass::send_mag_cal_progress(mavlink_channel_t chan)
|
|
|
|
{
|
2016-10-25 02:16:11 -03:00
|
|
|
uint8_t cal_mask = _get_cal_mask();
|
2015-03-18 20:42:30 -03:00
|
|
|
|
2015-09-02 19:30:42 -03:00
|
|
|
for (uint8_t compass_id=0; compass_id<COMPASS_MAX_INSTANCES; compass_id++) {
|
2016-10-25 02:16:11 -03:00
|
|
|
// ensure we don't try to send with no space available
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_PROGRESS)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2016-04-22 19:21:18 -03:00
|
|
|
auto& calibrator = _calibrator[compass_id];
|
|
|
|
uint8_t cal_status = calibrator.get_status();
|
2015-03-18 20:42:30 -03:00
|
|
|
|
2015-03-18 21:49:39 -03:00
|
|
|
if (cal_status == COMPASS_CAL_WAITING_TO_START ||
|
|
|
|
cal_status == COMPASS_CAL_RUNNING_STEP_ONE ||
|
|
|
|
cal_status == COMPASS_CAL_RUNNING_STEP_TWO) {
|
2016-04-22 19:21:18 -03:00
|
|
|
uint8_t completion_pct = calibrator.get_completion_percent();
|
|
|
|
auto& completion_mask = calibrator.get_completion_mask();
|
2015-03-18 20:42:30 -03:00
|
|
|
Vector3f direction(0.0f,0.0f,0.0f);
|
2015-09-02 19:30:42 -03:00
|
|
|
uint8_t attempt = _calibrator[compass_id].get_attempt();
|
2015-03-18 20:42:30 -03:00
|
|
|
|
|
|
|
mavlink_msg_mag_cal_progress_send(
|
|
|
|
chan,
|
|
|
|
compass_id, cal_mask,
|
|
|
|
cal_status, attempt, completion_pct, completion_mask,
|
|
|
|
direction.x, direction.y, direction.z
|
|
|
|
);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void Compass::send_mag_cal_report(mavlink_channel_t chan)
|
|
|
|
{
|
2016-10-25 02:16:11 -03:00
|
|
|
uint8_t cal_mask = _get_cal_mask();
|
2015-03-18 20:42:30 -03:00
|
|
|
|
2015-09-02 19:30:42 -03:00
|
|
|
for (uint8_t compass_id=0; compass_id<COMPASS_MAX_INSTANCES; compass_id++) {
|
2016-10-25 02:16:11 -03:00
|
|
|
// ensure we don't try to send with no space available
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, MAG_CAL_REPORT)) {
|
|
|
|
return;
|
|
|
|
}
|
2015-03-18 20:42:30 -03:00
|
|
|
|
2015-09-02 19:30:42 -03:00
|
|
|
uint8_t cal_status = _calibrator[compass_id].get_status();
|
2015-08-27 23:44:33 -03:00
|
|
|
if ((cal_status == COMPASS_CAL_SUCCESS ||
|
2016-10-25 02:16:11 -03:00
|
|
|
cal_status == COMPASS_CAL_FAILED)) {
|
2015-09-02 19:30:42 -03:00
|
|
|
float fitness = _calibrator[compass_id].get_fitness();
|
2015-03-18 20:42:30 -03:00
|
|
|
Vector3f ofs, diag, offdiag;
|
2015-09-02 19:30:42 -03:00
|
|
|
_calibrator[compass_id].get_calibration(ofs, diag, offdiag);
|
2016-10-25 02:16:11 -03:00
|
|
|
uint8_t autosaved = _cal_saved[compass_id];
|
2015-03-18 20:42:30 -03:00
|
|
|
|
|
|
|
mavlink_msg_mag_cal_report_send(
|
|
|
|
chan,
|
|
|
|
compass_id, cal_mask,
|
|
|
|
cal_status, autosaved,
|
|
|
|
fitness,
|
|
|
|
ofs.x, ofs.y, ofs.z,
|
|
|
|
diag.x, diag.y, diag.z,
|
|
|
|
offdiag.x, offdiag.y, offdiag.z
|
|
|
|
);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
bool
|
|
|
|
Compass::is_calibrating() const
|
|
|
|
{
|
2016-10-25 02:16:11 -03:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
|
|
switch(_calibrator[i].get_status()) {
|
|
|
|
case COMPASS_CAL_NOT_STARTED:
|
|
|
|
case COMPASS_CAL_SUCCESS:
|
|
|
|
case COMPASS_CAL_FAILED:
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
2015-03-18 20:42:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t
|
2016-10-25 02:16:11 -03:00
|
|
|
Compass::_get_cal_mask() const
|
2015-03-18 20:42:30 -03:00
|
|
|
{
|
|
|
|
uint8_t cal_mask = 0;
|
2015-03-18 21:49:39 -03:00
|
|
|
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
|
|
|
|
if (_calibrator[i].get_status() != COMPASS_CAL_NOT_STARTED) {
|
2015-03-18 20:42:30 -03:00
|
|
|
cal_mask |= 1 << i;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return cal_mask;
|
|
|
|
}
|
2015-08-23 07:23:38 -03:00
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
handle an incoming MAG_CAL command
|
|
|
|
*/
|
|
|
|
uint8_t Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
uint8_t result = MAV_RESULT_FAILED;
|
|
|
|
|
|
|
|
switch (packet.command) {
|
|
|
|
case MAV_CMD_DO_START_MAG_CAL: {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2015-09-03 03:50:56 -03:00
|
|
|
if (hal.util->get_soft_armed()) {
|
2017-01-21 00:36:34 -04:00
|
|
|
hal.console->printf("Disarm for compass calibration\n");
|
2015-09-03 03:50:56 -03:00
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
if (packet.param1 < 0 || packet.param1 > 255) {
|
2015-08-23 07:23:38 -03:00
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t mag_mask = packet.param1;
|
2015-11-24 14:57:42 -04:00
|
|
|
bool retry = !is_zero(packet.param2);
|
|
|
|
bool autosave = !is_zero(packet.param3);
|
2015-08-23 07:23:38 -03:00
|
|
|
float delay = packet.param4;
|
2015-11-24 14:57:42 -04:00
|
|
|
bool autoreboot = !is_zero(packet.param5);
|
2015-08-23 07:23:38 -03:00
|
|
|
|
|
|
|
if (mag_mask == 0) { // 0 means all
|
2016-10-25 02:16:11 -03:00
|
|
|
start_calibration_all(retry, autosave, delay, autoreboot);
|
2015-08-23 07:23:38 -03:00
|
|
|
} else {
|
2016-10-25 02:16:11 -03:00
|
|
|
if (!_start_calibration_mask(mag_mask, retry, autosave, delay, autoreboot)) {
|
2015-08-23 07:23:38 -03:00
|
|
|
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
|
2016-10-25 02:16:11 -03:00
|
|
|
mag_mask = 0xFF;
|
2015-08-23 07:23:38 -03:00
|
|
|
}
|
|
|
|
|
2016-10-25 02:16:11 -03:00
|
|
|
if(!_accept_calibration_mask(mag_mask)) {
|
2015-08-23 07:23:38 -03:00
|
|
|
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;
|
|
|
|
}
|
|
|
|
|
2016-10-25 02:16:11 -03:00
|
|
|
_cancel_calibration_mask(mag_mask);
|
2015-08-23 07:23:38 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return result;
|
|
|
|
}
|