testTranslationFactor.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2020, 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/geometry/Point3.h>
22 
24 
25 using namespace std;
26 using namespace gtsam;
27 
28 // Create a noise model for the chordal error
29 static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.05));
30 
31 // Keys are deliberately *not* in sorted order to test that case.
32 static const Key kKey1(2), kKey2(1);
33 static const Unit3 kMeasured(1, 0, 0);
34 
35 /* ************************************************************************* */
36 TEST(TranslationFactor, Constructor) {
38 }
39 
40 /* ************************************************************************* */
41 TEST(TranslationFactor, ZeroError) {
42  // Create a factor
44 
45  // Set the linearization
46  Point3 T1(1, 0, 0), T2(2, 0, 0);
47 
48  // Use the factor to calculate the error
49  Vector actualError(factor.evaluateError(T1, T2));
50 
51  // Verify we get the expected error
52  Vector expected = (Vector3() << 0, 0, 0).finished();
53  EXPECT(assert_equal(expected, actualError, 1e-9));
54 }
55 
56 /* ************************************************************************* */
57 TEST(TranslationFactor, NonZeroError) {
58  // create a factor
60 
61  // set the linearization
62  Point3 T1(0, 1, 1), T2(0, 2, 2);
63 
64  // use the factor to calculate the error
65  Vector actualError(factor.evaluateError(T1, T2));
66 
67  // verify we get the expected error
68  Vector expected = (Vector3() << -1, 1 / sqrt(2), 1 / sqrt(2)).finished();
69  EXPECT(assert_equal(expected, actualError, 1e-9));
70 }
71 
72 /* ************************************************************************* */
74  const TranslationFactor &factor) {
75  return factor.evaluateError(T1, T2);
76 }
77 
78 TEST(TranslationFactor, Jacobian) {
79  // Create a factor
81 
82  // Set the linearization
83  Point3 T1(1, 0, 0), T2(2, 0, 0);
84 
85  // Use the factor to calculate the Jacobians
86  Matrix H1Actual, H2Actual;
87  factor.evaluateError(T1, T2, H1Actual, H2Actual);
88 
89  // Use numerical derivatives to calculate the Jacobians
90  Matrix H1Expected, H2Expected;
91  H1Expected = numericalDerivative11<Vector, Point3>(
92  boost::bind(&factorError, _1, T2, factor), T1);
93  H2Expected = numericalDerivative11<Vector, Point3>(
94  boost::bind(&factorError, T1, _1, factor), T2);
95 
96  // Verify the Jacobians are correct
97  EXPECT(assert_equal(H1Expected, H1Actual, 1e-9));
98  EXPECT(assert_equal(H2Expected, H2Actual, 1e-9));
99 }
100 
101 /* ************************************************************************* */
102 int main() {
103  TestResult tr;
104  return TestRegistry::runAllTests(tr);
105 }
106 /* ************************************************************************* */
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
Matrix expected
Definition: testMatrix.cpp:974
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
TEST(TranslationFactor, Constructor)
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
Definition: Half.h:150
Some functions to compute numerical derivatives.
static const Key kKey2(1)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
Eigen::VectorXd Vector
Definition: Vector.h:38
Vector evaluateError(const Point3 &Ta, const Point3 &Tb, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Caclulate error: (norm(Tb - Ta) - measurement) where Tb and Ta are Point3 translations and measuremen...
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Binary factor for a relative translation direction measurement.
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
3D Point
static const Key kKey1(2)
Vector3 Point3
Definition: Point3.h:35
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
Vector factorError(const Point3 &T1, const Point3 &T2, const TranslationFactor &factor)
static const Unit3 kMeasured(1, 0, 0)
int main()
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.05))


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:50:06