g2o
Loading...
Searching...
No Matches
bal_example.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2012 R. Kümmerle
3// All rights reserved.
4//
5// Redistribution and use in source and binary forms, with or without
6// modification, are permitted provided that the following conditions are
7// met:
8//
9// * Redistributions of source code must retain the above copyright notice,
10// this list of conditions and the following disclaimer.
11// * Redistributions in binary form must reproduce the above copyright
12// notice, this list of conditions and the following disclaimer in the
13// documentation and/or other materials provided with the distribution.
14//
15// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26
27#include <Eigen/Core>
28#include <Eigen/Geometry>
29#include <cassert>
30#include <iostream>
31#include <string_view>
32
40#include "g2o/core/solver.h"
44
45#if defined G2O_HAVE_CHOLMOD
47#else
49#endif
50
51using namespace std;
52
53namespace g2o {
54namespace bal {
56}
57} // namespace g2o
58
69class VertexCameraBAL : public g2o::BaseVertex<9, g2o::bal::Vector9> {
70 public:
73
74 bool read(std::istream& /*is*/) override {
75 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
76 return false;
77 }
78
79 bool write(std::ostream& /*os*/) const override {
80 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
81 return false;
82 }
83
84 void setToOriginImpl() override {
85 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
86 }
87
88 void oplusImpl(const double* update) override {
89 g2o::bal::Vector9::ConstMapType v(update, VertexCameraBAL::Dimension);
90 _estimate += v;
91 }
92};
93
99class VertexPointBAL : public g2o::BaseVertex<3, g2o::Vector3> {
100 public:
103
104 bool read(std::istream& /*is*/) override {
105 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
106 return false;
107 }
108
109 bool write(std::ostream& /*os*/) const override {
110 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
111 return false;
112 }
113
114 void setToOriginImpl() override {
115 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
116 }
117
118 void oplusImpl(const double* update) override {
119 g2o::Vector3::ConstMapType v(update);
120 _estimate += v;
121 }
122};
123
147 : public g2o::BaseBinaryEdge<2, g2o::Vector2, VertexCameraBAL,
148 VertexPointBAL> {
149 public:
152 bool read(std::istream& /*is*/) override {
153 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
154 return false;
155 }
156 bool write(std::ostream& /*os*/) const override {
157 cerr << __PRETTY_FUNCTION__ << " not implemented yet" << endl;
158 return false;
159 }
160
164 template <typename T>
165 bool operator()(const T* p_camera, const T* p_point, T* p_error) const {
166 typename g2o::VectorN<9, T>::ConstMapType camera(p_camera);
167 typename g2o::VectorN<3, T>::ConstMapType point(p_point);
168
169 typename g2o::VectorN<3, T> p;
170
171 // Rodrigues' formula for the rotation
172 T theta = camera.template head<3>().norm();
173 if (theta > T(0)) {
174 g2o::VectorN<3, T> v = camera.template head<3>() / theta;
175 T cth = cos(theta);
176 T sth = sin(theta);
177
178 g2o::VectorN<3, T> vXp = v.cross(point);
179 T vDotp = v.dot(point);
180 T oneMinusCth = T(1) - cth;
181
182 p = point * cth + vXp * sth + v * vDotp * oneMinusCth;
183 } else {
184 // taylor expansion for theta close to zero
185 p = point + camera.template head<3>().cross(point);
186 }
187
188 // translation of the camera
189 p += camera.template segment<3>(3);
190
191 // perspective division
192 g2o::VectorN<2, T> projectedPoint = -p.template head<2>() / p(2);
193
194 // conversion to pixel coordinates
195 T radiusSqr = projectedPoint.squaredNorm();
196 const T& f = camera(6);
197 const T& k1 = camera(7);
198 const T& k2 = camera(8);
199 T r_p = T(1) + k1 * radiusSqr + k2 * radiusSqr * radiusSqr;
200 g2o::VectorN<2, T> prediction = f * r_p * projectedPoint;
201
202 // compute the error
203 typename g2o::VectorN<2, T>::MapType error(p_error);
204 error = prediction - measurement().cast<T>();
205 (void)error;
206 return true;
207 }
208
210};
211
212int main(int argc, char** argv) {
213 int maxIterations;
214 bool verbose;
215 bool usePCG;
216 string outputFilename;
217 string inputFilename;
218 string statsFilename;
220 arg.param("i", maxIterations, 5, "perform n iterations");
221 arg.param("o", outputFilename, "", "write points into a vrml file");
222 arg.param("pcg", usePCG, false, "use PCG instead of the Cholesky");
223 arg.param("v", verbose, false, "verbose output of the optimization process");
224 arg.param("stats", statsFilename, "", "specify a file for the statistics");
225 arg.paramLeftOver("graph-input", inputFilename, "",
226 "file which will be processed");
227
228 arg.parseArgs(argc, argv);
229
230 using BalBlockSolver = g2o::BlockSolver<g2o::BlockSolverTraits<9, 3>>;
231 using BalLinearSolverPCG =
233
234 g2o::SparseOptimizer optimizer;
235 std::unique_ptr<g2o::LinearSolver<BalBlockSolver::PoseMatrixType>>
236 linearSolver;
237 if (usePCG) {
238 cout << "Using PCG" << endl;
239 linearSolver = std::make_unique<BalLinearSolverPCG>();
240 } else {
241#ifdef G2O_HAVE_CHOLMOD
242 string_view choleskySolverName = "CHOLMOD";
243 using BalLinearSolver =
245#else
246 string_view choleskySolverName = "Eigen";
247 using BalLinearSolver =
249#endif
250 cout << "Using Cholesky: " << choleskySolverName << endl;
251 auto cholesky = std::make_unique<BalLinearSolver>();
252 cholesky->setBlockOrdering(true);
253 linearSolver = std::move(cholesky);
254 }
257 std::make_unique<BalBlockSolver>(std::move(linearSolver)));
258
259 // solver->setUserLambdaInit(1);
260 optimizer.setAlgorithm(solver);
261 if (statsFilename.size() > 0) {
262 optimizer.setComputeBatchStatistics(true);
263 }
264
265 vector<VertexPointBAL*> points;
266 vector<VertexCameraBAL*> cameras;
267
268 // parse BAL dataset
269 cout << "Loading BAL dataset " << inputFilename << endl;
270 {
271 ifstream ifs(inputFilename.c_str());
272 int numCameras, numPoints, numObservations;
273 ifs >> numCameras >> numPoints >> numObservations;
274
275 cerr << PVAR(numCameras) << " " << PVAR(numPoints) << " "
276 << PVAR(numObservations) << endl;
277
278 int id = 0;
279 cameras.reserve(numCameras);
280 for (int i = 0; i < numCameras; ++i, ++id) {
282 cam->setId(id);
283 optimizer.addVertex(cam);
284 cameras.push_back(cam);
285 }
286
287 points.reserve(numPoints);
288 for (int i = 0; i < numPoints; ++i, ++id) {
290 p->setId(id);
291 p->setMarginalized(true);
292 bool addedVertex = optimizer.addVertex(p);
293 if (!addedVertex) {
294 cerr << "failing adding vertex" << endl;
295 }
296 points.push_back(p);
297 }
298
299 // read in the observation
300 for (int i = 0; i < numObservations; ++i) {
301 int camIndex, pointIndex;
302 double obsX, obsY;
303 ifs >> camIndex >> pointIndex >> obsX >> obsY;
304
305 assert(camIndex >= 0 && (size_t)camIndex < cameras.size() &&
306 "Index out of bounds");
307 VertexCameraBAL* cam = cameras[camIndex];
308 assert(pointIndex >= 0 && (size_t)pointIndex < points.size() &&
309 "Index out of bounds");
310 VertexPointBAL* point = points[pointIndex];
311
313 e->setVertex(0, cam);
314 e->setVertex(1, point);
315 e->setInformation(g2o::Matrix2::Identity());
316 e->setMeasurement(g2o::Vector2(obsX, obsY));
317 bool addedEdge = optimizer.addEdge(e);
318 if (!addedEdge) {
319 cerr << "error adding edge" << endl;
320 }
321 }
322
323 // read in the camera params
324 for (int i = 0; i < numCameras; ++i) {
325 g2o::bal::Vector9 cameraParameter;
326 for (int j = 0; j < 9; ++j) ifs >> cameraParameter(j);
327 VertexCameraBAL* cam = cameras[i];
328 cam->setEstimate(cameraParameter);
329 }
330
331 // read in the points
332 for (int i = 0; i < numPoints; ++i) {
333 g2o::Vector3 p;
334 ifs >> p(0) >> p(1) >> p(2);
335 VertexPointBAL* point = points[i];
336 point->setEstimate(p);
337 }
338 }
339 cout << "done." << endl;
340
341 cout << "Initializing ... " << flush;
342 optimizer.initializeOptimization();
343 cout << "done." << endl;
344 optimizer.setVerbose(verbose);
345 cout << "Start to optimize" << endl;
346 optimizer.optimize(maxIterations);
347
348 if (statsFilename != "") {
349 cerr << "writing stats to file \"" << statsFilename << "\" ... ";
350 ofstream fout(statsFilename.c_str());
351 const g2o::BatchStatisticsContainer& bsc = optimizer.batchStatistics();
352 for (size_t i = 0; i < bsc.size(); i++) fout << bsc[i] << endl;
353 cerr << "done." << endl;
354 }
355
356 // dump the points
357 if (outputFilename.size() > 0) {
358 ofstream fout(outputFilename.c_str()); // loadable with meshlab
359 fout << "#VRML V2.0 utf8\n"
360 << "Shape {\n"
361 << " appearance Appearance {\n"
362 << " material Material {\n"
363 << " diffuseColor " << 1 << " " << 0 << " " << 0 << "\n"
364 << " ambientIntensity 0.2\n"
365 << " emissiveColor 0.0 0.0 0.0\n"
366 << " specularColor 0.0 0.0 0.0\n"
367 << " shininess 0.2\n"
368 << " transparency 0.0\n"
369 << " }\n"
370 << " }\n"
371 << " geometry PointSet {\n"
372 << " coord Coordinate {\n"
373 << " point [\n";
374 for (vector<VertexPointBAL*>::const_iterator it = points.begin();
375 it != points.end(); ++it) {
376 fout << (*it)->estimate().transpose() << endl;
377 }
378 fout << " ]\n"
379 << " }\n"
380 << "}\n"
381 << " }\n";
382 }
383
384 return 0;
385}
#define G2O_MAKE_AUTO_AD_FUNCTIONS
edge representing the observation of a world feature by a camera
bool write(std::ostream &) const override
write the vertex to a stream
bool operator()(const T *p_camera, const T *p_point, T *p_error) const
bool read(std::istream &) override
read the vertex from a stream, i.e., the internal state of the vertex
camera vertex which stores the parameters for a pinhole camera
bool read(std::istream &) override
read the vertex from a stream, i.e., the internal state of the vertex
bool write(std::ostream &) const override
write the vertex to a stream
void oplusImpl(const double *update) override
void setToOriginImpl() override
sets the node to the origin (used in the multilevel stuff)
3D world feature
void setToOriginImpl() override
sets the node to the origin (used in the multilevel stuff)
bool write(std::ostream &) const override
write the vertex to a stream
void oplusImpl(const double *update) override
bool read(std::istream &) override
read the vertex from a stream, i.e., the internal state of the vertex
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition base_edge.h:119
virtual void setMeasurement(const Measurement &m)
Definition base_edge.h:122
void setInformation(const InformationType &information)
Definition base_edge.h:111
const ErrorVector & error() const
Definition base_edge.h:103
Templatized BaseVertex.
Definition base_vertex.h:51
static const int Dimension
dimension of the estimate (minimal) in the manifold space
Definition base_vertex.h:56
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Implementation of a solver operating on the blocks of the Hessian.
Command line parsing of argc and argv.
bool parseArgs(int argc, char **argv, bool exitOnError=true)
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
void setVertex(size_t i, Vertex *v)
basic solver for Ax = b which has to reimplemented for different linear algebra libraries
linear solver which uses the sparse Cholesky solver from Eigen
linear solver using PCG, pre-conditioner is block Jacobi
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
Implementation of the Levenberg Algorithm.
int optimize(int iterations, bool online=false)
void setVerbose(bool verbose)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
void setAlgorithm(OptimizationAlgorithm *algorithm)
const BatchStatisticsContainer & batchStatistics() const
void setComputeBatchStatistics(bool computeBatchStatistics)
int main()
Definition gicp_demo.cpp:44
#define __PRETTY_FUNCTION__
Definition macros.h:90
VectorN< 9 > Vector9
VectorN< 3 > Vector3
Definition eigen_types.h:51
Eigen::Matrix< T, N, 1, Eigen::ColMajor > VectorN
Definition eigen_types.h:49
std::vector< G2OBatchStatistics > BatchStatisticsContainer
Definition batch_stats.h:86
VectorN< 2 > Vector2
Definition eigen_types.h:50
Definition jet.h:876
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)