Use existing covariance prediction code to set quaternion state covariances.
Assumes tilt error is 3 deg 1-sigma.
TODO derive and add function that calculates tilt error variance.
we need to reset the body mag variances if we change sensors or if we
are starting 3D fusion. When not doing 3D fusion we zero the
variances, so they must be initialised again when we restart
fusion. This fixes a bug in handling the variances on a 2nd flight
this allows the EKF core index to be used to select a GPS/baro/mag
instance. This is an alternative to GPS blending that allows EKF lane
switching to be used to select the right combination of GPS and IMU
add logging to XKFS message
../../libraries/AP_NavEKF2/AP_NavEKF2_core.cpp: In member function ‘void NavEKF2_core::InitialiseVariables()’:
../../libraries/AP_NavEKF2/AP_NavEKF2_core.cpp:343:50: warning: ‘void* memset(void*, int, size_t)’ clearing an object of non-trivial type ‘struct NavEKF2_core::ext_nav_vel_elements’; use assignment or value-initialization instead [-Wclass-memaccess]
343 | memset(&extNavVelNew, 0, sizeof(extNavVelNew));
| ^
In file included from ../../libraries/AP_NavEKF2/AP_NavEKF2_core.cpp:4:
../../libraries/AP_NavEKF2/AP_NavEKF2_core.h:518:12: note: ‘struct NavEKF2_core::ext_nav_vel_elements’ declared here
518 | struct ext_nav_vel_elements {
| ^~~~~~~~~~~~~~~~~~~~
../../libraries/AP_NavEKF2/AP_NavEKF2_core.cpp:344:58: warning: ‘void* memset(void*, int, size_t)’ clearing an object of non-trivial type ‘struct NavEKF2_core::ext_nav_vel_elements’; use assignment or value-initialization instead [-Wclass-memaccess]
344 | memset(&extNavVelDelayed, 0, sizeof(extNavVelDelayed));
| ^
In file included from ../../libraries/AP_NavEKF2/AP_NavEKF2_core.cpp:4:
../../libraries/AP_NavEKF2/AP_NavEKF2_core.h:518:12: note: ‘struct NavEKF2_core::ext_nav_vel_elements’ declared here
518 | struct ext_nav_vel_elements {
| ^~~~~~~~~~~~~~~~~~~~