From 03e60653806755a6c7aae36bfeb6a3750ed0e900 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 27 Mar 2019 18:02:24 +1100 Subject: [PATCH] Sub: move automatic declination setting into AP_Compass itself --- ArduSub/ArduSub.cpp | 3 --- ArduSub/Sub.h | 1 - ArduSub/sensors.cpp | 15 --------------- 3 files changed, 19 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 6cf098de28..07042491df 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -284,9 +284,6 @@ void Sub::one_hz_loop() // log terrain data terrain_logging(); - // init compass location for declination - init_compass_location(); - // need to set "likely flying" when armed to allow for compass // learning to run ahrs.set_likely_flying(hal.util->get_soft_armed()); diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index fd8962abcd..efae5a19c0 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -454,7 +454,6 @@ private: static const AP_Param::Info var_info[]; static const struct LogStructure log_structure[]; - void init_compass_location(); void fast_loop(); void fifty_hz_loop(); void update_batt_compass(void); diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index 54c2987452..830b14b3be 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -80,21 +80,6 @@ void Sub::rpm_update(void) } #endif -/* - initialise compass's location used for declination - */ -void Sub::init_compass_location() -{ - // update initial location used for declination - if (!ap.compass_init_location) { - Location loc; - if (ahrs.get_position(loc)) { - compass.set_initial_location(loc.lat, loc.lng); - ap.compass_init_location = true; - } - } -} - // initialise optical flow sensor #if OPTFLOW == ENABLED void Sub::init_optflow()