Skip to content

Commit

Permalink
Sub: remove compass accumulate
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 authored and tridge committed Aug 6, 2018
1 parent 903d00c commit 54df7ad
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 11 deletions.
4 changes: 3 additions & 1 deletion ArduSub/ArduSub.cpp
Expand Up @@ -35,7 +35,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(update_altitude, 10, 100),
SCHED_TASK(three_hz_loop, 3, 75),
SCHED_TASK(update_turn_counter, 10, 50),
SCHED_TASK(compass_accumulate, 100, 100),
SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90),
SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90),
SCHED_TASK(one_hz_loop, 1, 100),
Expand Down Expand Up @@ -289,6 +288,9 @@ void Sub::one_hz_loop()

// log terrain data
terrain_logging();

// init compass location for declination
init_compass_location();
}

// called at 50hz
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/Sub.h
Expand Up @@ -456,7 +456,7 @@ class Sub : public AP_HAL::HAL::Callbacks {
static const AP_Param::Info var_info[];
static const struct LogStructure log_structure[];

void compass_accumulate(void);
void init_compass_location();
void compass_cal_update(void);
void fast_loop();
void fifty_hz_loop();
Expand Down
11 changes: 2 additions & 9 deletions ArduSub/sensors.cpp
Expand Up @@ -93,17 +93,10 @@ void Sub::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 Sub::compass_accumulate()
void Sub::init_compass_location()
{
if (!g.compass_enabled) {
return;
}

compass.accumulate();

// update initial location used for declination
if (!ap.compass_init_location) {
Location loc;
Expand Down

0 comments on commit 54df7ad

Please sign in to comment.