testEssentialMatrixConstraint.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, 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 
21 #include <gtsam/nonlinear/Symbol.h>
22 #include <gtsam/geometry/Pose3.h>
26 
27 using namespace std;
28 using namespace gtsam;
29 
30 /* ************************************************************************* */
32  // Create a factor
33  Key poseKey1(1);
34  Key poseKey2(2);
35  Rot3 trueRotation = Rot3::RzRyRx(0.15, 0.15, -0.20);
36  Point3 trueTranslation(+0.5, -1.0, +1.0);
37  Unit3 trueDirection(trueTranslation);
38  EssentialMatrix measurement(trueRotation, trueDirection);
39  SharedNoiseModel model = noiseModel::Isotropic::Sigma(5, 0.25);
40  EssentialMatrixConstraint factor(poseKey1, poseKey2, measurement, model);
41 
42  // Create a linearization point at the zero-error point
43  Pose3 pose1(Rot3::RzRyRx(0.00, -0.15, 0.30), Point3(-4.0, 7.0, -10.0));
44  Pose3 pose2(
45  Rot3::RzRyRx(0.179693265735950, 0.002945368776519, 0.102274823253840),
46  Point3(-3.37493895, 6.14660244, -8.93650986));
47 
48  Vector expected = Z_5x1;
49  Vector actual = factor.evaluateError(pose1,pose2);
50  CHECK(assert_equal(expected, actual, 1e-8));
51 
52  // Calculate numerical derivatives
53  Matrix expectedH1 = numericalDerivative11<Vector5,Pose3>(
54  boost::bind(&EssentialMatrixConstraint::evaluateError, &factor, _1, pose2,
55  boost::none, boost::none), pose1);
56  Matrix expectedH2 = numericalDerivative11<Vector5,Pose3>(
57  boost::bind(&EssentialMatrixConstraint::evaluateError, &factor, pose1, _1,
58  boost::none, boost::none), pose2);
59 
60  // Use the factor to calculate the derivative
61  Matrix actualH1;
62  Matrix actualH2;
63  factor.evaluateError(pose1, pose2, actualH1, actualH2);
64 
65  // Verify we get the expected error
66  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
67  CHECK(assert_equal(expectedH2, actualH2, 1e-5));
68 }
69 
70 /* ************************************************************************* */
71 int main() {
72  TestResult tr;
73  return TestRegistry::runAllTests(tr);
74 }
75 /* ************************************************************************* */
76 
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:109
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
Definition: test.py:1
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
double measurement(10.0)
Definition: Half.h:150
Some functions to compute numerical derivatives.
Point3 trueTranslation(0.1, 0, 0)
Vector evaluateError(const Pose3 &p1, const Pose3 &p2, boost::optional< Matrix & > Hp1=boost::none, boost::optional< Matrix & > Hp2=boost::none) const override
TEST(EssentialMatrixConstraint, test)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Eigen::VectorXd Vector
Definition: Vector.h:38
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Unit3 trueDirection(trueTranslation)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Rot3 trueRotation
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
static Key poseKey1(x1)
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:30