mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 02:58:31 -04:00
AP_Compass: never override custom orentation in calabration
This commit is contained in:
parent
be2e75f8db
commit
1771481779
@ -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);
|
||||
}
|
||||
|
||||
|
@ -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
|
||||
|
@ -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…
Reference in New Issue
Block a user