mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_Compass: narrow range of allowed scale factor
This commit is contained in:
parent
536222859d
commit
342dd67dc0
@ -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:
|
||||
|
Loading…
Reference in New Issue
Block a user