testTriangulationFactor.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 
27 
28 using namespace std;
29 using namespace gtsam;
30 using namespace std::placeholders;
31 
32 // Some common constants
33 static const std::shared_ptr<Cal3_S2> sharedCal = //
34  std::make_shared<Cal3_S2>(1500, 1200, 0, 640, 480);
35 
36 // Looking along X-axis, 1 meter above ground plane (x-y)
37 static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2);
38 static const Pose3 pose1 = Pose3(upright, gtsam::Point3(0, 0, 1));
40 
41 // landmark ~5 meters infront of camera
42 static const Point3 landmark(5, 0.5, 1.2);
43 
44 // 1. Project two landmarks into two cameras and triangulate
46 
47 //******************************************************************************
48 TEST( triangulation, TriangulationFactor ) {
49 
50  Key pointKey(1);
53  Factor factor(camera1, z1, model, pointKey);
54 
55  // Use the factor to calculate the Jacobians
56  Matrix HActual;
57  factor.evaluateError(landmark, HActual);
58 
59  Matrix HExpected = numericalDerivative11<Vector,Point3>(
60  [&factor](const Point3& l) { return factor.evaluateError(l);}, landmark);
61 
62  // Verify the Jacobians are correct
63  CHECK(assert_equal(HExpected, HActual, 1e-3));
64 }
65 
66 //******************************************************************************
67 TEST( triangulation, TriangulationFactorStereo ) {
68 
69  Key pointKey(1);
70  SharedNoiseModel model=noiseModel::Isotropic::Sigma(3,0.5);
71  Cal3_S2Stereo::shared_ptr stereoCal(new Cal3_S2Stereo(1500, 1200, 0, 640, 480, 0.5));
72  StereoCamera camera2(pose1, stereoCal);
73 
75 
77  Factor factor(camera2, z2, model, pointKey);
78 
79  // Use the factor to calculate the Jacobians
80  Matrix HActual;
81  factor.evaluateError(landmark, HActual);
82 
83  Matrix HExpected = numericalDerivative11<Vector, Point3>(
84  [&factor](const Point3& l) { return factor.evaluateError(l);}, landmark);
85 
86  // Verify the Jacobians are correct
87  CHECK(assert_equal(HExpected, HActual, 1e-3));
88 
89  // compare same problem against expression factor
91  std::bind(&StereoCamera::project2, camera2, std::placeholders::_1,
92  nullptr, std::placeholders::_2);
94  Expression<StereoPoint2> project2_(f, point_);
95 
96  ExpressionFactor<StereoPoint2> eFactor(model, z2, project2_);
97 
98  Values values;
100 
101  vector<Matrix> HActual1(1), HActual2(1);
102  Vector error1 = factor.unwhitenedError(values, HActual1);
103  Vector error2 = eFactor.unwhitenedError(values, HActual2);
104  EXPECT(assert_equal(error1, error2));
105  EXPECT(assert_equal(HActual1[0], HActual2[0]));
106 }
107 
108 //******************************************************************************
109 int main() {
110  TestResult tr;
111  return TestRegistry::runAllTests(tr);
112 }
113 //******************************************************************************
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
camera1
PinholeCamera< Cal3_S2 > camera1(pose1, *sharedCal)
gtsam.examples.DogLegOptimizerExample.type
type
Definition: DogLegOptimizerExample.py:111
pointKey
const gtsam::Key pointKey
Definition: testRelativeElevationFactor.cpp:25
gtsam::TriangulationFactor
Definition: TriangulationFactor.h:31
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
project2
static Point2 project2(const CalibratedCamera &camera, const Point3 &point)
Definition: testCalibratedCamera.cpp:127
gtsam::Expression::UnaryFunction
Definition: Expression.h:69
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
landmark
static const Point3 landmark(5, 0.5, 1.2)
z1
Point2 z1
Definition: testTriangulationFactor.cpp:45
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Factor
Definition: Factor.h:69
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
upright
static const Rot3 upright
Definition: testTriangulationFactor.cpp:37
triangulation.h
Functions for triangulation.
gtsam::PinholeBaseK::project
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
gtsam::Expression
Definition: Expression.h:47
numericalDerivative.h
Some functions to compute numerical derivatives.
pose1
static const Pose3 pose1
Definition: testTriangulationFactor.cpp:38
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::PinholeCamera
Definition: PinholeCamera.h:33
TEST
TEST(triangulation, TriangulationFactor)
Definition: testTriangulationFactor.cpp:48
l
static const Line3 l(Rot3(), 1, 1)
PinholeCamera.h
Base class for all pinhole cameras.
gtsam::Cal3_S2Stereo::shared_ptr
std::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
sharedCal
static const std::shared_ptr< Cal3_S2 > sharedCal
Definition: testTriangulationFactor.cpp:33
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
TestResult
Definition: TestResult.h:26
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::ExpressionFactor::unwhitenedError
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Definition: ExpressionFactor.h:104
gtsam
traits
Definition: chartTesting.h:28
gtsam::Cal3_S2Stereo
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
leaf::values
leaf::MyValues values
gtsam::Values
Definition: Values.h:65
CHECK
#define CHECK(condition)
Definition: Test.h:108
gtsam::StereoPoint2
Definition: StereoPoint2.h:34
std
Definition: BFloat16.h:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::StereoCamera
Definition: StereoCamera.h:47
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
ExpressionFactor.h
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
main
int main()
Definition: testTriangulationFactor.cpp:109
M_PI
#define M_PI
Definition: mconf.h:117
camera2
static const Camera2 camera2(pose1, K2)
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
Expression.h
Expressions for Block Automatic Differentiation.
Cal3Bundler.h
Calibration used by Bundler.
gtsam::ExpressionFactor
Definition: Expression.h:36
StereoCamera.h
A Stereo Camera based on two Simple Cameras.
z2
static const Unit3 z2
Definition: testRotateFactor.cpp:43


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:07:09