AP_NavEKF3: remove unused usingWheelSensors variable
This variable was set but never consumed
This commit is contained in:
parent
c4b7a1c41a
commit
3d5161f364
@ -1804,8 +1804,6 @@ void NavEKF3_core::SelectBodyOdomFusion()
|
||||
// start performance timer
|
||||
hal.util->perf_begin(_perf_FuseBodyOdom);
|
||||
|
||||
usingWheelSensors = false;
|
||||
|
||||
// Fuse data into the main filter
|
||||
FuseBodyVel();
|
||||
|
||||
@ -1832,7 +1830,6 @@ void NavEKF3_core::SelectBodyOdomFusion()
|
||||
|
||||
// This is a hack to enable use of the existing body frame velocity fusion method
|
||||
// TODO write a dedicated observation model for wheel encoders
|
||||
usingWheelSensors = true;
|
||||
bodyOdmDataDelayed.vel = prevTnb * velNED;
|
||||
bodyOdmDataDelayed.body_offset = wheelOdmDataDelayed.hub_offset;
|
||||
bodyOdmDataDelayed.velErr = frontend->_wencOdmVelErr;
|
||||
|
@ -402,7 +402,6 @@ void NavEKF3_core::InitialiseVariables()
|
||||
bodyOdmMeasTime_ms = 0;
|
||||
bodyVelFusionDelayed = false;
|
||||
bodyVelFusionActive = false;
|
||||
usingWheelSensors = false;
|
||||
wheelOdmMeasTime_ms = 0;
|
||||
|
||||
// yaw sensor fusion
|
||||
|
@ -1261,7 +1261,6 @@ private:
|
||||
|
||||
// wheel sensor fusion
|
||||
uint32_t wheelOdmMeasTime_ms; // time wheel odometry measurements were accepted for input to the data buffer (msec)
|
||||
bool usingWheelSensors; // true when the body frame velocity fusion method should take onbservation data from the wheel odometry 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
|
||||
|
Loading…
Reference in New Issue
Block a user