mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Arming: Primary Compass is always at serial# 0
This commit is contained in:
parent
b5cf1ecfe1
commit
653fad44d4
@ -389,7 +389,7 @@ bool AP_Arming::compass_checks(bool report)
|
||||
|
||||
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can
|
||||
// incorrectly skip the remaining checks, pass the primary instance directly
|
||||
if (!_compass.use_for_yaw(_compass.get_primary())) {
|
||||
if (!_compass.use_for_yaw(0)) {
|
||||
// compass use is disabled
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user