mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Sub: enable in-flight compass learning
This commit is contained in:
parent
de58fb4637
commit
a8f5079df9
@ -291,6 +291,10 @@ void Sub::one_hz_loop()
|
|||||||
|
|
||||||
// init compass location for declination
|
// init compass location for declination
|
||||||
init_compass_location();
|
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());
|
||||||
}
|
}
|
||||||
|
|
||||||
// called at 50hz
|
// called at 50hz
|
||||||
|
Loading…
Reference in New Issue
Block a user