mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_NavEKF3: avoid build warnings with g++ 9
This commit is contained in:
parent
3e853344f3
commit
5350ea5c58
@ -950,6 +950,8 @@ void NavEKF3_core::writeExtNavData(const Vector3f &pos, const Quaternion &quat,
|
||||
extNavMeasTime_ms = timeStamp_ms;
|
||||
}
|
||||
|
||||
ext_nav_elements extNavDataNew {};
|
||||
|
||||
if (resetTime_ms != extNavLastPosResetTime_ms) {
|
||||
extNavDataNew.posReset = true;
|
||||
extNavLastPosResetTime_ms = resetTime_ms;
|
||||
|
@ -395,8 +395,7 @@ void NavEKF3_core::InitialiseVariables()
|
||||
memset(&yawAngDataDelayed, 0, sizeof(yawAngDataDelayed));
|
||||
|
||||
// external nav data fusion
|
||||
memset(&extNavDataNew, 0, sizeof(extNavDataNew));
|
||||
memset(&extNavDataDelayed, 0, sizeof(extNavDataDelayed));
|
||||
extNavDataDelayed = {};
|
||||
extNavMeasTime_ms = 0;
|
||||
extNavLastPosResetTime_ms = 0;
|
||||
lastExtNavPassTime_ms = 0;
|
||||
|
@ -1329,7 +1329,6 @@ private:
|
||||
|
||||
// external navigation fusion
|
||||
obs_ring_buffer_t<ext_nav_elements> storedExtNav; // external navigation data buffer
|
||||
ext_nav_elements extNavDataNew; // External nav data at the current time horizon
|
||||
ext_nav_elements extNavDataDelayed; // External nav at the fusion time horizon
|
||||
uint32_t extNavMeasTime_ms; // time external measurements were accepted for input to the data buffer (msec)
|
||||
uint32_t extNavLastPosResetTime_ms; // last time the external nav systen performed a position reset (msec)
|
||||
|
Loading…
Reference in New Issue
Block a user