testTSAMFactors.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 
23 #include "gtsam/geometry/Point2.h"
24 
25 using namespace std::placeholders;
26 using namespace std;
27 using namespace gtsam;
28 
29 Key i(1), j(2); // Key for pose and point
30 
31 //*************************************************************************
33  // Create a factor
34  Point2 measurement(1, 1);
35  static SharedNoiseModel model(noiseModel::Unit::Create(2));
36  DeltaFactor factor(i, j, measurement, model);
37 
38  // Set the linearization point
39  Pose2 pose(1, 2, 0);
40  Point2 point(4, 11);
41  Vector2 expected(4 - 1 - 1, 11 - 2 - 1);
42 
43  // Use the factor to calculate the Jacobians
44  Matrix H1Actual, H2Actual;
45  Vector actual = factor.evaluateError(pose, point, H1Actual, H2Actual);
46  EXPECT(assert_equal(expected, actual, 1e-9));
47 
48  // Use numerical derivatives to calculate the Jacobians
49  Matrix H1Expected, H2Expected;
50 
51  H1Expected = numericalDerivative11<Vector2, Pose2>(
52  [&factor, &point](const Pose2& pose) { return factor.evaluateError(pose, point); }, pose);
53  H2Expected = numericalDerivative11<Vector2, Point2>(
54  [&factor, &pose](const Point2& point) { return factor.evaluateError(pose, point); }, point);
55 
56  // Verify the Jacobians are correct
57  EXPECT(assert_equal(H1Expected, H1Actual, 1e-9));
58  EXPECT(assert_equal(H2Expected, H2Actual, 1e-9));
59 }
60 
61 //*************************************************************************
63  // Create a factor
64  Key b1(10), b2(20);
65  Point2 measurement(1, 1);
66  static SharedNoiseModel model(noiseModel::Unit::Create(2));
67  DeltaFactorBase factor(b1, i, b2, j, measurement, model);
68 
69  // Set the linearization point
70  Pose2 base1, base2(1, 0, 0);
71  Pose2 pose(1, 2, 0);
72  Point2 point(4, 11);
73  Vector2 expected(4 + 1 - 1 - 1, 11 - 2 - 1);
74 
75  // Use the factor to calculate the Jacobians
76  Matrix H1Actual, H2Actual, H3Actual, H4Actual;
77  Vector actual = factor.evaluateError(base1, pose, base2, point, H1Actual,
78  H2Actual, H3Actual, H4Actual);
79  EXPECT(assert_equal(expected, actual, 1e-9));
80 
81  // Use numerical derivatives to calculate the Jacobians
82  Matrix H1Expected, H2Expected, H3Expected, H4Expected;
83  H1Expected = numericalDerivative11<Vector2, Pose2>(
84  [&factor, &pose, &base2, &point](const Pose2& pose_arg) {
85  return factor.evaluateError(pose_arg, pose, base2, point);
86  },
87  base1);
88  H2Expected = numericalDerivative11<Vector2, Pose2>(
89  [&factor, &point, &base1, &base2](const Pose2& pose_arg) {
90  return factor.evaluateError(base1, pose_arg, base2, point);
91  },
92  pose);
93  H3Expected = numericalDerivative11<Vector2, Pose2>(
94  [&factor, &pose, &base1, &point](const Pose2& pose_arg) {
95  return factor.evaluateError(base1, pose, pose_arg, point);
96  },
97  base2);
98  H4Expected = numericalDerivative11<Vector2, Point2>(
99  [&factor, &pose, &base1, &base2](const Point2& point_arg) {
100  return factor.evaluateError(base1, pose, base2, point_arg);
101  },
102  point);
103 
104  // Verify the Jacobians are correct
105  EXPECT(assert_equal(H1Expected, H1Actual, 1e-9));
106  EXPECT(assert_equal(H2Expected, H2Actual, 1e-9));
107  EXPECT(assert_equal(H3Expected, H3Actual, 1e-9));
108  EXPECT(assert_equal(H4Expected, H4Actual, 1e-9));
109 }
110 
111 //*************************************************************************
113  // Create a factor
114  Key b1(10), b2(20);
115  Pose2 measurement(1, 1, 0);
116  static SharedNoiseModel model(noiseModel::Unit::Create(2));
117  OdometryFactorBase factor(b1, i, b2, j, measurement, model);
118 
119  // Set the linearization pose2
120  Pose2 base1, base2(1, 0, 0);
121  Pose2 pose1(1, 2, 0), pose2(4, 11, 0);
122  Vector3 expected(4 + 1 - 1 - 1, 11 - 2 - 1, 0);
123 
124  // Use the factor to calculate the Jacobians
125  Matrix H1Actual, H2Actual, H3Actual, H4Actual;
126  Vector actual = factor.evaluateError(base1, pose1, base2, pose2, H1Actual,
127  H2Actual, H3Actual, H4Actual);
128  EXPECT(assert_equal(expected, actual, 1e-9));
129 
130  // Use numerical derivatives to calculate the Jacobians
131  Matrix H1Expected, H2Expected, H3Expected, H4Expected;
132  // using lambdas to replace bind
133  H1Expected = numericalDerivative11<Vector3, Pose2>(
134  [&factor, &pose1, &pose2, &base2](const Pose2& pose_arg) {
135  return factor.evaluateError(pose_arg, pose1, base2, pose2);
136  },
137  base1);
138  H2Expected = numericalDerivative11<Vector3, Pose2>(
139  [&factor, &pose2, &base1, &base2](const Pose2& pose_arg) {
140  return factor.evaluateError(base1, pose_arg, base2, pose2);
141  },
142  pose1);
143  H3Expected = numericalDerivative11<Vector3, Pose2>(
144  [&factor, &pose1, &base1, &pose2](const Pose2& pose_arg) {
145  return factor.evaluateError(base1, pose1, pose_arg, pose2);
146  },
147  base2);
148  H4Expected = numericalDerivative11<Vector3, Pose2>(
149  [&factor, &pose1, &base1, &base2](const Pose2& pose_arg) {
150  return factor.evaluateError(base1, pose1, base2, pose_arg);
151  },
152  pose2);
153 
154  // Verify the Jacobians are correct
155  EXPECT(assert_equal(H1Expected, H1Actual, 1e-9));
156  EXPECT(assert_equal(H2Expected, H2Actual, 1e-9));
157  EXPECT(assert_equal(H3Expected, H3Actual, 1e-9));
158  EXPECT(assert_equal(H4Expected, H4Actual, 1e-9));
159 }
160 
161 //*************************************************************************
162 int main() {
163  TestResult tr;
164  return TestRegistry::runAllTests(tr);
165 }
166 //*************************************************************************
167 
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
simple_graph::b1
Vector2 b1(2, -1)
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
gtsam::DeltaFactor
Definition: TSAMFactors.h:29
j
Key j(2)
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TSAMFactors.h
TSAM 1 Factors, simpler than the hierarchical TSAM 2.
TestHarness.h
simple_graph::b2
Vector2 b2(4, -5)
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::OdometryFactorBase::evaluateError
Vector evaluateError(const Pose2 &base1, const Pose2 &pose1, const Pose2 &base2, const Pose2 &pose2, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4) const override
Evaluate measurement error h(x)-z.
Definition: TSAMFactors.h:138
main
int main()
Definition: testTSAMFactors.cpp:162
Point2.h
2D Point
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::OdometryFactorBase
Definition: TSAMFactors.h:116
numericalDerivative.h
Some functions to compute numerical derivatives.
TEST
TEST(DeltaFactor, all)
Definition: testTSAMFactors.cpp:32
gtsam::DeltaFactorBase::evaluateError
Vector evaluateError(const Pose2 &base1, const Pose2 &pose, const Pose2 &base2, const Point2 &point, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4) const override
Evaluate measurement error h(x)-z.
Definition: TSAMFactors.h:82
Eigen::all
static const Eigen::internal::all_t all
Definition: IndexedViewHelper.h:171
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
Vector2
Definition: test_operator_overloading.cpp:18
i
Key i(1)
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
TestResult
Definition: TestResult.h:26
gtsam::DeltaFactorBase
Definition: TSAMFactors.h:60
gtsam
traits
Definition: SFMdata.h:40
pose1
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
std
Definition: BFloat16.h:88
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::DeltaFactor::evaluateError
Vector evaluateError(const Pose2 &pose, const Point2 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate measurement error h(x)-z.
Definition: TSAMFactors.h:51
measurement
static Point2 measurement(323.0, 240.0)
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:54