mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Clean up initialisation of boolean array
This commit is contained in:
parent
b0763f04f1
commit
ac92182153
|
@ -595,7 +595,7 @@ void NavEKF3_core::FuseVelPosNED()
|
|||
bool hgtCheckPassed = false; // boolean true if height measurements have passed innovation consistency check
|
||||
|
||||
// declare variables used to control access to arrays
|
||||
bool fuseData[6] = {false,false,false,false,false,false};
|
||||
bool fuseData[6] {};
|
||||
uint8_t stateIndex;
|
||||
uint8_t obsIndex;
|
||||
|
||||
|
|
Loading…
Reference in New Issue