AP_Compass: use rotation_equal() from AP_Compass

This commit is contained in:
Andrew Tridgell 2018-10-01 13:04:27 +10:00 committed by Randy Mackay
parent e90e89b687
commit 1fd5017fab
2 changed files with 0 additions and 18 deletions

View File

@ -768,23 +768,6 @@ Vector3f CompassCalibrator::calculate_earth_field(CompassSample &sample, enum Ro
return efield;
}
/*
return true if two rotations are equivalent
This copes with the fact that we have some duplicates, like ROLL_180_YAW_90 and PITCH_180_YAW_270
*/
bool CompassCalibrator::rotation_equal(enum Rotation r1, enum Rotation r2) const
{
if (r1 == r2) {
return true;
}
Vector3f v(1,2,3);
Vector3f v1 = v;
Vector3f v2 = v;
v1.rotate(r1);
v2.rotate(r2);
return (v1 - v2).length() < 0.001;
}
/*
calculate compass orientation using the attitude estimate associated
with each sample, and fix orientation on external compasses if

View File

@ -171,5 +171,4 @@ private:
Vector3f calculate_earth_field(CompassSample &sample, enum Rotation r);
bool calculate_orientation();
bool rotation_equal(enum Rotation r1, enum Rotation r2) const;
};