AP_NavEKF2: 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:
priseborough 2017-02-15 10:36:07 +11:00 committed by Francisco Ferreira
parent 8c7b214d71
commit a1d41edc4e

View File

@ -45,11 +45,6 @@ void NavEKF2_core::controlFilterModes()
*/
uint8_t NavEKF2_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;
}