mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_NavEKF2: Prevent return of uninitialised variable
This commit is contained in:
parent
3d8e74df26
commit
e33aa7898a
@ -689,6 +689,8 @@ uint8_t NavEKF2::getActiveMag(int8_t instance)
|
||||
if (instance < 0 || instance >= num_cores) instance = primary;
|
||||
if (core) {
|
||||
return core[instance].getActiveMag();
|
||||
} else {
|
||||
return 255;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user