SFMExample_SmartFactorPCG.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 
18 // For an explanation of these headers, see SFMExample_SmartFactor.cpp
19 #include "SFMdata.h"
21 
22 // These extra headers allow us a LM outer loop with PCG linear solver (inner loop)
25 #include <gtsam/linear/PCGSolver.h>
26 
27 using namespace std;
28 using namespace gtsam;
29 
30 // Make the typename short so it looks much cleaner
32 
33 // create a typedef to the camera type
35 
36 /* ************************************************************************* */
37 int main(int argc, char* argv[]) {
38  // Define the camera calibration parameters
39  Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0));
40 
41  // Define the camera observation noise model
42  auto measurementNoise =
43  noiseModel::Isotropic::Sigma(2, 1.0); // one pixel in u and v
44 
45  // Create the set of ground-truth landmarks and poses
46  vector<Point3> points = createPoints();
47  vector<Pose3> poses = createPoses();
48 
49  // Create a factor graph
51 
52  // Simulated measurements from each camera pose, adding them to the factor graph
53  for (size_t j = 0; j < points.size(); ++j) {
54  // every landmark represent a single landmark, we use shared pointer to init
55  // the factor, and then insert measurements.
56  SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K));
57 
58  for (size_t i = 0; i < poses.size(); ++i) {
59  // generate the 2D measurement
60  Camera camera(poses[i], K);
61  Point2 measurement = camera.project(points[j]);
62 
63  // call add() function to add measurement into a single factor
64  smartfactor->add(measurement, i);
65  }
66 
67  // insert the smart factor in the graph
68  graph.push_back(smartfactor);
69  }
70 
71  // Add a prior on pose x0. This indirectly specifies where the origin is.
72  // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
73  auto noise = noiseModel::Diagonal::Sigmas(
74  (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
75  graph.addPrior(0, poses[0], noise);
76 
77  // Fix the scale ambiguity by adding a prior
78  graph.addPrior(1, poses[0], noise);
79 
80  // Create the initial estimate to the solution
81  Values initialEstimate;
82  Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20));
83  for (size_t i = 0; i < poses.size(); ++i)
84  initialEstimate.insert(i, poses[i].compose(delta));
85 
86  // We will use LM in the outer optimization loop, but by specifying
87  // "Iterative" below We indicate that an iterative linear solver should be
88  // used. In addition, the *type* of the iterativeParams decides on the type of
89  // iterative solver, in this case the SPCG (subgraph PCG)
91  parameters.linearSolverType = NonlinearOptimizerParams::Iterative;
92  parameters.absoluteErrorTol = 1e-10;
93  parameters.relativeErrorTol = 1e-10;
94  parameters.maxIterations = 500;
96  boost::make_shared<PCGSolverParameters>();
97  pcg->preconditioner_ =
98  boost::make_shared<BlockJacobiPreconditionerParameters>();
99  // Following is crucial:
100  pcg->setEpsilon_abs(1e-10);
101  pcg->setEpsilon_rel(1e-10);
102  parameters.iterativeParams = pcg;
103 
104  LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
105  Values result = optimizer.optimize();
106 
107  // Display result as in SFMExample_SmartFactor.run
108  result.print("Final results:\n");
109  Values landmark_result;
110  for (size_t j = 0; j < points.size(); ++j) {
111  auto smart = boost::dynamic_pointer_cast<SmartFactor>(graph[j]);
112  if (smart) {
113  boost::optional<Point3> point = smart->point(result);
114  if (point) // ignore if boost::optional return nullptr
115  landmark_result.insert(j, *point);
116  }
117  }
118 
119  landmark_result.print("Landmark results:\n");
120  cout << "final error: " << graph.error(result) << endl;
121  cout << "number of iterations: " << optimizer.iterations() << endl;
122 
123  return 0;
124 }
125 /* ************************************************************************* */
126 
PinholePose< Cal3_S2 > Camera
Smart factor on poses, assuming camera calibration is fixed.
virtual const Values & optimize()
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)
double measurement(10.0)
Definition: Half.h:150
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:166
NonlinearFactorGraph graph
double absoluteErrorTol
The maximum absolute error decrease to stop iterating (default 1e-5)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Point3 point(10, 0,-5)
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
std::vector< gtsam::Point3 > createPoints()
Definition: SFMdata.h:37
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
Values result
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
IterativeOptimizationParameters::shared_ptr iterativeParams
The container for iterativeOptimization parameters. used in CG Solvers.
static ConjugateGradientParameters parameters
traits
Definition: chartTesting.h:28
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:77
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
Simple example for the structure-from-motion problems.
boost::shared_ptr< PCGSolverParameters > shared_ptr
Definition: PCGSolver.h:39
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Vector3 Point3
Definition: Point3.h:35
double error(const Values &values) const
int main(int argc, char *argv[])
Definition: camera.h:36
static const CalibratedCamera camera(kDefaultPose)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
boost::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
LinearSolverType linearSolverType
The type of linear solver to use in the nonlinear optimizer.
std::ptrdiff_t j
size_t maxIterations
The maximum iterations to stop iterating (default 100)
size_t iterations() const
return number of iterations in current optimizer state


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