mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: added parameter for compass calibration fitness threshold
This commit is contained in:
parent
eea54c9e09
commit
fa9ff5b604
|
@ -47,9 +47,9 @@ Compass::start_calibration(uint8_t i, bool retry, bool autosave, float delay, bo
|
|||
AP_Notify::events.initiated_compass_cal = 1;
|
||||
}
|
||||
if (i == get_primary()) {
|
||||
_calibrator[i].set_tolerance(8);
|
||||
_calibrator[i].set_tolerance(_calibration_threshold);
|
||||
} else {
|
||||
_calibrator[i].set_tolerance(16);
|
||||
_calibrator[i].set_tolerance(_calibration_threshold*2);
|
||||
}
|
||||
_calibrator[i].start(retry, autosave, delay);
|
||||
_compass_cal_autoreboot = autoreboot;
|
||||
|
|
|
@ -365,6 +365,14 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
|
|||
AP_GROUPINFO("ODI3", 29, Compass, _state[2].offdiagonals, 0),
|
||||
#endif
|
||||
|
||||
// @Param: CAL_FIT
|
||||
// @DisplayName: Compass calibration fitness
|
||||
// @Description: This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value.
|
||||
// @Range: 4 20
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, 8.0f),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -406,6 +406,8 @@ private:
|
|||
|
||||
// if we want HIL only
|
||||
bool _hil_mode:1;
|
||||
|
||||
AP_Float _calibration_threshold;
|
||||
};
|
||||
|
||||
#include "AP_Compass_Backend.h"
|
||||
|
|
Loading…
Reference in New Issue