mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: wheelOdmDataNew member made local
this variable is never used outside the writeWheelOdom method
This commit is contained in:
parent
3d5161f364
commit
056a2de260
|
@ -162,6 +162,7 @@ void NavEKF3_core::writeWheelOdom(float delAng, float delTime, uint32_t timeStam
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
wheel_odm_elements wheelOdmDataNew = {};
|
||||||
wheelOdmDataNew.hub_offset = &posOffset;
|
wheelOdmDataNew.hub_offset = &posOffset;
|
||||||
wheelOdmDataNew.delAng = delAng;
|
wheelOdmDataNew.delAng = delAng;
|
||||||
wheelOdmDataNew.radius = radius;
|
wheelOdmDataNew.radius = radius;
|
||||||
|
|
|
@ -1262,7 +1262,6 @@ private:
|
||||||
// wheel sensor fusion
|
// wheel sensor fusion
|
||||||
uint32_t wheelOdmMeasTime_ms; // time wheel odometry measurements were accepted for input to the data buffer (msec)
|
uint32_t wheelOdmMeasTime_ms; // time wheel odometry measurements were accepted for input to the data buffer (msec)
|
||||||
obs_ring_buffer_t<wheel_odm_elements> storedWheelOdm; // body velocity data buffer
|
obs_ring_buffer_t<wheel_odm_elements> storedWheelOdm; // body velocity data buffer
|
||||||
wheel_odm_elements wheelOdmDataNew; // Body frame odometry data at the current time horizon
|
|
||||||
wheel_odm_elements wheelOdmDataDelayed; // Body frame odometry data at the fusion time horizon
|
wheel_odm_elements wheelOdmDataDelayed; // Body frame odometry data at the fusion time horizon
|
||||||
|
|
||||||
// yaw sensor fusion
|
// yaw sensor fusion
|
||||||
|
|
Loading…
Reference in New Issue