mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: limit rotations we try to ROTATION_MAX_AUTO_ROTATION
This commit is contained in:
parent
f908e56154
commit
270844745f
|
@ -823,9 +823,9 @@ bool CompassCalibrator::calculate_orientation(void)
|
|||
// this function is very slow
|
||||
EXPECT_DELAY_MS(1000);
|
||||
|
||||
float variance[ROTATION_MAX] {};
|
||||
float variance[ROTATION_MAX_AUTO_ROTATION+1] {};
|
||||
|
||||
for (enum Rotation r = ROTATION_NONE; r<ROTATION_MAX; r = (enum Rotation)(r+1)) {
|
||||
for (enum Rotation r = ROTATION_NONE; r <= ROTATION_MAX_AUTO_ROTATION; r = (enum Rotation)(r+1)) {
|
||||
// calculate the average implied earth field across all samples
|
||||
Vector3f total_ef {};
|
||||
for (uint32_t i=0; i<_samples_collected; i++) {
|
||||
|
@ -846,7 +846,7 @@ bool CompassCalibrator::calculate_orientation(void)
|
|||
// find the rotation with the lowest variance
|
||||
enum Rotation besti = ROTATION_NONE;
|
||||
float bestv = variance[0];
|
||||
for (enum Rotation r = ROTATION_NONE; r<ROTATION_MAX; r = (enum Rotation)(r+1)) {
|
||||
for (enum Rotation r = ROTATION_NONE; r <= ROTATION_MAX_AUTO_ROTATION; r = (enum Rotation)(r+1)) {
|
||||
if (variance[r] < bestv) {
|
||||
bestv = variance[r];
|
||||
besti = r;
|
||||
|
@ -859,7 +859,7 @@ bool CompassCalibrator::calculate_orientation(void)
|
|||
|
||||
float second_best = besti==ROTATION_NONE?variance[1]:variance[0];
|
||||
enum Rotation besti2 = ROTATION_NONE;
|
||||
for (enum Rotation r = ROTATION_NONE; r<ROTATION_MAX; r = (enum Rotation)(r+1)) {
|
||||
for (enum Rotation r = ROTATION_NONE; r <= ROTATION_MAX_AUTO_ROTATION; r = (enum Rotation)(r+1)) {
|
||||
if (!rotation_equal(besti, r)) {
|
||||
if (variance[r] < second_best) {
|
||||
second_best = variance[r];
|
||||
|
|
Loading…
Reference in New Issue