Merge pull request #2139 from borglab/fix/example

Fix example
release/4.3a0
Frank Dellaert 2025-05-16 21:20:23 -04:00 committed by GitHub
commit cc4a0e1804
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
3 changed files with 8 additions and 7 deletions

View File

@ -10,7 +10,7 @@
* -------------------------------------------------------------------------- */ * -------------------------------------------------------------------------- */
/** /**
* @file IEKF_Rot3Example.cpp * @file GEKF_Rot3Example.cpp
* @brief LeftInvariant EKF on SO(3) with statedependent pitch/roll control * @brief LeftInvariant EKF on SO(3) with statedependent pitch/roll control
* and a single magnetometer update. * and a single magnetometer update.
* @date April 25, 2025 * @date April 25, 2025

View File

@ -17,6 +17,7 @@
*/ */
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
#include <gtsam/base/VectorSpace.h>
#include <gtsam/base/OptionalJacobian.h> #include <gtsam/base/OptionalJacobian.h>
#include <gtsam/navigation/InvariantEKF.h> #include <gtsam/navigation/InvariantEKF.h>
#include <gtsam/navigation/NavState.h> #include <gtsam/navigation/NavState.h>
@ -73,23 +74,23 @@ int main() {
z2 << 0.6, 0, 0; z2 << 0.6, 0, 0;
cout << "=== Init ===\nX: " << ekf.state() << "\nP: " << ekf.covariance() cout << "=== Init ===\nX: " << ekf.state() << "\nP: " << ekf.covariance()
<< "\n\n"; << "\n\n";
// --- first predict/update --- // --- first predict/update ---
ekf.predict(dynamics(imu1), dt, Q); ekf.predict(dynamics(imu1), dt, Q);
cout << "--- After predict 1 ---\nX: " << ekf.state() cout << "--- After predict 1 ---\nX: " << ekf.state()
<< "\nP: " << ekf.covariance() << "\n\n"; << "\nP: " << ekf.covariance() << "\n\n";
ekf.update(h_gps, z1, R); ekf.update(h_gps, z1, R);
cout << "--- After update 1 ---\nX: " << ekf.state() cout << "--- After update 1 ---\nX: " << ekf.state()
<< "\nP: " << ekf.covariance() << "\n\n"; << "\nP: " << ekf.covariance() << "\n\n";
// --- second predict/update --- // --- second predict/update ---
ekf.predict(dynamics(imu2), dt, Q); ekf.predict(dynamics(imu2), dt, Q);
cout << "--- After predict 2 ---\nX: " << ekf.state() cout << "--- After predict 2 ---\nX: " << ekf.state()
<< "\nP: " << ekf.covariance() << "\n\n"; << "\nP: " << ekf.covariance() << "\n\n";
ekf.update(h_gps, z2, R); ekf.update(h_gps, z2, R);
cout << "--- After update 2 ---\nX: " << ekf.state() cout << "--- After update 2 ---\nX: " << ekf.state()
<< "\nP: " << ekf.covariance() << "\n"; << "\nP: " << ekf.covariance() << "\n";
return 0; return 0;
} }

View File

@ -47,7 +47,7 @@ set (LIBVERSION_BUILD 17.1.2)
string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER) string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
string (TOUPPER ${PROJECT_NAME} PROJECT_NAME_UPPER) string (TOUPPER ${PROJECT_NAME} PROJECT_NAME_UPPER)
cmake_minimum_required (VERSION 2.8.4) # This version was released 2011-02-16 cmake_minimum_required (VERSION 3.5) # This version was released 2011-02-16
# User-settable variables # User-settable variables