SFMExampleExpressions.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 
25 // The two new headers that allow using our Automatic Differentiation Expression framework
26 #include <gtsam/slam/expressions.h>
28 
29 // Header order is close to far
30 #include "SFMdata.h"
31 #include <gtsam/geometry/Point2.h>
33 #include <gtsam/nonlinear/Values.h>
34 #include <gtsam/inference/Symbol.h>
35 
36 #include <vector>
37 
38 using namespace std;
39 using namespace gtsam;
40 using namespace noiseModel;
41 
42 /* ************************************************************************* */
43 int main(int argc, char* argv[]) {
44 
45  Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0);
46  Isotropic::shared_ptr measurementNoise = Isotropic::Sigma(2, 1.0); // one pixel in u and v
47 
48  // Create the set of ground-truth landmarks and poses
49  vector<Point3> points = createPoints();
50  vector<Pose3> poses = createPoses();
51 
52  // Create a factor graph
54 
55  // Specify uncertainty on first pose prior
56  Vector6 sigmas; sigmas << Vector3(0.3,0.3,0.3), Vector3(0.1,0.1,0.1);
57  Diagonal::shared_ptr poseNoise = Diagonal::Sigmas(sigmas);
58 
59  // Here we don't use a PriorFactor but directly the ExpressionFactor class
60  // x0 is an Expression, and we create a factor wanting it to be equal to poses[0]
61  Pose3_ x0('x',0);
62  graph.addExpressionFactor(x0, poses[0], poseNoise);
63 
64  // We create a constant Expression for the calibration here
65  Cal3_S2_ cK(K);
66 
67  // Simulated measurements from each camera pose, adding them to the factor graph
68  for (size_t i = 0; i < poses.size(); ++i) {
69  Pose3_ x('x', i);
70  PinholeCamera<Cal3_S2> camera(poses[i], K);
71  for (size_t j = 0; j < points.size(); ++j) {
72  Point2 measurement = camera.project(points[j]);
73  // Below an expression for the prediction of the measurement:
74  Point3_ p('l', j);
75  Point2_ prediction = uncalibrate(cK, project(transformTo(x, p)));
76  // Again, here we use an ExpressionFactor
77  graph.addExpressionFactor(prediction, measurement, measurementNoise);
78  }
79  }
80 
81  // Add prior on first point to constrain scale, again with ExpressionFactor
82  Isotropic::shared_ptr pointNoise = Isotropic::Sigma(3, 0.1);
83  graph.addExpressionFactor(Point3_('l', 0), points[0], pointNoise);
84 
85  // Create perturbed initial
87  Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
88  for (size_t i = 0; i < poses.size(); ++i)
89  initial.insert(Symbol('x', i), poses[i].compose(delta));
90  for (size_t j = 0; j < points.size(); ++j)
91  initial.insert<Point3>(Symbol('l', j), points[j] + Point3(-0.25, 0.20, 0.15));
92  cout << "initial error = " << graph.error(initial) << endl;
93 
94  /* Optimize the graph and print results */
95  Values result = DoglegOptimizer(graph, initial).optimize();
96  cout << "final error = " << graph.error(result) << endl;
97 
98  return 0;
99 }
100 /* ************************************************************************* */
101 
Expression< Point3 > Point3_
int main(int argc, char *argv[])
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
virtual const Values & optimize()
Eigen::Vector3d Vector3
Definition: Vector.h:43
A non-templated config holding any types of Manifold-group elements.
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Vector2 Point2
Definition: Point2.h:27
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Values initial
double measurement(10.0)
Definition: Half.h:150
NonlinearFactorGraph graph
T compose(const T &t1, const T &t2)
Definition: lieProxies.h:39
std::vector< gtsam::Point3 > createPoints()
Definition: SFMdata.h:37
Values result
Factor graph that supports adding ExpressionFactors directly.
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
static Symbol x0('x', 0)
traits
Definition: chartTesting.h:28
std::vector< gtsam::Pose3 > createPoses(const gtsam::Pose3 &init=gtsam::Pose3(gtsam::Rot3::Ypr(M_PI/2, 0,-M_PI/2), gtsam::Point3(30, 0, 0)), const gtsam::Pose3 &delta=gtsam::Pose3(gtsam::Rot3::Ypr(0,-M_PI/4, 0), gtsam::Point3(sin(M_PI/4)*30, 0, 30 *(1-sin(M_PI/4)))), int steps=8)
Definition: SFMdata.h:54
float * p
Simple example for the structure-from-motion problems.
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
boost::shared_ptr< Isotropic > shared_ptr
Definition: NoiseModel.h:541
void addExpressionFactor(const Expression< T > &h, const T &z, const SharedNoiseModel &R)
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
Vector3 Point3
Definition: Point3.h:35
double error(const Values &values) const
static const CalibratedCamera camera(kDefaultPose)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
2D Point
std::ptrdiff_t j
Point2 uncalibrate(const CAL &K, const Point2 &p, OptionalJacobian< 2, 5 > Dcal, OptionalJacobian< 2, 2 > Dp)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:01