mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: compass learn off by default
This commit is contained in:
parent
00dc9712de
commit
b8974dec99
@ -973,6 +973,11 @@ static void load_parameters(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
// setup different Compass learn setting for ArduCopter than the default
|
||||
// but allow users to override in their config
|
||||
if (!compass._learn.load()) {
|
||||
compass._learn.set_and_save(0);
|
||||
}
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
|
@ -190,11 +190,13 @@ public:
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
// settable parameters
|
||||
AP_Int8 _learn; ///<enable calibration learning
|
||||
|
||||
protected:
|
||||
enum Rotation _orientation;
|
||||
AP_Vector3f _offset;
|
||||
AP_Float _declination;
|
||||
AP_Int8 _learn; ///<enable calibration learning
|
||||
AP_Int8 _use_for_yaw; ///<enable use for yaw calculation
|
||||
AP_Int8 _auto_declination; ///<enable automatic declination code
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user