Browse Source

Sub: remove compass accumulate

master
Randy Mackay 7 years ago committed by Andrew Tridgell
parent
commit
54df7ad88d
  1. 4
      ArduSub/ArduSub.cpp
  2. 2
      ArduSub/Sub.h
  3. 11
      ArduSub/sensors.cpp

4
ArduSub/ArduSub.cpp

@ -35,7 +35,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { @@ -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),
@ -289,6 +288,9 @@ void Sub::one_hz_loop() @@ -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

2
ArduSub/Sub.h

@ -456,7 +456,7 @@ private: @@ -456,7 +456,7 @@ private:
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();

11
ArduSub/sensors.cpp

@ -93,17 +93,10 @@ void Sub::init_compass() @@ -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;

Loading…
Cancel
Save