AP_Compass: narrow range of allowed scale factor

This commit is contained in:
Andrew Tridgell 2019-12-02 15:55:27 +11:00
parent 3e2d7aa1e2
commit d3226e1f94

View File

@ -19,8 +19,8 @@ enum compass_cal_status_t {
COMPASS_CAL_BAD_RADIUS = 7,
};
#define COMPASS_MIN_SCALE_FACTOR 0.3
#define COMPASS_MAX_SCALE_FACTOR 1.6
#define COMPASS_MIN_SCALE_FACTOR 0.85
#define COMPASS_MAX_SCALE_FACTOR 1.3
class CompassCalibrator {
public: