27 using namespace gtsam;
 
   34     return p.retract(
v * 
dt);
 
   43       auto h = [](
const Unit3& p_) { 
return p_.point3().z(); };
 
   44       *
H = numericalDerivative11<double, Unit3, 2>(
h, 
p);
 
   46     return p.point3().z();
 
   71 TEST(ManifoldEKF_Unit3, Predict) {
 
   84   auto predict_wrapper = [&](
const Unit3& 
p) -> 
Unit3 {
 
   87   Matrix2 
F = numericalDerivative11<Unit3, Unit3>(predict_wrapper, 
data.p0);
 
   97   Matrix2 P_expected = 
F * 
data.P0 * 
F.transpose() + 
data.Q;
 
  101   Vector2 zero_velocity = Vector2::Zero();
 
  102   auto predict_wrapper_zero = [&](
const Unit3& 
p) -> 
Unit3 {
 
  105   Matrix2 F_zero = numericalDerivative11<Unit3, Unit3>(predict_wrapper_zero, 
data.p0);
 
  106   EXPECT(assert_equal<Matrix2>(I_2x2, F_zero, 1
e-8));
 
  110 TEST(ManifoldEKF_Unit3, Update) {
 
  115   Matrix2 P_start = I_2x2 * 0.05;
 
  120   double z_observed = z_true + 0.02; 
 
  131   double y = z_pred - z_observed; 
 
  135   Matrix K = P_start * 
H.transpose() * 
S.inverse(); 
 
  142   Matrix2 I_KH = I_2x2 - 
K * 
H;
 
  143   Matrix2 P_updated_expected = I_KH * P_start;
 
  161     if (
p.rows() != 2 || 
p.cols() != 2) {
 
  162       throw std::invalid_argument(
"Matrix must be 2x2.");
 
  165       H->resize(1, 
p.size());
 
  166       *
H << 1.0, 0.0, 0.0, 1.0; 
 
  168     return p(0, 0) + 
p(1, 1); 
 
  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; 
 
  176   Vector vTangent = (
Vector(4) << 0.5, 0.1, -0.1, -0.5).finished(); 
 
  177   double deltaTime = 0.1;
 
  178   Matrix processNoiseCovariance = I_4x4 * 0.001; 
 
  179   Matrix measurementNoiseCovariance = Matrix::Identity(1, 1) * 0.005; 
 
  193   ekf.
predict(pPredictedMean, fJacobian, processNoiseCovariance);
 
  196   Matrix pPredictedCovarianceExpected = fJacobian * pInitialCovariance * fJacobian.transpose() + processNoiseCovariance;
 
  206   double zObserved = zTrue - 0.03;
 
  213   Matrix hJacobianExpected = (
Matrix(1, 4) << 1.0, 0.0, 0.0, 1.0).finished();
 
  217   double yInnovation = zObserved - zPredictionManual;
 
  218   Matrix innovationCovariance = hJacobian * pCurrentCovarianceForUpdate * hJacobian.transpose() + measurementNoiseCovariance;
 
  220   Matrix kalmanGain = pCurrentCovarianceForUpdate * hJacobian.transpose() * innovationCovariance.inverse(); 
 
  223   Vector deltaXiTangent = kalmanGain * yInnovation; 
 
  226   Matrix pUpdatedCovarianceManualExpected = (I_4x4 - kalmanGain * hJacobian) * pCurrentCovarianceForUpdate;