testInvDepthFactor3.cpp
Go to the documentation of this file.
1 /*
2  * testInvDepthFactor.cpp
3  *
4  * Created on: Apr 13, 2012
5  * Author: cbeall3
6  */
7 
9 
14 #include <gtsam/inference/Symbol.h>
15 
17 
18 using namespace std;
19 using namespace gtsam;
20 
21 static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480));
22 static SharedNoiseModel sigma(noiseModel::Unit::Create(2));
23 
24 // camera pose at (0,0,1) looking straight along the x-axis.
25 Pose3 level_pose = Pose3(Rot3::Ypr(-M_PI/2, 0., -M_PI/2), gtsam::Point3(0,0,1));
27 
30 
31 /* ************************************************************************* */
32 TEST( InvDepthFactor, optimize) {
33 
34  // landmark 5 meters infront of camera (camera center at (0,0,1))
35  Point3 landmark(5, 0, 1);
36 
37  // get expected projection using pinhole camera
38  Point2 expected_uv = level_camera.project(landmark);
39 
40  InvDepthCamera3<Cal3_S2> inv_camera(level_pose, K);
41  Vector5 inv_landmark((Vector(5) << 0., 0., 1., 0., 0.).finished());
42  // initialize inverse depth with "incorrect" depth of 1/4
43  // in reality this is 1/5, but initial depth is guessed
44  double inv_depth(1./4);
45 
48 
50  Symbol('x',1), Symbol('l',1), Symbol('d',1), K));
51  graph.push_back(factor);
52  graph += PoseConstraint(Symbol('x',1),level_pose);
53  initial.insert(Symbol('x',1), level_pose);
54  initial.insert(Symbol('l',1), inv_landmark);
55  initial.insert(Symbol('d',1), inv_depth);
56 
58  Values result = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize();
59 
60  // with a single factor the incorrect initialization of 1/4 should not move!
61  EXPECT(assert_equal(initial, result, 1e-9));
62 
64 
65  // add a camera 2 meters to the right
66  Pose3 right_pose = level_pose * Pose3(Rot3(), Point3(2,0,0));
67  PinholeCamera<Cal3_S2> right_camera(right_pose, *K);
68 
69  // projection measurement of landmark into right camera
70  // this measurement disagrees with the depth initialization
71  // and will push it to 1/5
72  Point2 right_uv = right_camera.project(landmark);
73 
75  Symbol('x',2), Symbol('l',1),Symbol('d',1),K));
76  graph.push_back(factor1);
77 
78  graph += PoseConstraint(Symbol('x',2),right_pose);
79 
80  initial.insert(Symbol('x',2), right_pose);
81 
82  Values result2 = LevenbergMarquardtOptimizer(graph, initial, lmParams).optimize();
83 
85  result2.at<Vector5>(Symbol('l',1)),
86  result2.at<double>(Symbol('d',1)));
87  EXPECT(assert_equal(landmark, result2_lmk, 1e-9));
88 
89  // TODO: need to add priors to make this work with
90  // Values result2 = optimize<NonlinearFactorGraph>(graph, initial,
91  // NonlinearOptimizationParameters(),MULTIFRONTAL, GN);
92 }
93 
94 
95 /* ************************************************************************* */
96 int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
97 /* ************************************************************************* */
Pose3 level_pose
virtual const Values & optimize()
static int runAllTests(TestResult &result)
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
#define M_PI
Definition: main.h:78
Values initial
int main()
static Cal3_S2::shared_ptr K(new Cal3_S2(1500, 1200, 0, 640, 480))
Definition: Half.h:150
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
NonlinearFactorGraph graph
static SharedNoiseModel sigma(noiseModel::Unit::Create(2))
static Point3 landmark(0, 0, 5)
NonlinearEquality< Pose3 > PoseConstraint
Base class for all pinhole cameras.
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
#define EXPECT(condition)
Definition: Test.h:151
PinholeCamera< Cal3_S2 > level_camera(level_pose,*K)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Inverse Depth Factor based on Civera09tro, Montiel06rss. Landmarks are initialized from the first cam...
traits
Definition: chartTesting.h:28
TEST(InvDepthFactor, optimize)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
LevenbergMarquardtParams lmParams
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
Definition: timeSFMBAL.h:63
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
Vector3 Point3
Definition: Point3.h:35
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
boost::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
InvDepthFactor3< Pose3, Vector5, double > InverseDepthFactor
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
JacobianFactor factor1(keyX, A11, b1, noiseModel::Isotropic::Sigma(2, sigma1))


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:47:31