mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_Compass: raise default max compass offsets
the larger offset doesn't present any problems for the compass drivers, and helps on planes with magnetic hatches
This commit is contained in:
parent
ba7b354326
commit
700519d805
@ -35,7 +35,7 @@ extern AP_HAL::HAL& hal;
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_OFFSETS_MAX_DEFAULT
|
||||
#define AP_COMPASS_OFFSETS_MAX_DEFAULT 1250
|
||||
#define AP_COMPASS_OFFSETS_MAX_DEFAULT 1800
|
||||
#endif
|
||||
|
||||
#ifndef HAL_COMPASS_FILTER_DEFAULT
|
||||
|
Loading…
Reference in New Issue
Block a user