mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
Rover: use AP::compass().available in place of enabled()
This commit is contained in:
parent
3e13790039
commit
ffd577f30b
@ -10,7 +10,7 @@ void Rover::update_compass(void)
|
|||||||
|
|
||||||
// Save compass offsets
|
// Save compass offsets
|
||||||
void Rover::compass_save() {
|
void Rover::compass_save() {
|
||||||
if (AP::compass().enabled() &&
|
if (AP::compass().available() &&
|
||||||
compass.get_learn_type() >= Compass::LEARN_INTERNAL &&
|
compass.get_learn_type() >= Compass::LEARN_INTERNAL &&
|
||||||
!arming.is_armed()) {
|
!arming.is_armed()) {
|
||||||
compass.save_offsets();
|
compass.save_offsets();
|
||||||
|
Loading…
Reference in New Issue
Block a user