testManifoldEKF.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
3  * Atlanta, Georgia 30332-0415
4  * All Rights Reserved
5  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
6  *
7  * See LICENSE for the license information
8  * -------------------------------------------------------------------------- */
9 
17 #include <gtsam/base/Testable.h>
19 #include <gtsam/geometry/Point3.h>
20 #include <gtsam/geometry/Unit3.h>
22 
24 
25 #include <iostream>
26 
27 using namespace gtsam;
28 
29 // Define simple dynamics for Unit3: constant velocity in the tangent space
30 namespace exampleUnit3 {
31 
32  // Predicts the next state given current state, tangent velocity, and dt
33  Unit3 f(const Unit3& p, const Vector2& v, double dt) {
34  return p.retract(v * dt);
35  }
36 
37  // Define a measurement model: measure the z-component of the Unit3 direction
38  // H is the Jacobian dh/d(local(p))
40  if (H) {
41  // H = d(p.point3().z()) / d(local(p))
42  // Calculate numerically for simplicity in test
43  auto h = [](const Unit3& p_) { return p_.point3().z(); };
44  *H = numericalDerivative11<double, Unit3, 2>(h, p);
45  }
46  return p.point3().z();
47  }
48 
49 } // namespace exampleUnit3
50 
51 // Test fixture for ManifoldEKF with Unit3
52 struct Unit3EKFTest {
54  Matrix2 P0;
56  double dt;
57  Matrix2 Q; // Process noise
58  Matrix1 R; // Measurement noise
59 
61  p0(Unit3(Point3(1, 0, 0))), // Start pointing along X-axis
62  P0(I_2x2 * 0.01),
63  velocity((Vector2() << 0.0, M_PI / 4.0).finished()), // Rotate towards +Z axis
64  dt(0.1),
65  Q(I_2x2 * 0.001),
66  R(Matrix1::Identity() * 0.01) {
67  }
68 };
69 
70 
71 TEST(ManifoldEKF_Unit3, Predict) {
73 
74  // Initialize the EKF
75  ManifoldEKF<Unit3> ekf(data.p0, data.P0);
76 
77  // --- Prepare inputs for ManifoldEKF::predict ---
78  // 1. Compute expected next state
79  Unit3 p_next_expected = exampleUnit3::f(data.p0, data.velocity, data.dt);
80 
81  // 2. Compute state transition Jacobian F = d(local(p_next)) / d(local(p))
82  // We can compute this numerically using the f function.
83  // GTSAM's numericalDerivative handles derivatives *between* manifolds.
84  auto predict_wrapper = [&](const Unit3& p) -> Unit3 {
85  return exampleUnit3::f(p, data.velocity, data.dt);
86  };
87  Matrix2 F = numericalDerivative11<Unit3, Unit3>(predict_wrapper, data.p0);
88 
89  // --- Perform EKF prediction ---
90  ekf.predict(p_next_expected, F, data.Q);
91 
92  // --- Verification ---
93  // Check state
94  EXPECT(assert_equal(p_next_expected, ekf.state(), 1e-8));
95 
96  // Check covariance
97  Matrix2 P_expected = F * data.P0 * F.transpose() + data.Q;
98  EXPECT(assert_equal(P_expected, ekf.covariance(), 1e-8));
99 
100  // Check F manually for a simple case (e.g., zero velocity should give Identity)
101  Vector2 zero_velocity = Vector2::Zero();
102  auto predict_wrapper_zero = [&](const Unit3& p) -> Unit3 {
103  return exampleUnit3::f(p, zero_velocity, data.dt);
104  };
105  Matrix2 F_zero = numericalDerivative11<Unit3, Unit3>(predict_wrapper_zero, data.p0);
106  EXPECT(assert_equal<Matrix2>(I_2x2, F_zero, 1e-8));
107 
108 }
109 
110 TEST(ManifoldEKF_Unit3, Update) {
112 
113  // Use a slightly different starting point and covariance for variety
114  Unit3 p_start = Unit3(Point3(0, 1, 0)).retract((Vector2() << 0.1, 0).finished()); // Perturb pointing along Y
115  Matrix2 P_start = I_2x2 * 0.05;
116  ManifoldEKF<Unit3> ekf(p_start, P_start);
117 
118  // Simulate a measurement (e.g., true value + noise)
119  double z_true = exampleUnit3::measureZ(p_start, {});
120  double z_observed = z_true + 0.02; // Add some noise
121 
122  // --- Perform EKF update ---
123  ekf.update(exampleUnit3::measureZ, z_observed, data.R);
124 
125  // --- Verification (Manual Kalman Update Steps) ---
126  // 1. Predict measurement and get Jacobian H
127  Matrix12 H; // Note: Jacobian is 1x2 for Unit3
128  double z_pred = exampleUnit3::measureZ(p_start, H);
129 
130  // 2. Innovation and Covariance
131  double y = z_pred - z_observed; // Innovation (using vector subtraction for z)
132  Matrix1 S = H * P_start * H.transpose() + data.R; // 1x1 matrix
133 
134  // 3. Kalman Gain K
135  Matrix K = P_start * H.transpose() * S.inverse(); // 2x1 matrix
136 
137  // 4. State Correction (in tangent space)
138  Vector2 delta_xi = -K * y; // 2x1 vector
139 
140  // 5. Expected Updated State and Covariance
141  Unit3 p_updated_expected = p_start.retract(delta_xi);
142  Matrix2 I_KH = I_2x2 - K * H;
143  Matrix2 P_updated_expected = I_KH * P_start;
144 
145  // --- Compare EKF result with manual calculation ---
146  EXPECT(assert_equal(p_updated_expected, ekf.state(), 1e-8));
147  EXPECT(assert_equal(P_updated_expected, ekf.covariance(), 1e-8));
148 }
149 
150 // Define simple dynamics and measurement for a 2x2 Matrix state
151 namespace exampleDynamicMatrix {
152 
153  // Predicts the next state given current state (Matrix), tangent "velocity" (Vector), and dt.
154  Matrix f(const Matrix& p, const Vector& vTangent, double dt) {
155  return traits<Matrix>::Retract(p, vTangent * dt); // +
156  }
157 
158  // Define a measurement model: measure the trace of the Matrix (assumed 2x2 here)
159  double h(const Matrix& p, OptionalJacobian<-1, -1> H = {}) {
160  // Specialized for a 2x2 matrix!
161  if (p.rows() != 2 || p.cols() != 2) {
162  throw std::invalid_argument("Matrix must be 2x2.");
163  }
164  if (H) {
165  H->resize(1, p.size());
166  *H << 1.0, 0.0, 0.0, 1.0; // d(trace)/dp00, d(trace)/dp01, d(trace)/dp10, d(trace)/dp11
167  }
168  return p(0, 0) + p(1, 1); // Trace of the matrix
169  }
170 
171 } // namespace exampleDynamicMatrix
172 
173 TEST(ManifoldEKF_DynamicMatrix, CombinedPredictAndUpdate) {
174  Matrix pInitial = (Matrix(2, 2) << 1.0, 2.0, 3.0, 4.0).finished();
175  Matrix pInitialCovariance = I_4x4 * 0.01; // Covariance for 2x2 matrix (4x4)
176  Vector vTangent = (Vector(4) << 0.5, 0.1, -0.1, -0.5).finished(); // [dp00, dp10, dp01, dp11]/sec
177  double deltaTime = 0.1;
178  Matrix processNoiseCovariance = I_4x4 * 0.001; // Process noise covariance (4x4)
179  Matrix measurementNoiseCovariance = Matrix::Identity(1, 1) * 0.005; // Measurement noise covariance (1x1)
180 
181  ManifoldEKF<Matrix> ekf(pInitial, pInitialCovariance);
182  // For a 2x2 Matrix, tangent space dimension is 2*2=4.
183  EXPECT_LONGS_EQUAL(4, ekf.state().size());
184  EXPECT_LONGS_EQUAL(pInitial.rows() * pInitial.cols(), ekf.state().size());
185 
186  // Predict Step
187  Matrix pPredictedMean = exampleDynamicMatrix::f(pInitial, vTangent, deltaTime);
188 
189  // For this linear prediction model (pNext = pCurrent + V*dt in tangent space),
190  // Derivative w.r.t deltaXi is Identity.
191  Matrix fJacobian = I_4x4;
192 
193  ekf.predict(pPredictedMean, fJacobian, processNoiseCovariance);
194 
195  EXPECT(assert_equal(pPredictedMean, ekf.state(), 1e-9));
196  Matrix pPredictedCovarianceExpected = fJacobian * pInitialCovariance * fJacobian.transpose() + processNoiseCovariance;
197  EXPECT(assert_equal(pPredictedCovarianceExpected, ekf.covariance(), 1e-9));
198 
199  // Update Step
200  Matrix pCurrentForUpdate = ekf.state();
201  Matrix pCurrentCovarianceForUpdate = ekf.covariance();
202 
203  // True trace of pCurrentForUpdate (which is pPredictedMean)
204  double zTrue = exampleDynamicMatrix::h(pCurrentForUpdate);
205  EXPECT_DOUBLES_EQUAL(5.0, zTrue, 1e-9);
206  double zObserved = zTrue - 0.03;
207 
208  ekf.update(exampleDynamicMatrix::h, zObserved, measurementNoiseCovariance);
209 
210  // Manual Kalman Update Steps for Verification
211  Matrix hJacobian(1, 4); // Measurement Jacobian H (1x4 for 2x2 matrix, trace measurement)
212  double zPredictionManual = exampleDynamicMatrix::h(pCurrentForUpdate, hJacobian);
213  Matrix hJacobianExpected = (Matrix(1, 4) << 1.0, 0.0, 0.0, 1.0).finished();
214  EXPECT(assert_equal(hJacobianExpected, hJacobian, 1e-9));
215 
216  // Innovation: y = zObserved - zPredictionManual (since measurement is double)
217  double yInnovation = zObserved - zPredictionManual;
218  Matrix innovationCovariance = hJacobian * pCurrentCovarianceForUpdate * hJacobian.transpose() + measurementNoiseCovariance;
219 
220  Matrix kalmanGain = pCurrentCovarianceForUpdate * hJacobian.transpose() * innovationCovariance.inverse(); // K is 4x1
221 
222  // State Correction (in tangent space of Matrix)
223  Vector deltaXiTangent = kalmanGain * yInnovation; // deltaXi is 4x1 Vector
224 
225  Matrix pUpdatedManualExpected = traits<Matrix>::Retract(pCurrentForUpdate, deltaXiTangent);
226  Matrix pUpdatedCovarianceManualExpected = (I_4x4 - kalmanGain * hJacobian) * pCurrentCovarianceForUpdate;
227 
228  EXPECT(assert_equal(pUpdatedManualExpected, ekf.state(), 1e-9));
229  EXPECT(assert_equal(pUpdatedCovarianceManualExpected, ekf.covariance(), 1e-9));
230 }
231 
232 int main() {
233  TestResult tr;
234  return TestRegistry::runAllTests(tr);
235 }
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
exampleUnit3
Definition: testManifoldEKF.cpp:30
H
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
ManifoldEKF.h
Extended Kalman Filter base class on a generic manifold M.
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
exampleDynamicMatrix::h
double h(const Matrix &p, OptionalJacobian<-1, -1 > H={})
Definition: testInvariantEKF.cpp:127
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
Testable.h
Concept check for values that can be used in unit tests.
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
gtsam::Vector2
Eigen::Vector2d Vector2
Definition: Vector.h:43
TestHarness.h
dt
const double dt
Definition: testVelocityConstraint.cpp:15
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Point3.h
3D Point
Unit3EKFTest::Unit3EKFTest
Unit3EKFTest()
Definition: testManifoldEKF.cpp:60
Unit3EKFTest::p0
Unit3 p0
Definition: testManifoldEKF.cpp:53
h
const double h
Definition: testSimpleHelicopter.cpp:19
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::ManifoldEKF::predict
void predict(const M &X_next, const Jacobian &F, const Covariance &Q)
Definition: ManifoldEKF.h:128
Unit3.h
exampleUnit3::f
Unit3 f(const Unit3 &p, const Vector2 &v, double dt)
Definition: testManifoldEKF.cpp:33
numericalDerivative.h
Some functions to compute numerical derivatives.
data
int data[]
Definition: Map_placement_new.cpp:1
gtsam::ManifoldEKF::covariance
const Covariance & covariance() const
Definition: ManifoldEKF.h:111
gtsam::ManifoldEKF::state
const M & state() const
Definition: ManifoldEKF.h:108
Vector2
Definition: test_operator_overloading.cpp:18
gtsam::ManifoldEKF::update
void update(const Measurement &prediction, const Eigen::Matrix< double, traits< Measurement >::dimension, Dim > &H, const Measurement &z, const Eigen::Matrix< double, traits< Measurement >::dimension, traits< Measurement >::dimension > &R)
Definition: ManifoldEKF.h:152
Unit3EKFTest::R
Matrix1 R
Definition: testManifoldEKF.cpp:58
exampleUnit3::measureZ
double measureZ(const Unit3 &p, OptionalJacobian< 1, 2 > H)
Definition: testManifoldEKF.cpp:39
gtsam::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
main
int main()
Definition: testManifoldEKF.cpp:232
gtsam::Unit3::retract
Unit3 retract(const Vector2 &v, OptionalJacobian< 2, 2 > H={}) const
The retract function.
Definition: Unit3.cpp:255
EXPECT_DOUBLES_EQUAL
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:161
TestResult
Definition: TestResult.h:26
y
Scalar * y
Definition: level1_cplx_impl.h:124
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
gtsam::ManifoldEKF
Extended Kalman Filter on a generic manifold M.
Definition: ManifoldEKF.h:65
gtsam
traits
Definition: ABC.h:17
gtsam::TEST
TEST(SmartFactorBase, Pinhole)
Definition: testSmartFactorBase.cpp:38
gtsam::traits
Definition: Group.h:36
K
#define K
Definition: igam.h:8
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
p0
Vector3f p0
Definition: MatrixBase_all.cpp:2
Unit3EKFTest::Q
Matrix2 Q
Definition: testManifoldEKF.cpp:57
p
float * p
Definition: Tutorial_Map_using.cpp:9
Unit3EKFTest::dt
double dt
Definition: testManifoldEKF.cpp:56
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
Unit3EKFTest::P0
Matrix2 P0
Definition: testManifoldEKF.cpp:54
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:41
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
Eigen::Matrix< double, 1, 1 >
Unit3EKFTest::velocity
Vector2 velocity
Definition: testManifoldEKF.cpp:55
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
M_PI
#define M_PI
Definition: mconf.h:117
P0
static double P0[5]
Definition: ndtri.c:59
exampleDynamicMatrix::f
Matrix f(const Matrix &p, const Vector &vTangent, double dt)
Definition: testInvariantEKF.cpp:124
exampleDynamicMatrix
Definition: testInvariantEKF.cpp:123
R
Rot2 R(Rot2::fromAngle(0.1))
Unit3EKFTest
Definition: testManifoldEKF.cpp:52
S
DiscreteKey S(1, 2)
gtsam::velocity
Velocity3_ velocity(const NavState_ &X)
Definition: navigation/expressions.h:40


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:06:53