ekf_localization_node system model when fusing IMU and Odometry
Hello,
I have found this great tutorial about Extended Kalman filter which made me wonder how does ekf_localization_node in ROS work (I found a similar question asked before, however it was not answered).
Firstly, Id like to understand model system of my robot (in this case, I am using Jackal robot which is originally a tank-like robot. However, with the help of teb_local_planner it was possible to limit the minimum turning radius and make it move more like a car. The purpose of ekf_localization_node in my case is just to fuse Odometry and IMU data, but how does it work? What is my system model in this case?
One more question regarding ekf_localization_node. I have read that EKF (in general) is capable of adding bias of a sensor. I havent found a parameter in the wiki regarding it. How does one smoothen sensor measurement noise then?
I have read couple of papers regarding model system, or in this case motion system (since its odometry?).
Is this what I am using? Am I looking the right way?
Clearly, I am a noobie here so any help is appreciated!
EDIT One more question. So I know my current kinematic model, but what is my system's observation model then? When I look at the code, I am focusing at this area (lines 109-144) where it builds the measurement matrices but how? What does it use to build it?
for (size_t i = 0; i < updateSize; ++i)
{
measurementSubset(i) = measurement.measurement_(updateIndices[i]);
stateSubset(i) = state_(updateIndices[i]);
for (size_t j = 0; j < updateSize; ++j)
{
measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]);
}
// Handle negative (read: bad) covariances in the measurement. Rather
// than exclude the measurement or make up a covariance, just take
// the absolute value.
if (measurementCovarianceSubset(i, i) < 0)
{
FB_DEBUG("WARNING: Negative covariance for index " << i <<
" of measurement (value is" << measurementCovarianceSubset(i, i) <<
"). Using absolute value...\n");
measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i));
}
// If the measurement variance for a given variable is very
// near 0 (as in e-50 or so) and the variance for that
// variable in the covariance matrix is also near zero, then
// the Kalman gain computation will blow up. Really, no
// measurement can be completely without error, so add a small
// amount in that case.
if (measurementCovarianceSubset(i, i) < 1e-9)
{
FB_DEBUG("WARNING: measurement had very small error covariance for index " << updateIndices[i] <<
". Adding some noise to maintain filter stability.\n");
measurementCovarianceSubset(i, i) = 1e-9;
}
}