mirror of https://github.com/ArduPilot/ardupilot
parent
eb2aa80fca
commit
a07920c5b2
|
@ -415,6 +415,7 @@ private:
|
|||
void update_trigger(void);
|
||||
void update_alt();
|
||||
void gcs_failsafe_check(void);
|
||||
void init_compass(void);
|
||||
void compass_accumulate(void);
|
||||
void compass_cal_update(void);
|
||||
void update_compass(void);
|
||||
|
|
|
@ -1,5 +1,20 @@
|
|||
#include "Rover.h"
|
||||
|
||||
// initialise compass
|
||||
void Rover::init_compass()
|
||||
{
|
||||
if (!g.compass_enabled) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!compass.init()|| !compass.read()) {
|
||||
cliSerial->printf("Compass initialisation failed!\n");
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
ahrs.set_compass(&compass);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
if the compass is enabled then try to accumulate a reading
|
||||
also update initial location used for declination
|
||||
|
|
|
@ -145,15 +145,8 @@ void Rover::init_ardupilot()
|
|||
log_init();
|
||||
#endif
|
||||
|
||||
if (g.compass_enabled == true) {
|
||||
if (!compass.init()|| !compass.read()) {
|
||||
cliSerial->printf("Compass initialisation failed!\n");
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
ahrs.set_compass(&compass);
|
||||
// compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||
}
|
||||
}
|
||||
// initialise compass
|
||||
init_compass();
|
||||
|
||||
// initialise sonar
|
||||
init_sonar();
|
||||
|
|
Loading…
Reference in New Issue