Tracker: factor out compass functions

This commit is contained in:
IamPete1 2019-02-08 19:22:08 +00:00 committed by Peter Barker
parent ed5fc06a5d
commit 1bade761a1
4 changed files with 50 additions and 11 deletions

View File

@ -101,12 +101,13 @@ void Tracker::one_second_loop()
one_second_counter++; one_second_counter++;
if (one_second_counter >= 60) { if (one_second_counter >= 60) {
if (g.compass_enabled) { compass_save();
compass.save_offsets();
}
one_second_counter = 0; one_second_counter = 0;
} }
// init compass location for declination
init_compass_location();
if (!ahrs.home_is_set()) { if (!ahrs.home_is_set()) {
// set home to current location // set home to current location
Location temp_loc; Location temp_loc;

View File

@ -193,6 +193,9 @@ private:
static const AP_Param::Info var_info[]; static const AP_Param::Info var_info[];
static const struct LogStructure log_structure[]; static const struct LogStructure log_structure[];
// true if the compass's initial location has been set
bool compass_init_location;
// AntennaTracker.cpp // AntennaTracker.cpp
void one_second_loop(); void one_second_loop();
void ten_hz_logging_loop(); void ten_hz_logging_loop();
@ -231,6 +234,9 @@ private:
// sensors.cpp // sensors.cpp
void update_ahrs(); void update_ahrs();
void init_compass();
void compass_save();
void init_compass_location();
void update_compass(void); void update_compass(void);
void compass_cal_update(); void compass_cal_update();
void accel_cal_update(void); void accel_cal_update(void);

View File

@ -8,6 +8,35 @@ void Tracker::update_ahrs()
ahrs.update(); ahrs.update();
} }
// initialise compass
void Tracker::init_compass()
{
if (!g.compass_enabled) {
return;
}
if (!compass.init()|| !compass.read()) {
hal.console->printf("Compass initialisation failed!\n");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
}
}
/*
initialise compass's location used for declination
*/
void Tracker::init_compass_location(void)
{
// update initial location used for declination
if (!compass_init_location) {
Location loc;
if (ahrs.get_position(loc)) {
compass.set_initial_location(loc.lat, loc.lng);
compass_init_location = true;
}
}
}
/* /*
read and update compass read and update compass
@ -31,6 +60,15 @@ void Tracker::compass_cal_update() {
} }
} }
// Save compass offsets
void Tracker::compass_save() {
if (g.compass_enabled &&
compass.get_learn_type() >= Compass::LEARN_INTERNAL &&
!hal.util->get_soft_armed()) {
compass.save_offsets();
}
}
/* /*
Accel calibration Accel calibration
*/ */

View File

@ -53,14 +53,8 @@ void Tracker::init_tracker()
log_init(); log_init();
#endif #endif
if (g.compass_enabled==true) { // initialise compass
if (!compass.init() || !compass.read()) { init_compass();
hal.console->printf("Compass initialisation failed!\n");
g.compass_enabled = false;
} else {
ahrs.set_compass(&compass);
}
}
// GPS Initialization // GPS Initialization
gps.set_log_gps_bit(MASK_LOG_GPS); gps.set_log_gps_bit(MASK_LOG_GPS);