From 346e9e36db46b4e01cf38dedee91ccb4ab4c7901 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 2 Aug 2018 12:19:50 +0900 Subject: [PATCH] Copter: remove compass accumulate --- ArduCopter/ArduCopter.cpp | 4 +++- ArduCopter/Copter.h | 2 +- ArduCopter/compassmot.cpp | 2 -- ArduCopter/sensors.cpp | 11 ++--------- 4 files changed, 6 insertions(+), 13 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 2a0732664e..ca2b8de545 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -117,7 +117,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #endif SCHED_TASK(three_hz_loop, 3, 75), SCHED_TASK_CLASS(AP_ServoRelayEvents, &copter.ServoRelayEvents, update_events, 50, 75), - SCHED_TASK(compass_accumulate, 100, 100), SCHED_TASK_CLASS(AP_Baro, &copter.barometer, accumulate, 50, 90), #if PRECISION_LANDING == ENABLED SCHED_TASK(update_precland, 400, 50), @@ -456,6 +455,9 @@ void Copter::one_hz_loop() // indicates that the sensor or subsystem is present but not // functioning correctly update_sensor_status_flags(); + + // init compass location for declination + init_compass_location(); } // called at 50hz diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index d8b497b9a9..03fd54c1d2 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -862,7 +862,7 @@ private: bool rangefinder_alt_ok(); void rpm_update(); void init_compass(); - void compass_accumulate(void); + void init_compass_location(); void init_optflow(); void update_optical_flow(void); void compass_cal_update(void); diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index b020df599e..3f2a5e2cfa 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -137,8 +137,6 @@ MAV_RESULT Copter::mavlink_compassmot(mavlink_channel_t chan) while (command_ack_start == command_ack_counter && compass.healthy() && motors->armed()) { // 50hz loop if (millis() - last_run_time < 20) { - // grab some compass values - compass.accumulate(); hal.scheduler->delay(5); continue; } diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 8b08dbf689..967a50e132 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -102,17 +102,10 @@ void Copter::init_compass() } /* - if the compass is enabled then try to accumulate a reading - also update initial location used for declination + initialise compass's location used for declination */ -void Copter::compass_accumulate(void) +void Copter::init_compass_location() { - if (!g.compass_enabled) { - return; - } - - compass.accumulate(); - // update initial location used for declination if (!ap.compass_init_location) { Location loc;