Skip to content

Commit 2e8bfd6

Browse files
committed
using correct jacobian computation for calibration
1 parent 2e69d09 commit 2e8bfd6

File tree

1 file changed

+11
-9
lines changed

1 file changed

+11
-9
lines changed

gtsam/slam/EssentialMatrixFactor.h

Lines changed: 11 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ class EssentialMatrixFactor : public NoiseModelFactor1<EssentialMatrix> {
8080
const EssentialMatrix& E,
8181
boost::optional<Matrix&> H = boost::none) const override {
8282
Vector error(1);
83-
error << E.error(vA_, vB_, H);
83+
error << E.error(vA_, vB_, H, boost::none, boost::none);
8484
return error;
8585
}
8686

@@ -367,20 +367,22 @@ class EssentialMatrixFactor4
367367
Vector3 vA = EssentialMatrix::Homogeneous(cA);
368368
Vector3 vB = EssentialMatrix::Homogeneous(cB);
369369

370+
371+
Matrix13 error_H_vA, error_H_vB;
372+
Vector error(1);
373+
error << E.error(vA, vB, H1, H2 ? &error_H_vA : 0, H2 ? &error_H_vB : 0);
374+
370375
if (H2) {
371376
// compute the jacobian of error w.r.t K
372377

373-
// error function f = vA.T * E * vB
374-
// H2 = df/dK = vB.T * E.T * dvA/dK + vA.T * E * dvB/dK
378+
// error function f
379+
// H2 = df/dK = df/dvA * dvA/dK + df/dvB * dvB/dK
375380
// where dvA/dK = dvA/dcA * dcA/dK, dVB/dK = dvB/dcB * dcB/dK
376381
// and dvA/dcA = dvB/dcB = [[1, 0], [0, 1], [0, 0]]
377-
*H2 = vB.transpose() * E.matrix().transpose().leftCols<2>() * cA_H_K +
378-
vA.transpose() * E.matrix().leftCols<2>() * cB_H_K;
382+
*H2 = error_H_vA.leftCols<2>() * cA_H_K
383+
+ error_H_vB.leftCols<2>() * cB_H_K;
379384
}
380-
381-
Vector error(1);
382-
error << E.error(vA, vB, H1);
383-
385+
384386
return error;
385387
}
386388

0 commit comments

Comments
 (0)