mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_NavEKF2: Suppress clearing non-trival type warning
This commit is contained in:
parent
dda7c615a8
commit
29db069c75
@ -663,7 +663,7 @@ bool NavEKF2::InitialiseFilter(void)
|
||||
|
||||
// zero the structs used capture reset events
|
||||
memset(&yaw_reset_data, 0, sizeof(yaw_reset_data));
|
||||
memset(&pos_reset_data, 0, sizeof(pos_reset_data));
|
||||
memset((void *)&pos_reset_data, 0, sizeof(pos_reset_data));
|
||||
memset(&pos_down_reset_data, 0, sizeof(pos_down_reset_data));
|
||||
|
||||
check_log_write();
|
||||
|
@ -19,7 +19,7 @@ public:
|
||||
{
|
||||
return false;
|
||||
}
|
||||
memset(buffer,0,size*sizeof(element_t));
|
||||
memset((void *)buffer,0,size*sizeof(element_t));
|
||||
_size = size;
|
||||
_head = 0;
|
||||
_tail = 0;
|
||||
@ -103,7 +103,7 @@ public:
|
||||
_head = 0;
|
||||
_tail = 0;
|
||||
_new_data = false;
|
||||
memset(buffer,0,_size*sizeof(element_t));
|
||||
memset((void *)buffer,0,_size*sizeof(element_t));
|
||||
}
|
||||
|
||||
private:
|
||||
@ -130,7 +130,7 @@ public:
|
||||
{
|
||||
return false;
|
||||
}
|
||||
memset(buffer,0,size*sizeof(element_t));
|
||||
memset((void *)buffer,0,size*sizeof(element_t));
|
||||
_size = size;
|
||||
_youngest = 0;
|
||||
_oldest = 0;
|
||||
@ -173,7 +173,7 @@ public:
|
||||
inline void reset() {
|
||||
_youngest = 0;
|
||||
_oldest = 0;
|
||||
memset(buffer,0,_size*sizeof(element_t));
|
||||
memset((void *)buffer,0,_size*sizeof(element_t));
|
||||
}
|
||||
|
||||
// retrieves data from the ring buffer at a specified index
|
||||
|
@ -258,8 +258,8 @@ void NavEKF2_core::InitialiseVariables()
|
||||
memset(&velPosObs, 0, sizeof(velPosObs));
|
||||
|
||||
// range beacon fusion variables
|
||||
memset(&rngBcnDataNew, 0, sizeof(rngBcnDataNew));
|
||||
memset(&rngBcnDataDelayed, 0, sizeof(rngBcnDataDelayed));
|
||||
memset((void *)&rngBcnDataNew, 0, sizeof(rngBcnDataNew));
|
||||
memset((void *)&rngBcnDataDelayed, 0, sizeof(rngBcnDataDelayed));
|
||||
rngBcnStoreIndex = 0;
|
||||
lastRngBcnPassTime_ms = 0;
|
||||
rngBcnTestRatio = 0.0f;
|
||||
@ -297,8 +297,8 @@ void NavEKF2_core::InitialiseVariables()
|
||||
last_gps_idx = 0;
|
||||
|
||||
// external nav data fusion
|
||||
memset(&extNavDataNew, 0, sizeof(extNavDataNew));
|
||||
memset(&extNavDataDelayed, 0, sizeof(extNavDataDelayed));
|
||||
memset((void *)&extNavDataNew, 0, sizeof(extNavDataNew));
|
||||
memset((void *)&extNavDataDelayed, 0, sizeof(extNavDataDelayed));
|
||||
extNavDataToFuse = false;
|
||||
extNavMeasTime_ms = 0;
|
||||
extNavLastPosResetTime_ms = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user