Browse Source

APM: enable the new offset nulling in APM

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
989304fb47
  1. 2
      ArduPlane/ArduPlane.pde
  2. 2
      ArduPlane/test.pde

2
ArduPlane/ArduPlane.pde

@ -784,7 +784,7 @@ static void medium_loop() @@ -784,7 +784,7 @@ static void medium_loop()
// Calculate heading
Matrix3f m = ahrs.get_dcm_matrix();
compass.calculate(m);
compass.null_offsets(m);
compass.null_offsets();
} else {
ahrs.set_compass(NULL);
}

2
ArduPlane/test.pde

@ -603,7 +603,7 @@ test_mag(uint8_t argc, const Menu::arg *argv) @@ -603,7 +603,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
// Calculate heading
Matrix3f m = ahrs.get_dcm_matrix();
compass.calculate(m);
compass.null_offsets(m);
compass.null_offsets();
}
medium_loopCounter = 0;
}

Loading…
Cancel
Save