mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Compass: allow override of COMPASS_AUTO_ROT
This commit is contained in:
parent
7cb169d0b9
commit
cdae1606ce
@ -41,6 +41,10 @@ extern AP_HAL::HAL& hal;
|
||||
#define HAL_COMPASS_FILTER_DEFAULT 0 // turned off by default
|
||||
#endif
|
||||
|
||||
#ifndef HAL_COMPASS_AUTO_ROT_DEFAULT
|
||||
#define HAL_COMPASS_AUTO_ROT_DEFAULT 1
|
||||
#endif
|
||||
|
||||
const AP_Param::GroupInfo Compass::var_info[] = {
|
||||
// index 0 was used for the old orientation matrix
|
||||
|
||||
@ -448,7 +452,7 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
||||
// @DisplayName: Automatically check orientation
|
||||
// @Description: When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.
|
||||
// @Values: 0:Disabled,1:CheckOnly,2:CheckAndFix
|
||||
AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, 1),
|
||||
AP_GROUPINFO("AUTO_ROT", 35, Compass, _rotate_auto, HAL_COMPASS_AUTO_ROT_DEFAULT),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user