EssentialMatrixConstraint.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2014, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 //#include <gtsam/linear/GaussianFactor.h>
21 //#include <gtsam/base/Testable.h>
22 
23 #include <ostream>
24 
25 namespace gtsam {
26 
27 /* ************************************************************************* */
28 void EssentialMatrixConstraint::print(const std::string& s,
29  const KeyFormatter& keyFormatter) const {
30  std::cout << s << "EssentialMatrixConstraint(" << keyFormatter(this->key<1>())
31  << "," << keyFormatter(this->key<2>()) << ")\n";
32  measuredE_.print(" measured: ");
33  this->noiseModel_->print(" noise model: ");
34 }
35 
36 /* ************************************************************************* */
38  double tol) const {
39  const This *e = dynamic_cast<const This*>(&expected);
40  return e != nullptr && Base::equals(*e, tol)
41  && this->measuredE_.equals(e->measuredE_, tol);
42 }
43 
44 /* ************************************************************************* */
46  const Pose3& p2, OptionalMatrixType Hp1,
47  OptionalMatrixType Hp2) const {
48 
49  // compute relative Pose3 between p1 and p2
50  Pose3 _1P2_ = p1.between(p2, Hp1, Hp2);
51 
52  // convert to EssentialMatrix
53  Matrix D_hx_1P2;
54  EssentialMatrix hx;
55  if (Hp1 || Hp2) {
56  hx = EssentialMatrix::FromPose3(_1P2_, D_hx_1P2);
57  } else {
59  }
60 
61  // Calculate derivatives if needed
62  if (Hp1) {
63  // Hp1 will already contain the 6*6 derivative D_1P2_p1
64  const Matrix& D_1P2_p1 = *Hp1;
65  // The 5*6 derivative is obtained by chaining with 5*6 D_hx_1P2:
66  *Hp1 = D_hx_1P2 * D_1P2_p1;
67  }
68  if (Hp2) {
69  // Hp2 will already contain the 6*6 derivative D_1P2_p1
70  const Matrix& D_1P2_p2 = *Hp2;
71  // The 5*6 derivative is obtained by chaining with 5*6 D_hx_1P2:
72  *Hp2 = D_hx_1P2 * D_1P2_p2;
73  }
74 
75  // manifold equivalent of h(x)-z -> log(z,h(x))
76  return measuredE_.localCoordinates(hx); // 5D error
77 }
78 
79 }
bool equals(const EssentialMatrix &other, double tol=1e-8) const
assert equality up to a tolerance
static GTSAM_EXPORT EssentialMatrix FromPose3(const Pose3 &_1P2_, OptionalJacobian< 5, 6 > H={})
Named constructor converting a Pose3 with scale to EssentialMatrix (no scale)
Vector3f p1
Matrix expected
Definition: testMatrix.cpp:971
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
#define OptionalNone
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
Vector5 localCoordinates(const EssentialMatrix &other) const
Compute the coordinates in the tangent space.
GTSAM_EXPORT void print(const std::string &s="") const
print with optional string
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
traits
Definition: chartTesting.h:28
SharedNoiseModel noiseModel_
Class between(const Class &g) const
Definition: Lie.h:52
Vector evaluateError(const Pose3 &p1, const Pose3 &p2, OptionalMatrixType Hp1, OptionalMatrixType Hp2) const override
static Point3 p2
const G double tol
Definition: Group.h:86


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:12