mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Compass: Increase default MAX compass offset
After discussing the @tridge and @rmackay9 it was suggested that raising the maximum allowable compass offset value would allow users of the LIS3MDL and possibly others with larger compass offsets to fly with the default setting. This has been deemed a fairly safe change that still allows for sufficient overhead to prevent saturation.
This commit is contained in:
parent
c8f93a3ddc
commit
27a2b8a350
@ -35,7 +35,7 @@ extern AP_HAL::HAL& hal;
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT
|
||||
#define AP_COMPASS_OFFSETS_MAX_DEFAULT 850
|
||||
#define AP_COMPASS_OFFSETS_MAX_DEFAULT 1250
|
||||
#endif
|
||||
|
||||
#ifndef HAL_COMPASS_FILTER_DEFAULT
|
||||
|
Loading…
Reference in New Issue
Block a user