Browse Source

ACM: use compass.accumulate() in ArduCopter

this gives us a much less noisy magnetometer
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
f97104b435
  1. 7
      ArduCopter/ArduCopter.pde

7
ArduCopter/ArduCopter.pde

@ -981,6 +981,7 @@ void setup() { @@ -981,6 +981,7 @@ void setup() {
void loop()
{
uint32_t timer = micros();
bool spare_time = true;
// We want this to execute fast
// ----------------------------
@ -996,6 +997,7 @@ void loop() @@ -996,6 +997,7 @@ void loop()
// Execute the fast loop
// ---------------------
fast_loop();
spare_time = false;
} else {
#ifdef DESKTOP_BUILD
usleep(1000);
@ -1053,6 +1055,11 @@ void loop() @@ -1053,6 +1055,11 @@ void loop()
perf_mon_counter = 0;
}
//PORTK &= B10111111;
spare_time = false;
}
if (spare_time && g.compass_enabled) {
compass.accumulate();
}
}
// PORTK |= B01000000;

Loading…
Cancel
Save