mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: allow single compass configure for autopilot boards
This commit is contained in:
parent
5865e010b0
commit
b31a04e52b
@ -51,8 +51,12 @@
|
|||||||
#ifndef HAL_COMPASS_MAX_SENSORS
|
#ifndef HAL_COMPASS_MAX_SENSORS
|
||||||
#define HAL_COMPASS_MAX_SENSORS 3
|
#define HAL_COMPASS_MAX_SENSORS 3
|
||||||
#endif
|
#endif
|
||||||
|
#if HAL_COMPASS_MAX_SENSORS > 1
|
||||||
#define COMPASS_MAX_UNREG_DEV 5
|
#define COMPASS_MAX_UNREG_DEV 5
|
||||||
#else
|
#else
|
||||||
|
#define COMPASS_MAX_UNREG_DEV 0
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
#ifndef HAL_COMPASS_MAX_SENSORS
|
#ifndef HAL_COMPASS_MAX_SENSORS
|
||||||
#define HAL_COMPASS_MAX_SENSORS 1
|
#define HAL_COMPASS_MAX_SENSORS 1
|
||||||
#endif
|
#endif
|
||||||
|
@ -53,10 +53,13 @@ bool Compass::_start_calibration(uint8_t i, bool retry, float delay)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
Priority prio = Priority(i);
|
Priority prio = Priority(i);
|
||||||
|
|
||||||
|
#if COMPASS_MAX_INSTANCES > 1
|
||||||
if (_priority_did_list[prio] != _priority_did_stored_list[prio]) {
|
if (_priority_did_list[prio] != _priority_did_stored_list[prio]) {
|
||||||
gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change");
|
gcs().send_text(MAV_SEVERITY_ERROR, "Compass cal requires reboot after priority change");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (_calibrator[prio] == nullptr) {
|
if (_calibrator[prio] == nullptr) {
|
||||||
_calibrator[prio] = new CompassCalibrator();
|
_calibrator[prio] = new CompassCalibrator();
|
||||||
|
Loading…
Reference in New Issue
Block a user