Browse Source

Copter: change to Compass::learn_offsets

master
Andrew Tridgell 11 years ago
parent
commit
9c66dd0d2c
  1. 2
      ArduCopter/ArduCopter.pde
  2. 2
      ArduCopter/test.pde

2
ArduCopter/ArduCopter.pde

@ -1066,7 +1066,7 @@ static void update_batt_compass(void) @@ -1066,7 +1066,7 @@ static void update_batt_compass(void)
// update compass with throttle value - used for compassmot
compass.set_throttle((float)g.rc_3.servo_out/1000.0f);
if (compass.read()) {
compass.null_offsets();
compass.learn_offsets();
}
// log compass information
if (g.log_bitmask & MASK_LOG_COMPASS) {

2
ArduCopter/test.pde

@ -136,7 +136,7 @@ test_compass(uint8_t argc, const Menu::arg *argv) @@ -136,7 +136,7 @@ test_compass(uint8_t argc, const Menu::arg *argv)
// Calculate heading
const Matrix3f &m = ahrs.get_dcm_matrix();
heading = compass.calculate_heading(m);
compass.null_offsets();
compass.learn_offsets();
}
medium_loopCounter = 0;
}

Loading…
Cancel
Save