Copter: move automatic declination setting into AP_Compass itself

This commit is contained in:
Peter Barker 2019-03-27 18:02:01 +11:00 committed by Andrew Tridgell
parent 2428487383
commit 4fa83ed40d
3 changed files with 0 additions and 19 deletions

View File

@ -454,9 +454,6 @@ void Copter::one_hz_loop()
// indicates that the sensor or subsystem is present but not
// functioning correctly
gcs().update_sensor_status_flags();
// init compass location for declination
init_compass_location();
}
// called at 50hz

View File

@ -825,7 +825,6 @@ private:
void read_rangefinder(void);
bool rangefinder_alt_ok();
void rpm_update();
void init_compass_location();
void init_optflow();
void update_optical_flow(void);
void compass_cal_update(void);

View File

@ -85,21 +85,6 @@ void Copter::rpm_update(void)
#endif
}
/*
initialise compass's location used for declination
*/
void Copter::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
void Copter::init_optflow()
{