mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: fixed build with g++ 9.1
this is a false positive, but the cost of clearing this array is low, and it saves a much more complex fix
This commit is contained in:
parent
36ac689838
commit
de12430977
|
@ -1040,7 +1040,7 @@ void NavEKF2_core::FuseDeclination(float declErr)
|
|||
float t12 = 1.0f/t11;
|
||||
|
||||
float H_MAG[24];
|
||||
Vector28 Kfusion;
|
||||
Vector28 Kfusion {};
|
||||
|
||||
H_MAG[16] = -magE*t5;
|
||||
H_MAG[17] = magN*t5;
|
||||
|
|
|
@ -285,7 +285,7 @@ void NavEKF2_core::FuseOptFlow()
|
|||
Vector3f relVelSensor;
|
||||
Vector14 SH_LOS;
|
||||
Vector2 losPred;
|
||||
Vector28 Kfusion;
|
||||
Vector28 Kfusion {};
|
||||
|
||||
// Copy required states to local variable names
|
||||
float q0 = stateStruct.quat[0];
|
||||
|
|
Loading…
Reference in New Issue