Browse Source

AP_Compass: never override custom orentation in calabration

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
1771481779
  1. 2
      libraries/AP_Compass/AP_Compass_Calibration.cpp
  2. 1
      libraries/AP_Compass/CompassCalibrator.cpp
  3. 1
      libraries/AP_Compass/CompassCalibrator.h

2
libraries/AP_Compass/AP_Compass_Calibration.cpp

@ -207,7 +207,7 @@ bool Compass::_accept_calibration(uint8_t i) @@ -207,7 +207,7 @@ bool Compass::_accept_calibration(uint8_t i)
set_and_save_offdiagonals(i,offdiag);
set_and_save_scale_factor(i,scale_factor);
if (_get_state(prio).external && _rotate_auto >= 2) {
if (cal_report.check_orientation && _get_state(prio).external && _rotate_auto >= 2) {
set_and_save_orientation(i, cal_report.orientation);
}

1
libraries/AP_Compass/CompassCalibrator.cpp

@ -324,6 +324,7 @@ void CompassCalibrator::update_cal_report() @@ -324,6 +324,7 @@ void CompassCalibrator::update_cal_report()
cal_report.orientation_confidence = _orientation_confidence;
cal_report.original_orientation = _orig_orientation;
cal_report.orientation = _orientation_solution;
cal_report.check_orientation = _check_orientation;
}
// running method for use in thread

1
libraries/AP_Compass/CompassCalibrator.h

@ -67,6 +67,7 @@ public: @@ -67,6 +67,7 @@ public:
Rotation original_orientation;
Rotation orientation;
float scale_factor;
bool check_orientation;
} cal_report;
// Structure setup to set calibration run settings

Loading…
Cancel
Save