mirror of https://github.com/ArduPilot/ardupilot
Copter: init_compass get g.compass_enabled check
No functional change
This commit is contained in:
parent
ac8234cdf0
commit
ec491d3c6b
|
@ -100,6 +100,10 @@ void Copter::rpm_update(void)
|
|||
// initialise compass
|
||||
void Copter::init_compass()
|
||||
{
|
||||
if (!g.compass_enabled) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (!compass.init() || !compass.read()) {
|
||||
// make sure we don't pass a broken compass to DCM
|
||||
cliSerial->printf("COMPASS INIT ERROR\n");
|
||||
|
|
|
@ -207,8 +207,7 @@ void Copter::init_ardupilot()
|
|||
// Do GPS init
|
||||
gps.init(&DataFlash, serial_manager);
|
||||
|
||||
if(g.compass_enabled)
|
||||
init_compass();
|
||||
init_compass();
|
||||
|
||||
#if OPTFLOW == ENABLED
|
||||
// make optflow available to AHRS
|
||||
|
|
Loading…
Reference in New Issue