FisheyeExample.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 // For loading the data
28 #include "SFMdata.h"
29 
30 // Camera observations of landmarks will be stored as Point2 (x, y).
31 #include <gtsam/geometry/Point2.h>
32 
33 // Each variable in the system (poses and landmarks) must be identified with a
34 // unique key. We can either use simple integer keys (1, 2, 3, ...) or symbols
35 // (X1, X2, L1). Here we will use Symbols
36 #include <gtsam/inference/Symbol.h>
37 
38 // Use GaussNewtonOptimizer to solve graph
41 #include <gtsam/nonlinear/Values.h>
42 
43 // In GTSAM, measurement functions are represented as 'factors'. Several common
44 // factors have been provided with the library for solving robotics/SLAM/Bundle
45 // Adjustment problems. Here we will use Projection factors to model the
46 // camera's landmark observations. Also, we will initialize the robot at some
47 // location using a Prior factor.
49 #include <gtsam/slam/PriorFactor.h>
51 
52 #include <fstream>
53 #include <vector>
54 
55 using namespace std;
56 using namespace gtsam;
57 
58 using symbol_shorthand::L; // for landmarks
59 using symbol_shorthand::X; // for poses
60 
61 /* ************************************************************************* */
62 int main(int argc, char *argv[]) {
63  // Define the camera calibration parameters
64  auto K = std::make_shared<Cal3Fisheye>(
65  278.66, 278.48, 0.0, 319.75, 241.96, -0.013721808247486035,
66  0.020727425669427896, -0.012786476702685545, 0.0025242267320687625);
67 
68  // Define the camera observation noise model, 1 pixel stddev
69  auto measurementNoise = noiseModel::Isotropic::Sigma(2, 1.0);
70 
71  // Create the set of ground-truth landmarks
72  const vector<Point3> points = createPoints();
73 
74  // Create the set of ground-truth poses
75  const vector<Pose3> poses = createPoses();
76 
77  // Create a Factor Graph and Values to hold the new data
79  Values initialEstimate;
80 
81  // Add a prior on pose x0, 0.1 rad on roll,pitch,yaw, and 30cm std on x,y,z
82  auto posePrior = noiseModel::Diagonal::Sigmas(
83  (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished());
84  graph.emplace_shared<PriorFactor<Pose3>>(X(0), poses[0], posePrior);
85 
86  // Add a prior on landmark l0
87  auto pointPrior = noiseModel::Isotropic::Sigma(3, 0.1);
88  graph.emplace_shared<PriorFactor<Point3>>(L(0), points[0], pointPrior);
89 
90  // Add initial guesses to all observed landmarks
91  // Intentionally initialize the variables off from the ground truth
92  static const Point3 kDeltaPoint(-0.25, 0.20, 0.15);
93  for (size_t j = 0; j < points.size(); ++j)
94  initialEstimate.insert<Point3>(L(j), points[j] + kDeltaPoint);
95 
96  // Loop over the poses, adding the observations to the graph
97  for (size_t i = 0; i < poses.size(); ++i) {
98  // Add factors for each landmark observation
99  for (size_t j = 0; j < points.size(); ++j) {
101  Point2 measurement = camera.project(points[j]);
103  measurement, measurementNoise, X(i), L(j), K);
104  }
105 
106  // Add an initial guess for the current pose
107  // Intentionally initialize the variables off from the ground truth
108  static const Pose3 kDeltaPose(Rot3::Rodrigues(-0.1, 0.2, 0.25),
109  Point3(0.05, -0.10, 0.20));
110  initialEstimate.insert(X(i), poses[i] * kDeltaPose);
111  }
112 
114  params.setVerbosity("TERMINATION");
115  params.maxIterations = 10000;
116 
117  std::cout << "Optimizing the factor graph" << std::endl;
118  GaussNewtonOptimizer optimizer(graph, initialEstimate, params);
119  Values result = optimizer.optimize();
120  std::cout << "Optimization complete" << std::endl;
121 
122  std::cout << "initial error=" << graph.error(initialEstimate) << std::endl;
123  std::cout << "final error=" << graph.error(result) << std::endl;
124 
125  graph.saveGraph("examples/vio_batch.dot", result);
126 
127  return 0;
128 }
129 /* ************************************************************************* */
createPoses
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:56
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
ProjectionFactor.h
Reprojection of a LANDMARK to a 2D point.
gtsam::GaussNewtonOptimizer
Definition: GaussNewtonOptimizer.h:38
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
createPoints
std::vector< gtsam::Point3 > createPoints()
Definition: SFMdata.h:39
X
#define X
Definition: icosphere.cpp:20
gtsam::NonlinearFactorGraph::saveGraph
void saveGraph(const std::string &filename, const Values &values, const KeyFormatter &keyFormatter=DefaultKeyFormatter, const GraphvizFormatting &writer=GraphvizFormatting()) const
output to file with graphviz format, with Values/extra options.
Definition: NonlinearFactorGraph.cpp:160
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
result
Values result
Definition: OdometryOptimize.cpp:8
Point2.h
2D Point
GaussNewtonOptimizer.h
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::Pose3
Definition: Pose3.h:37
gtsam::GaussNewtonParams
Definition: GaussNewtonOptimizer.h:30
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::GenericProjectionFactor
Definition: ProjectionFactor.h:40
L
MatrixXd L
Definition: LLT_example.cpp:6
Symbol.h
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
main
int main(int argc, char *argv[])
Definition: FisheyeExample.cpp:62
gtsam
traits
Definition: chartTesting.h:28
PriorFactor.h
K
#define K
Definition: igam.h:8
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
camera
static const CalibratedCamera camera(kDefaultPose)
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Factor::size
size_t size() const
Definition: Factor.h:159
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)
Values.h
A non-templated config holding any types of Manifold-group elements.
gtsam::CalibratedCamera::project
Point2 project(const Point3 &point, OptionalJacobian< 2, 6 > Dcamera={}, OptionalJacobian< 2, 3 > Dpoint={}) const
Definition: CalibratedCamera.cpp:188
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
Cal3Fisheye.h
Calibration of a fisheye camera.


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:52