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 #include <boost/assign.hpp>
29 #include <boost/assign/std/vector.hpp>
30 
31 using namespace std;
32 using namespace gtsam;
33 using namespace boost::assign;
34 
35 // Some common constants
36 static const boost::shared_ptr<Cal3_S2> sharedCal = //
37  boost::make_shared<Cal3_S2>(1500, 1200, 0, 640, 480);
38 
39 // Looking along X-axis, 1 meter above ground plane (x-y)
40 static const Rot3 upright = Rot3::Ypr(-M_PI / 2, 0., -M_PI / 2);
41 static const Pose3 pose1 = Pose3(upright, gtsam::Point3(0, 0, 1));
43 
44 // landmark ~5 meters infront of camera
45 static const Point3 landmark(5, 0.5, 1.2);
46 
47 // 1. Project two landmarks into two cameras and triangulate
49 
50 //******************************************************************************
51 TEST( triangulation, TriangulationFactor ) {
52 
53  Key pointKey(1);
56  Factor factor(camera1, z1, model, pointKey);
57 
58  // Use the factor to calculate the Jacobians
59  Matrix HActual;
60  factor.evaluateError(landmark, HActual);
61 
62  Matrix HExpected = numericalDerivative11<Vector,Point3>(
63  boost::bind(&Factor::evaluateError, &factor, _1, boost::none), landmark);
64 
65  // Verify the Jacobians are correct
66  CHECK(assert_equal(HExpected, HActual, 1e-3));
67 }
68 
69 //******************************************************************************
70 TEST( triangulation, TriangulationFactorStereo ) {
71 
72  Key pointKey(1);
73  SharedNoiseModel model=noiseModel::Isotropic::Sigma(3,0.5);
74  Cal3_S2Stereo::shared_ptr stereoCal(new Cal3_S2Stereo(1500, 1200, 0, 640, 480, 0.5));
75  StereoCamera camera2(pose1, stereoCal);
76 
77  StereoPoint2 z2 = camera2.project(landmark);
78 
80  Factor factor(camera2, z2, model, pointKey);
81 
82  // Use the factor to calculate the Jacobians
83  Matrix HActual;
84  factor.evaluateError(landmark, HActual);
85 
86  Matrix HExpected = numericalDerivative11<Vector,Point3>(
87  boost::bind(&Factor::evaluateError, &factor, _1, boost::none), landmark);
88 
89  // Verify the Jacobians are correct
90  CHECK(assert_equal(HExpected, HActual, 1e-3));
91 
92  // compare same problem against expression factor
93  Expression<StereoPoint2>::UnaryFunction<Point3>::type f = boost::bind(&StereoCamera::project2, camera2, _1, boost::none, _2);
94  Expression<Point3> point_(pointKey);
95  Expression<StereoPoint2> project2_(f, point_);
96 
97  ExpressionFactor<StereoPoint2> eFactor(model, z2, project2_);
98 
99  Values values;
100  values.insert(pointKey, landmark);
101 
102  vector<Matrix> HActual1(1), HActual2(1);
103  Vector error1 = factor.unwhitenedError(values, HActual1);
104  Vector error2 = eFactor.unwhitenedError(values, HActual2);
105  EXPECT(assert_equal(error1, error2));
106  EXPECT(assert_equal(HActual1[0], HActual2[0]));
107 }
108 
109 //******************************************************************************
110 int main() {
111  TestResult tr;
112  return TestRegistry::runAllTests(tr);
113 }
114 //******************************************************************************
static Point2 project2(const CalibratedCamera &camera, const Point3 &point)
#define CHECK(condition)
Definition: Test.h:109
static int runAllTests(TestResult &result)
noiseModel::Diagonal::shared_ptr model
void insert(Key j, const Value &val)
Definition: Values.cpp:140
static const Rot3 upright
Vector2 Point2
Definition: Point2.h:27
static const Point3 landmark(5, 0.5, 1.2)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
#define M_PI
Definition: main.h:78
leaf::MyValues values
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Definition: Half.h:150
Some functions to compute numerical derivatives.
static const Pose3 pose1
const gtsam::Key pointKey
Point2 z2
TEST(triangulation, TriangulationFactor)
Expressions for Block Automatic Differentiation.
PinholeCamera< Cal3_S2 > camera2(pose2,*sharedCal)
Base class for all pinhole cameras.
boost::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
Eigen::VectorXd Vector
Definition: Vector.h:38
#define EXPECT(condition)
Definition: Test.h:151
Functions for triangulation.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
A Stereo Camera based on two Simple Cameras.
StereoPoint2 project(const Point3 &point) const
Project 3D point to StereoPoint2 (uL,uR,v)
Vector3 Point3
Definition: Point3.h:35
PinholeCamera< Cal3_S2 > camera1(pose1,*sharedCal)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Calibration used by Bundler.
static const boost::shared_ptr< Cal3_S2 > sharedCal
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


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