Closed knightshrub closed 2 years ago
Hello Elia
In the Lie context, EKF and ESKF can be considered to be the same: you compute an error in the tangent space, which is the minimal space, which is the error space:
dx = K * (y - h(x) )
and then update the state with it
x = x * Exp (dx) = x (+) dx
If you overload the (+) operator with a regular +
sign, then you can write
x = x + K * ( y - h(x) )
which "looks like" standard EKF.
As per adding velocities, no problem. You have many options, but three are the main lines:
SE3 X;
Vector6d V; // Or SE3Tangent V;
You can proceed as so
Vector3d p;
SO3 R;
Vector3d v;
Vector3d w; // or SO3Tangent w;
Also, you can make use of the Rn
groups in Manif, and the Bundle
to build a composite state. Again, you have the two flavors:
X \in <SE3, R6>
X \in < R3, SO3, R3, R3>
Hello Joan, thanks for the clarification!
I'll think some more about a possible implementation for my use case. Alas, bundles don't seem to be supported by the Python bindings, but I think I can manage without them.
@knightshrub you may be interested in giving a look at kalmanif. It is a project that turns the manif filtering examples into more reusable code.
It doesn't quite support Bundle
yet, I started the integration on the feature/diff_drive
branch plus it has no Python bindings....
Hi from a different github account!
I came up with a formulation of my problem using the notation of your paper using the suggested solution of SE(2)xR3 as described in this document.
I modeled the system noise as random accelerations in the local tangent space. Does the derivation of the Jacobians for the prediction step and the update using a twist look correct? As far as I understand it, when using a compound state, the Kalman correction vector will be in the tangent space of SE(2) and R3, so I have to use (+)
for the pose update but can use regular +
for the velocity update as R3's tangent space is also R3 so in this case (+) == +
.
Looks good to me!
Only beware of the covariance of the perturbation when passing from continuous time to discrete time. Please read Appendix E in here: https://arxiv.org/pdf/1711.02508.pdf
Hello Jeremy and Joan, first of all, thank you for the great overview paper and library! It really allowed me to get a quick overview of the most important ideas behind Lie groups even though I had never heard of them before!
As someone who is quite new to robotics and state/pose estimation, I'm wondering what the motivation for using an error-state KF instead of a regular EKF is for the localization example in section V-A? I can see that tracking the pose (non-linear globally, because its part of a Lie group) using a separate "object" and then just operating on tangent vectors like in a regular KF is quite elegant, because vector addition and covariance definition now actually make sense. Is this the natural solution to building a KF state estimator using Lie group theory as presented in the paper? Is the ESKF solution a superior choice in IMU driven systems, where IMU measurements are available and need to be integrated into the state at high rate, so that interpreting IMU data as a control input circumvents the expensive EKF update step?
I'm wondering if it would be possible to define something more akin to a "normal" EKF that also allows me to track the velocity in the tangent space correctly (x velocity, y velocity and yaw rate)? So the state vector would be in R^6, with the first 3 entries being the tangent vector of X \in SE(2) at the identity (origin of coordinate system) and the last 3 entries are the x velocity, y velocity and yaw rate.