gtsam/examples/LIEKF_NavstateExample.cpp

112 lines
3.3 KiB
C++
Raw Normal View History

/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file LIEKF_NavstateExample.cpp
2025-04-27 00:30:55 +08:00
* @brief Example of a Left-Invariant Extended Kalman Filter on NavState
* using IMU (predict) and GPS (update) measurements.
* @date April 25, 2025
* @authors Scott Baker, Matt Kielo, Frank Dellaert
*/
2025-04-27 00:30:55 +08:00
#include <gtsam/base/Matrix.h>
#include <gtsam/base/OptionalJacobian.h>
2025-04-25 09:11:26 +08:00
#include <gtsam/navigation/NavState.h>
2025-04-27 00:33:05 +08:00
#include <gtsam/navigation/LIEKF.h>
2025-04-25 09:11:26 +08:00
#include <iostream>
using namespace std;
using namespace gtsam;
2025-04-27 00:30:55 +08:00
/**
* @brief Left-invariant dynamics for NavState.
* @param X Current state (unused for left-invariant error dynamics).
* @param imu 6×1 vector [a; ω]: linear accel (first 3) and angular vel (last
* 3).
* @param H Optional 9×9 Jacobian w.r.t. X (always zero here).
* @return 9×1 tangent: [ω; 0; a].
*/
2025-04-25 09:11:26 +08:00
Vector9 dynamics(const NavState& X, const Vector6& imu,
OptionalJacobian<9, 9> H = {}) {
2025-04-27 00:30:55 +08:00
auto a = imu.head<3>();
auto w = imu.tail<3>();
Vector9 xi;
xi << w, Vector3::Zero(), a;
if (H) *H = Matrix9::Zero();
return xi;
2025-04-25 09:11:26 +08:00
}
2025-04-27 00:30:55 +08:00
/**
* @brief GPS measurement model: returns position and its Jacobian.
* @param X Current state.
* @param H Optional 3×9 Jacobian w.r.t. X.
* @return 3×1 position vector.
*/
Vector3 h_gps(const NavState& X, OptionalJacobian<3, 9> H = {}) {
2025-04-27 00:30:55 +08:00
if (H) {
// H = [ 0₃×3, 0₃×3, R ]
*H << Z_3x3, Z_3x3, X.R();
}
return X.t();
}
int main() {
2025-04-27 00:30:55 +08:00
// Initial state, covariance, and time step
NavState X0;
Matrix9 P0 = Matrix9::Identity() * 0.1;
double dt = 1.0;
2025-04-27 00:30:55 +08:00
// Create the filter with the initial state and covariance.
2025-04-26 23:47:46 +08:00
LIEKF<NavState> ekf(X0, P0);
2025-04-27 00:30:55 +08:00
// Process & measurement noise
Matrix9 Q = Matrix9::Identity() * 0.01;
Matrix3 R = Matrix3::Identity() * 0.5;
// Create the IMU measurements of the form (linear_acceleration,
// angular_velocity)
Vector6 imu1, imu2;
2025-04-27 00:30:55 +08:00
imu1 << 0.1, 0.0, 0.0, 0.0, 0.2, 0.0;
imu2 << 0.0, 0.3, 0.0, 0.4, 0.0, 0.0;
// Create the GPS measurements of the form (px, py, pz)
Vector3 z1, z2;
2025-04-27 00:30:55 +08:00
z1 << 0.3, 0.0, 0.0;
z2 << 0.6, 0.0, 0.0;
2025-04-27 00:30:55 +08:00
cout << "=== Initialization ===\n"
<< "X0: " << ekf.state() << "\n"
<< "P0: " << ekf.covariance() << "\n\n";
2025-04-27 00:14:12 +08:00
ekf.predict(dynamics, imu1, dt, Q);
2025-04-27 00:30:55 +08:00
cout << "--- After first predict ---\n"
<< "X: " << ekf.state() << "\n"
<< "P: " << ekf.covariance() << "\n\n";
2025-04-26 23:47:46 +08:00
ekf.update(h_gps, z1, R);
2025-04-27 00:30:55 +08:00
cout << "--- After first update ---\n"
<< "X: " << ekf.state() << "\n"
<< "P: " << ekf.covariance() << "\n\n";
2025-04-27 00:14:12 +08:00
ekf.predict(dynamics, imu2, dt, Q);
2025-04-27 00:30:55 +08:00
cout << "--- After second predict ---\n"
<< "X: " << ekf.state() << "\n"
<< "P: " << ekf.covariance() << "\n\n";
2025-04-26 23:47:46 +08:00
ekf.update(h_gps, z2, R);
2025-04-27 00:30:55 +08:00
cout << "--- After second update ---\n"
<< "X: " << ekf.state() << "\n"
<< "P: " << ekf.covariance() << "\n";
return 0;
2025-04-27 00:30:55 +08:00
}