mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_NavEKF2: Primary compass is always at serial number 0
This commit is contained in:
parent
7da331535c
commit
4cca1c307c
@ -359,9 +359,7 @@ void NavEKF2_core::InitialiseVariablesMag()
|
||||
|
||||
inhibitMagStates = true;
|
||||
|
||||
if (_ahrs->get_compass()) {
|
||||
magSelectIndex = _ahrs->get_compass()->get_primary();
|
||||
}
|
||||
magSelectIndex = 0;
|
||||
lastMagOffsetsValid = false;
|
||||
magStateResetRequest = false;
|
||||
magStateInitComplete = false;
|
||||
|
Loading…
Reference in New Issue
Block a user