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>
25 
27 
28 using namespace std::placeholders;
29 using namespace std;
30 using namespace gtsam;
31 
32 /* ************************************************************************* */
34  // Create a factor
35  Key poseKey1(1);
36  Key poseKey2(2);
37  Rot3 trueRotation = Rot3::RzRyRx(0.15, 0.15, -0.20);
38  Point3 trueTranslation(+0.5, -1.0, +1.0);
41  SharedNoiseModel model = noiseModel::Isotropic::Sigma(5, 0.25);
43 
44  // Create a linearization point at the zero-error point
45  Pose3 pose1(Rot3::RzRyRx(0.00, -0.15, 0.30), Point3(-4.0, 7.0, -10.0));
46  Pose3 pose2(
47  Rot3::RzRyRx(0.179693265735950, 0.002945368776519, 0.102274823253840),
48  Point3(-3.37493895, 6.14660244, -8.93650986));
49 
50  Vector expected = Z_5x1;
51  Vector actual = factor.evaluateError(pose1,pose2);
52  CHECK(assert_equal(expected, actual, 1e-8));
53 
54  // Calculate numerical derivatives
55  Matrix expectedH1 = numericalDerivative11<Vector5, Pose3>(
56  [&factor, &pose2](const Pose3& p1) {return factor.evaluateError(p1, pose2);},
57  pose1);
58 
59  Matrix expectedH2 = numericalDerivative11<Vector5, Pose3>(
60  [&factor, &pose1](const Pose3& p2) {return factor.evaluateError(pose1, p2);},
61  pose2);
62 
63  // Use the factor to calculate the derivative
64  Matrix actualH1;
65  Matrix actualH2;
66  factor.evaluateError(pose1, pose2, actualH1, actualH2);
67 
68  // Verify we get the expected error
69  CHECK(assert_equal(expectedH1, actualH1, 1e-5));
70  CHECK(assert_equal(expectedH2, actualH2, 1e-5));
71 }
72 
73 /* ************************************************************************* */
74 int main() {
75  TestResult tr;
76  return TestRegistry::runAllTests(tr);
77 }
78 /* ************************************************************************* */
79 
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
gtsam::EssentialMatrixConstraint::evaluateError
Vector evaluateError(const Pose3 &p1, const Pose3 &p2, OptionalMatrixType Hp1, OptionalMatrixType Hp2) const override
Definition: EssentialMatrixConstraint.cpp:45
trueRotation
Rot3 trueRotation
Definition: testEssentialMatrix.cpp:25
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TestHarness.h
Symbol.h
Symbol.h was moved to inference directory, this header was retained for compatibility.
main
int main()
Definition: testEssentialMatrixConstraint.cpp:74
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
trueDirection
Unit3 trueDirection(trueTranslation)
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
TestableAssertions.h
Provides additional testing facilities for common data structures.
test
Definition: test.py:1
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
numericalDerivative.h
Some functions to compute numerical derivatives.
gtsam::EssentialMatrix
Definition: EssentialMatrix.h:26
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::EssentialMatrixConstraint
Definition: EssentialMatrixConstraint.h:30
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
trueTranslation
Point3 trueTranslation(0.1, 0, 0)
EssentialMatrixConstraint.h
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
p1
Vector3f p1
Definition: MatrixBase_all.cpp:2
TestResult
Definition: TestResult.h:26
gtsam
traits
Definition: chartTesting.h:28
poseKey2
static Key poseKey2(X(2))
pose1
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
TEST
TEST(EssentialMatrixConstraint, test)
Definition: testEssentialMatrixConstraint.cpp:33
CHECK
#define CHECK(condition)
Definition: Test.h:108
std
Definition: BFloat16.h:88
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
poseKey1
static Key poseKey1(X(1))
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
measurement
static Point2 measurement(323.0, 240.0)
Pose3.h
3D Pose


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:05:45