AP_Compass: use rotation_equal() from AP_Compass
This commit is contained in:
parent
d4eaf09baf
commit
2f2be6afda
@ -768,23 +768,6 @@ Vector3f CompassCalibrator::calculate_earth_field(CompassSample &sample, enum Ro
|
|||||||
return efield;
|
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
|
calculate compass orientation using the attitude estimate associated
|
||||||
with each sample, and fix orientation on external compasses if
|
with each sample, and fix orientation on external compasses if
|
||||||
|
@ -171,5 +171,4 @@ private:
|
|||||||
|
|
||||||
Vector3f calculate_earth_field(CompassSample &sample, enum Rotation r);
|
Vector3f calculate_earth_field(CompassSample &sample, enum Rotation r);
|
||||||
bool calculate_orientation();
|
bool calculate_orientation();
|
||||||
bool rotation_equal(enum Rotation r1, enum Rotation r2) const;
|
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user