mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Suppress clearing non-trival type warning
This commit is contained in:
parent
29db069c75
commit
25ef5fed82
|
@ -709,7 +709,7 @@ bool NavEKF3::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;
|
||||
|
@ -174,7 +174,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
|
||||
|
|
|
@ -303,8 +303,8 @@ void NavEKF3_core::InitialiseVariables()
|
|||
velResetSource = DEFAULT;
|
||||
|
||||
// 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;
|
||||
|
@ -342,8 +342,8 @@ void NavEKF3_core::InitialiseVariables()
|
|||
bcnOriginEstInit = false;
|
||||
|
||||
// body frame displacement fusion
|
||||
memset(&bodyOdmDataNew, 0, sizeof(bodyOdmDataNew));
|
||||
memset(&bodyOdmDataDelayed, 0, sizeof(bodyOdmDataDelayed));
|
||||
memset((void *)&bodyOdmDataNew, 0, sizeof(bodyOdmDataNew));
|
||||
memset((void *)&bodyOdmDataDelayed, 0, sizeof(bodyOdmDataDelayed));
|
||||
lastbodyVelPassTime_ms = 0;
|
||||
memset(&bodyVelTestRatio, 0, sizeof(bodyVelTestRatio));
|
||||
memset(&varInnovBodyVel, 0, sizeof(varInnovBodyVel));
|
||||
|
|
Loading…
Reference in New Issue