mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: use AP::compass().available in place of enabled()
This commit is contained in:
parent
d5ea202c20
commit
d40587062e
|
@ -151,7 +151,7 @@ void AP_Periph_FW::init()
|
|||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_MAG
|
||||
if (compass.enabled()) {
|
||||
if (compass.available()) {
|
||||
compass.init();
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -1480,7 +1480,7 @@ void AP_Periph_FW::can_update()
|
|||
void AP_Periph_FW::can_mag_update(void)
|
||||
{
|
||||
#ifdef HAL_PERIPH_ENABLE_MAG
|
||||
if (!compass.enabled()) {
|
||||
if (!compass.available()) {
|
||||
return;
|
||||
}
|
||||
compass.read();
|
||||
|
|
Loading…
Reference in New Issue