AP_Compass: allow single compass configure for autopilot boards

This commit is contained in:
Siddharth Purohit 2021-05-18 15:25:43 +05:30 committed by Andrew Tridgell
parent 5865e010b0
commit b31a04e52b
2 changed files with 7 additions and 0 deletions

View File

@ -51,8 +51,12 @@
#ifndef HAL_COMPASS_MAX_SENSORS
#define HAL_COMPASS_MAX_SENSORS 3
#endif
#if HAL_COMPASS_MAX_SENSORS > 1
#define COMPASS_MAX_UNREG_DEV 5
#else
#define COMPASS_MAX_UNREG_DEV 0
#endif
#else
#ifndef HAL_COMPASS_MAX_SENSORS
#define HAL_COMPASS_MAX_SENSORS 1
#endif

View File

@ -53,10 +53,13 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
return false;
}
Priority prio = Priority(i);
#if COMPASS_MAX_INSTANCES > 1
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;
}
#endif
if (_calibrator[prio] == nullptr) {
_calibrator[prio] = new CompassCalibrator();