Copter: compass learn off by default

This commit is contained in:
Randy Mackay 2013-04-16 18:47:39 +09:00
parent 00dc9712de
commit b8974dec99
2 changed files with 8 additions and 1 deletions

View File

@ -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) {

View File

@ -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