mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: relax compass cal fitness and consistency checks
This commit is contained in:
parent
b5573f6665
commit
855125381d
|
@ -398,7 +398,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|||
// @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 32
|
||||
// @Values: 4:Very Strict,8:Default,16:Relaxed,32:Very Relaxed
|
||||
// @Values: 4:Very Strict,8:Strict,16:Default,32:Relaxed
|
||||
// @Increment: 0.1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CAL_FIT", 30, Compass, _calibration_threshold, AP_COMPASS_CALIBRATION_FITNESS_DEFAULT),
|
||||
|
|
|
@ -30,17 +30,11 @@
|
|||
#endif
|
||||
|
||||
// define default compass calibration fitness and consistency checks
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_PX4_V4
|
||||
# define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT 16.0f
|
||||
# define AP_COMPASS_MAX_XYZ_ANG_DIFF radians(75.0f)
|
||||
# define AP_COMPASS_MAX_XY_ANG_DIFF radians(45.0f)
|
||||
# define AP_COMPASS_MAX_XY_LENGTH_DIFF 150.0f
|
||||
#else
|
||||
# define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT 8.0f
|
||||
# define AP_COMPASS_MAX_XYZ_ANG_DIFF radians(50.0f)
|
||||
# define AP_COMPASS_MAX_XY_ANG_DIFF radians(30.0f)
|
||||
# define AP_COMPASS_MAX_XY_LENGTH_DIFF 100.0f
|
||||
#endif
|
||||
#define AP_COMPASS_CALIBRATION_FITNESS_DEFAULT 16.0f
|
||||
#define AP_COMPASS_MAX_XYZ_ANG_DIFF radians(90.0f)
|
||||
#define AP_COMPASS_MAX_XY_ANG_DIFF radians(60.0f)
|
||||
#define AP_COMPASS_MAX_XY_LENGTH_DIFF 200.0f
|
||||
|
||||
/**
|
||||
maximum number of compass instances available on this platform. If more
|
||||
than 1 then redundant sensors may be available
|
||||
|
|
Loading…
Reference in New Issue