testProjectionFactorPPP.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 
22 #include <gtsam/inference/Symbol.h>
23 #include <gtsam/geometry/Cal3DS2.h>
24 #include <gtsam/geometry/Cal3_S2.h>
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/geometry/Point3.h>
27 #include <gtsam/geometry/Point2.h>
28 
30 
31 using namespace std::placeholders;
32 using namespace std;
33 using namespace gtsam;
34 
35 // make a realistic calibration matrix
36 static double fov = 60; // degrees
37 static size_t w=640,h=480;
38 static Cal3_S2::shared_ptr K(new Cal3_S2(fov,w,h));
39 
40 // Create a noise model for the pixel error
41 static SharedNoiseModel model(noiseModel::Unit::Create(2));
42 
43 // Convenience for named keys
47 
49 
51 namespace gtsam {
52 template<>
53 struct traits<TestProjectionFactor> : public Testable<TestProjectionFactor> {
54 };
55 }
56 
57 /* ************************************************************************* */
58 TEST( ProjectionFactorPPP, nonStandard ) {
60 }
61 
62 /* ************************************************************************* */
63 TEST( ProjectionFactorPPP, Constructor) {
64  Key poseKey(X(1));
65  Key transformKey(T(1));
66  Key pointKey(L(1));
67 
68  Point2 measurement(323.0, 240.0);
69 
70  TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K);
71 }
72 
73 /* ************************************************************************* */
74 TEST( ProjectionFactorPPP, ConstructorWithTransform) {
75  Key poseKey(X(1));
76  Key transformKey(T(1));
77  Key pointKey(L(1));
78 
79  Point2 measurement(323.0, 240.0);
80  TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K);
81 }
82 
83 /* ************************************************************************* */
85  // Create two identical factors and make sure they're equal
86  Point2 measurement(323.0, 240.0);
87 
88  TestProjectionFactor factor1(measurement, model, X(1), T(1), L(1), K);
89  TestProjectionFactor factor2(measurement, model, X(1), T(1), L(1), K);
90 
91  CHECK(assert_equal(factor1, factor2));
92 }
93 
94 /* ************************************************************************* */
95 TEST( ProjectionFactorPPP, EqualsWithTransform ) {
96  // Create two identical factors and make sure they're equal
97  Point2 measurement(323.0, 240.0);
98  Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0));
99 
100  TestProjectionFactor factor1(measurement, model, X(1), T(1), L(1), K);
101  TestProjectionFactor factor2(measurement, model, X(1), T(1), L(1), K);
102 
103  CHECK(assert_equal(factor1, factor2));
104 }
105 
106 /* ************************************************************************* */
108  // Create the factor with a measurement that is 3 pixels off in x
109  Key poseKey(X(1));
110  Key transformKey(T(1));
111  Key pointKey(L(1));
112  Point2 measurement(323.0, 240.0);
113  TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K);
114 
115  // Set the linearization point
116  Pose3 pose(Rot3(), Point3(0,0,-6));
117  Point3 point(0.0, 0.0, 0.0);
118 
119  // Use the factor to calculate the error
120  Vector actualError(factor.evaluateError(pose, Pose3(), point));
121 
122  // The expected error is (-3.0, 0.0) pixels / UnitCovariance
123  Vector expectedError = Vector2(-3.0, 0.0);
124 
125  // Verify we get the expected error
126  CHECK(assert_equal(expectedError, actualError, 1e-9));
127 }
128 
129 /* ************************************************************************* */
130 TEST( ProjectionFactorPPP, ErrorWithTransform ) {
131  // Create the factor with a measurement that is 3 pixels off in x
132  Key poseKey(X(1));
133  Key transformKey(T(1));
134  Key pointKey(L(1));
135  Point2 measurement(323.0, 240.0);
136  Pose3 transform(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0));
137  TestProjectionFactor factor(measurement, model, poseKey,transformKey, pointKey, K);
138 
139  // Set the linearization point. The vehicle pose has been selected to put the camera at (-6, 0, 0)
140  Pose3 pose(Rot3(), Point3(-6.25, 0.10 , -1.0));
141  Point3 point(0.0, 0.0, 0.0);
142 
143  // Use the factor to calculate the error
144  Vector actualError(factor.evaluateError(pose, transform, point));
145 
146  // The expected error is (-3.0, 0.0) pixels / UnitCovariance
147  Vector expectedError = Vector2(-3.0, 0.0);
148 
149  // Verify we get the expected error
150  CHECK(assert_equal(expectedError, actualError, 1e-9));
151 }
152 
153 /* ************************************************************************* */
154 TEST( ProjectionFactorPPP, Jacobian ) {
155  // Create the factor with a measurement that is 3 pixels off in x
156  Key poseKey(X(1));
157  Key transformKey(T(1));
158  Key pointKey(L(1));
159  Point2 measurement(323.0, 240.0);
160  TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K);
161 
162  // Set the linearization point
163  Pose3 pose(Rot3(), Point3(0,0,-6));
164  Point3 point(0.0, 0.0, 0.0);
165 
166  // Use the factor to calculate the Jacobians
167  Matrix H1Actual, H2Actual, H3Actual;
168  factor.evaluateError(pose, Pose3(), point, H1Actual, H2Actual, H3Actual);
169 
170  // The expected Jacobians
171  Matrix H1Expected = (Matrix(2, 6) << 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.).finished();
172  Matrix H3Expected = (Matrix(2, 3) << 92.376, 0., 0., 0., 92.376, 0.).finished();
173 
174  // Verify the Jacobians are correct
175  CHECK(assert_equal(H1Expected, H1Actual, 1e-3));
176  CHECK(assert_equal(H3Expected, H3Actual, 1e-3));
177 
178  // Verify H2 with numerical derivative
179  Matrix H2Expected = numericalDerivative32<Vector, Pose3, Pose3, Point3>(
180  [&factor](const Pose3& pose, const Pose3& transform, const Point3& point) {
181  return factor.evaluateError(pose, transform, point);
182  },
183  pose, Pose3(), point);
184 
185  CHECK(assert_equal(H2Expected, H2Actual, 1e-5));
186 }
187 
188 /* ************************************************************************* */
189 TEST( ProjectionFactorPPP, JacobianWithTransform ) {
190  // Create the factor with a measurement that is 3 pixels off in x
191  Key poseKey(X(1));
192  Key transformKey(T(1));
193  Key pointKey(L(1));
194  Point2 measurement(323.0, 240.0);
195  Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0));
196  TestProjectionFactor factor(measurement, model, poseKey, transformKey, pointKey, K);
197 
198  // Set the linearization point. The vehicle pose has been selected to put the camera at (-6, 0, 0)
199  Pose3 pose(Rot3(), Point3(-6.25, 0.10 , -1.0));
200  Point3 point(0.0, 0.0, 0.0);
201 
202  // Use the factor to calculate the Jacobians
203  Matrix H1Actual, H2Actual, H3Actual;
204  factor.evaluateError(pose, body_P_sensor, point, H1Actual, H2Actual, H3Actual);
205 
206  // The expected Jacobians
207  Matrix H1Expected = (Matrix(2, 6) << -92.376, 0., 577.350, 0., 92.376, 0., -9.2376, -577.350, 0., 0., 0., 92.376).finished();
208  Matrix H3Expected = (Matrix(2, 3) << 0., -92.376, 0., 0., 0., -92.376).finished();
209 
210  // Verify the Jacobians are correct
211  CHECK(assert_equal(H1Expected, H1Actual, 1e-3));
212  CHECK(assert_equal(H3Expected, H3Actual, 1e-3));
213 
214  // Verify H2 with numerical derivative
215  Matrix H2Expected = numericalDerivative32<Vector, Pose3, Pose3, Point3>(
216  [&factor](const Pose3& pose, const Pose3& transform, const Point3& point) {
217  return factor.evaluateError(pose, transform, point);
218  },
220 
221  CHECK(assert_equal(H2Expected, H2Actual, 1e-5));
222 
223 
224 }
225 
226 /* ************************************************************************* */
227 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
228 /* ************************************************************************* */
229 
const gtsam::Key poseKey
Provides additional testing facilities for common data structures.
#define CHECK(condition)
Definition: Test.h:108
static SharedNoiseModel model(noiseModel::Unit::Create(2))
static int runAllTests(TestResult &result)
Vector2 Point2
Definition: Point2.h:32
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
static double fov
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
Some functions to compute numerical derivatives.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
const gtsam::Key pointKey
static Cal3_S2::shared_ptr K(new Cal3_S2(fov, w, h))
static Point2 measurement(323.0, 240.0)
std::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
Eigen::VectorXd Vector
Definition: Vector.h:38
ProjectionFactorPPP< Pose3, Point3 > TestProjectionFactor
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
TEST(ProjectionFactorPPP, nonStandard)
Derived from ProjectionFactor, but estimates body-camera transform in addition to body pose and 3D la...
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
traits
Definition: chartTesting.h:28
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Eigen::Vector2d Vector2
Definition: Vector.h:42
static size_t w
3D Point
static size_t h
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
Vector3 Point3
Definition: Point3.h:38
#define X
Definition: icosphere.cpp:20
2D Point
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The most common 5DOF 3D->2D calibration.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:39:09