AP_Compass: never override custom orentation in calabration

This commit is contained in:
Iampete1 2021-11-03 11:28:41 +00:00 committed by Randy Mackay
parent d59caa95ad
commit ad9c411490
3 changed files with 3 additions and 1 deletions

View File

@ -200,7 +200,7 @@ bool Compass::_accept_calibration(uint8_t i)
set_and_save_offdiagonals(i,offdiag); set_and_save_offdiagonals(i,offdiag);
set_and_save_scale_factor(i,scale_factor); 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); set_and_save_orientation(i, cal_report.orientation);
} }

View File

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

View File

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