A left invariant Extended Kalman Filter example using a Lie group odometry as the prediction stage on SE(2) and. More...
Go to the source code of this file.
Functions | |
Vector2 | h_gps (const Pose2 &X, OptionalJacobian< 2, 3 > H={}) |
int | main () |
A left invariant Extended Kalman Filter example using a Lie group odometry as the prediction stage on SE(2) and.
This example uses the templated InvariantEKF class to estimate the state of an object using odometry / GPS measurements The prediction stage of the InvariantEKF uses a Lie Group element to propagate the stage in a discrete InvariantEKF. For most cases, U = exp(u^ * dt) if u is a control vector that is constant over the interval dt. However, if u is not constant over dt, other approaches are needed to find the value of U. This approach simply takes a Lie group element U, which can be found in various different ways.
This data was compared to a left invariant EKF on SE(2) using identical measurements and noise from the source of the InEKF plugin https://inekf.readthedocs.io/en/latest/ Based on the paper "An Introduction to the Invariant Extended Kalman Filter" by Easton R. Potokar, Randal W. Beard, and Joshua G. Mangelson
Definition in file IEKF_SE2Example.cpp.
Vector2 h_gps | ( | const Pose2 & | X, |
OptionalJacobian< 2, 3 > | H = {} |
||
) |
Definition at line 45 of file IEKF_SE2Example.cpp.
int main | ( | ) |
Definition at line 51 of file IEKF_SE2Example.cpp.