mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Compass: configured() only checks compasses with _USE set
This commit is contained in:
parent
2864d58474
commit
de600ca3da
@ -685,7 +685,7 @@ bool Compass::configured(void)
|
||||
{
|
||||
bool all_configured = true;
|
||||
for(uint8_t i=0; i<get_count(); i++) {
|
||||
all_configured = all_configured && configured(i);
|
||||
all_configured = all_configured && (!use_for_yaw(i) || configured(i));
|
||||
}
|
||||
return all_configured;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user