mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: fixed zero compass diagonals
this fixes a regression from 4.2 to 4.3. previously we automatically set the diagnoals to 1,1,1 if they were 0,0,0. We don't do that any more. I was helping a user who had copied an old config with 0,0,0 for diagonals and did not understand two things: - the compass did not work in 4.3 - large vehicle mag cal didn't work
This commit is contained in:
parent
6d117528e4
commit
4d002e5895
|
@ -87,13 +87,15 @@ void AP_Compass_Backend::correct_field(Vector3f &mag, uint8_t i)
|
|||
}
|
||||
|
||||
// apply eliptical correction
|
||||
Matrix3f mat(
|
||||
diagonals.x, offdiagonals.x, offdiagonals.y,
|
||||
offdiagonals.x, diagonals.y, offdiagonals.z,
|
||||
offdiagonals.y, offdiagonals.z, diagonals.z
|
||||
);
|
||||
if (!diagonals.is_zero()) {
|
||||
Matrix3f mat(
|
||||
diagonals.x, offdiagonals.x, offdiagonals.y,
|
||||
offdiagonals.x, diagonals.y, offdiagonals.z,
|
||||
offdiagonals.y, offdiagonals.z, diagonals.z
|
||||
);
|
||||
|
||||
mag = mat * mag;
|
||||
mag = mat * mag;
|
||||
}
|
||||
|
||||
#if COMPASS_MOT_ENABLED
|
||||
const Vector3f &mot = state.motor_compensation.get();
|
||||
|
|
|
@ -450,22 +450,25 @@ bool Compass::get_uncorrected_field(uint8_t instance, Vector3f &field) const
|
|||
// form eliptical correction matrix and invert it. This is
|
||||
// needed to remove the effects of the eliptical correction
|
||||
// when calculating new offsets
|
||||
const Vector3f &diagonals = get_diagonals(instance);
|
||||
const Vector3f &offdiagonals = get_offdiagonals(instance);
|
||||
Matrix3f mat {
|
||||
diagonals.x, offdiagonals.x, offdiagonals.y,
|
||||
offdiagonals.x, diagonals.y, offdiagonals.z,
|
||||
offdiagonals.y, offdiagonals.z, diagonals.z
|
||||
};
|
||||
if (!mat.invert()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// get corrected field
|
||||
field = get_field(instance);
|
||||
|
||||
// remove impact of diagonals and off-diagonals
|
||||
field = mat * field;
|
||||
const Vector3f &diagonals = get_diagonals(instance);
|
||||
if (!diagonals.is_zero()) {
|
||||
const Vector3f &offdiagonals = get_offdiagonals(instance);
|
||||
Matrix3f mat {
|
||||
diagonals.x, offdiagonals.x, offdiagonals.y,
|
||||
offdiagonals.x, diagonals.y, offdiagonals.z,
|
||||
offdiagonals.y, offdiagonals.z, diagonals.z
|
||||
};
|
||||
if (!mat.invert()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// remove impact of diagonals and off-diagonals
|
||||
field = mat * field;
|
||||
}
|
||||
|
||||
// remove impact of offsets
|
||||
field -= get_offsets(instance);
|
||||
|
|
Loading…
Reference in New Issue