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;
96  std::make_shared<PCGSolverParameters>();
97  pcg->preconditioner = std::make_shared<BlockJacobiPreconditionerParameters>();
98  // Following is crucial:
99  pcg->epsilon_abs = 1e-10;
100  pcg->epsilon_rel = 1e-10;
101  parameters.iterativeParams = pcg;
102 
103  LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters);
104  Values result = optimizer.optimize();
105 
106  // Display result as in SFMExample_SmartFactor.run
107  result.print("Final results:\n");
108  Values landmark_result;
109  for (size_t j = 0; j < points.size(); ++j) {
110  auto smart = std::dynamic_pointer_cast<SmartFactor>(graph[j]);
111  if (smart) {
112  std::optional<Point3> point = smart->point(result);
113  if (point) // ignore if std::optional return nullptr
114  landmark_result.insert(j, *point);
115  }
116  }
117 
118  landmark_result.print("Landmark results:\n");
119  cout << "final error: " << graph.error(result) << endl;
120  cout << "number of iterations: " << optimizer.iterations() << endl;
121 
122  return 0;
123 }
124 /* ************************************************************************* */
125 
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
gtsam::createPoints
std::vector< Point3 > createPoints()
Create a set of ground-truth landmarks.
Definition: SFMdata.h:43
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Camera
Definition: camera.h:36
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Camera
PinholePose< Cal3_S2 > Camera
Definition: SFMExample_SmartFactorPCG.cpp:34
result
Values result
Definition: OdometryOptimize.cpp:8
SmartFactor
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
Definition: SFMExample_SmartFactorPCG.cpp:31
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::Pose3
Definition: Pose3.h:37
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
gtsam::SmartProjectionPoseFactor
Definition: SmartProjectionPoseFactor.h:45
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
PCGSolver.h
gtsam::NonlinearFactorGraph::addPrior
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Definition: NonlinearFactorGraph.h:199
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::Cal3_S2::shared_ptr
std::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
gtsam::PCGSolverParameters::shared_ptr
std::shared_ptr< PCGSolverParameters > shared_ptr
Definition: PCGSolver.h:38
SmartProjectionPoseFactor.h
Smart factor on poses, assuming camera calibration is fixed.
gtsam::NonlinearOptimizer::iterations
size_t iterations() const
return number of iterations in current optimizer state
Definition: NonlinearOptimizer.cpp:53
gtsam::createPoses
std::vector< Pose3 > createPoses(const Pose3 &init=Pose3(Rot3::Ypr(M_PI_2, 0, -M_PI_2), {30, 0, 0}), const Pose3 &delta=Pose3(Rot3::Ypr(0, -M_PI_4, 0), {sin(M_PI_4) *30, 0, 30 *(1 - sin(M_PI_4))}), int steps=8)
Definition: SFMdata.h:62
gtsam::Values::print
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:66
gtsam
traits
Definition: SFMdata.h:40
K
#define K
Definition: igam.h:8
gtsam::ConjugateGradientParameters::maxIterations
size_t maxIterations
maximum number of cg iterations
Definition: ConjugateGradientSolver.h:35
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
main
int main(int argc, char *argv[])
Definition: SFMExample_SmartFactorPCG.cpp:37
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
Preconditioner.h
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::SmartProjectionPoseFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: SmartProjectionPoseFactor.h:59
camera
static const CalibratedCamera camera(kDefaultPose)
gtsam::PinholePose
Definition: PinholePose.h:239
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
SFMdata.h
Simple example for the structure-from-motion problems.
ceres::Vector
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Definition: gtsam/3rdparty/ceres/eigen.h:38
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
measurement
static Point2 measurement(323.0, 240.0)
gtsam::CalibratedCamera::project
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
Definition: CalibratedCamera.cpp:188


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:35:15