mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Use the same mag fusion method for all cores
The original reason for using a different method for the second core is no longer valid.
This commit is contained in:
parent
a1d41edc4e
commit
ccb952ba31
|
@ -45,11 +45,6 @@ void NavEKF3_core::controlFilterModes()
|
|||
*/
|
||||
uint8_t NavEKF3_core::effective_magCal(void) const
|
||||
{
|
||||
// if we are on the 2nd core and _magCal is 3 then treat it as
|
||||
// 2. This is a workaround for a mag fusion problem
|
||||
if (frontend->_magCal ==3 && imu_index == 1) {
|
||||
return 2;
|
||||
}
|
||||
return frontend->_magCal;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue