40 #include "g2o/config.h" 64 using namespace Eigen;
68 bool operator()(SparseOptimizer::Edge*
const & e1, SparseOptimizer::Edge*
const & e2)
70 const SparseOptimizer::Vertex* to1 =
static_cast<const SparseOptimizer::Vertex*
>(e1->vertices()[1]);
71 const SparseOptimizer::Vertex* to2 =
static_cast<const SparseOptimizer::Vertex*
>(e2->vertices()[1]);
73 int i11 = e1->vertices()[0]->id(), i12 = e1->vertices()[1]->id();
77 int i21 = e2->vertices()[0]->id(), i22 = e2->vertices()[1]->id();
86 return to1->dimension() > to2->dimension();
102 int main(
int argc,
char** argv)
104 OptimizableGraph::initMultiThreading();
107 string inputFilename;
109 string outputfilename;
110 string solverProperties;
114 bool initialGuessOdometry;
118 bool listRobustKernels;
123 bool computeMarginals;
124 bool printSolverProperties;
127 int maxIterationsWithGain;
129 int updateGraphEachN = 10;
134 std::vector<int> gaugeList;
136 arg.
param(
"i", maxIterations, 5,
"perform n iterations, if negative consider the gain");
137 arg.
param(
"gain", gain, 1e-6,
"the gain used to stop optimization (default = 1e-6)");
138 arg.
param(
"ig",maxIterationsWithGain, std::numeric_limits<int>::max(),
"Maximum number of iterations with gain enabled (default: inf)");
139 arg.
param(
"v", verbose,
false,
"verbose output of the optimization process");
140 arg.
param(
"guess", initialGuess,
false,
"initial guess based on spanning tree");
141 arg.
param(
"guessOdometry", initialGuessOdometry,
false,
"initial guess based on odometry");
142 arg.
param(
"inc", incremental,
false,
"run incremetally");
143 arg.
param(
"update", updateGraphEachN, 10,
"updates after x odometry nodes");
144 arg.
param(
"guiout", guiOut,
false,
"gui output while running incrementally");
145 arg.
param(
"marginalize", marginalize,
false,
"on or off");
146 arg.
param(
"printSolverProperties", printSolverProperties,
false,
"print the properties of the solver");
147 arg.
param(
"solverProperties", solverProperties,
"",
"set the internal properties of a solver,\n\te.g., initialLambda=0.0001,maxTrialsAfterFailure=2");
148 arg.
param(
"gnudump", gnudump,
"",
"dump to gnuplot data file");
149 arg.
param(
"robustKernel", robustKernel,
"",
"use this robust error function");
150 arg.
param(
"robustKernelWidth", huberWidth, -1.,
"width for the robust Kernel (only if robustKernel)");
151 arg.
param(
"computeMarginals", computeMarginals,
false,
"computes the marginal covariances of something. FOR TESTING ONLY");
152 arg.
param(
"gaugeId", gaugeId, -1,
"force the gauge");
153 arg.
param(
"o", outputfilename,
"",
"output final version of the graph");
154 arg.
param(
"solver", strSolver,
"gn_var",
"specify which solver to use underneat\n\t {gn_var, lm_fix3_2, gn_fix6_3, lm_fix7_3}");
155 #ifndef G2O_DISABLE_DYNAMIC_LOADING_OF_LIBRARIES 157 arg.
param(
"solverlib", dummy,
"",
"specify a solver library which will be loaded");
158 arg.
param(
"typeslib", dummy,
"",
"specify a types library which will be loaded");
160 arg.
param(
"stats", statsFile,
"",
"specify a file for the statistics");
161 arg.
param(
"listTypes", listTypes,
false,
"list the registered types");
162 arg.
param(
"listRobustKernels", listRobustKernels,
false,
"list the registered robust kernels");
163 arg.
param(
"listSolvers", listSolvers,
false,
"list the available solvers");
164 arg.
param(
"renameTypes", loadLookup,
"",
"create a lookup for loading types into other types,\n\t TAG_IN_FILE=INTERNAL_TAG_FOR_TYPE,TAG2=INTERNAL2\n\t e.g., VERTEX_CAM=VERTEX_SE3:EXPMAP");
165 arg.
param(
"gaugeList", gaugeList, std::vector<int>(),
"set the list of gauges separated by commas without spaces \n e.g: 1,2,3,4,5 ");
166 arg.
param(
"summary", summaryFile,
"",
"append a summary of this optimization run to the summary file passed as argument");
167 arg.
paramLeftOver(
"graph-input", inputFilename,
"",
"graph file which will be processed",
true);
168 arg.
param(
"nonSequential", nonSequential,
false,
"apply the robust kernel only on loop closures and not odometries");
174 cout <<
"# Used Compiler: " << G2O_CXX_COMPILER << endl;
177 #ifndef G2O_DISABLE_DYNAMIC_LOADING_OF_LIBRARIES 186 cout <<
"# linked version of g2o" << endl;
195 Factory::instance()->printRegisteredTypes(cout,
true);
198 if (listRobustKernels) {
199 std::vector<std::string> kernels;
200 RobustKernelFactory::instance()->fillKnownKernels(kernels);
201 cout <<
"Robust Kernels:" << endl;
202 for (
size_t i = 0; i < kernels.size(); ++i) {
203 cout << kernels[i] << endl;
212 if (maxIterations < 0) {
213 cerr <<
"# setup termination criterion based on the gain of the iteration" << endl;
214 maxIterations = maxIterationsWithGain;
224 if (! optimizer.
solver()) {
225 cerr <<
"Error allocating solver. Allocating \"" << strSolver <<
"\" failed!" << endl;
229 if (solverProperties.size() > 0) {
231 if (! updateStatus) {
232 cerr <<
"Failure while updating the solver properties from the given string" << endl;
235 if (solverProperties.size() > 0 || printSolverProperties) {
240 if (loadLookup.size() > 0) {
243 if (inputFilename.size() == 0) {
244 cerr <<
"No input data specified" << endl;
246 }
else if (inputFilename ==
"-") {
247 cerr <<
"Read input from stdin" << endl;
248 if (!optimizer.
load(cin)) {
249 cerr <<
"Error loading graph" << endl;
253 cerr <<
"Read input from " << inputFilename << endl;
254 ifstream ifs(inputFilename.c_str());
256 cerr <<
"Failed to open file" << endl;
259 if (!optimizer.
load(ifs)) {
260 cerr <<
"Error loading graph" << endl;
264 cerr <<
"Loaded " << optimizer.
vertices().size() <<
" vertices" << endl;
265 cerr <<
"Loaded " << optimizer.
edges().size() <<
" edges" << endl;
267 if (optimizer.
vertices().size() == 0) {
268 cerr <<
"Graph contains no vertices" << endl;
272 set<int> vertexDimensions = optimizer.
dimensions();
274 cerr <<
"The selected solver is not suitable for optimizing the given graph" << endl;
277 assert (optimizer.
solver());
285 if (gaugeList.size()){
286 cerr <<
"Fixing gauges: ";
287 for (
size_t i=0; i<gaugeList.size(); i++){
291 cerr <<
"fatal, not found the vertex of id " <<
id <<
" in the gaugeList. Aborting";
296 cerr << v->
id() <<
" ";
301 gaugeFreedom =
false;
307 cerr <<
"# cannot find a vertex to fix in this thing" << endl;
310 cerr <<
"# graph is fixed by node " << gauge->
id() << endl;
314 cerr <<
"# graph is fixed by priors or already fixed vertex" << endl;
319 int maxDim = *vertexDimensions.rbegin();
320 int minDim = *vertexDimensions.begin();
321 if (maxDim != minDim) {
322 cerr <<
"# Preparing Marginalization of the Landmarks ... ";
323 for (HyperGraph::VertexIDMap::iterator it=optimizer.
vertices().begin(); it!=optimizer.
vertices().end(); it++){
329 cerr <<
"done." << endl;
333 if (robustKernel.size() > 0) {
335 cerr <<
"# Preparing robust error function ... ";
338 for (SparseOptimizer::EdgeSet::iterator it = optimizer.
edges().begin(); it != optimizer.
edges().end(); ++it) {
339 SparseOptimizer::Edge* e =
dynamic_cast<SparseOptimizer::Edge*
>(*it);
340 if (e->vertices().size() >= 2 && std::abs(e->vertex(0)->id() - e->vertex(1)->id()) != 1) {
341 e->setRobustKernel(creator->
construct());
343 e->robustKernel()->setDelta(huberWidth);
347 for (SparseOptimizer::EdgeSet::iterator it = optimizer.
edges().begin(); it != optimizer.
edges().end(); ++it) {
348 SparseOptimizer::Edge* e =
dynamic_cast<SparseOptimizer::Edge*
>(*it);
349 e->setRobustKernel(creator->
construct());
351 e->robustKernel()->setDelta(huberWidth);
354 cerr <<
"done." << endl;
356 cerr <<
"Unknown Robust Kernel: " << robustKernel << endl;
367 cerr <<
CL_RED(
"Warning: d.visited().size() != optimizer.vertices().size()") << endl;
368 cerr <<
"visited: " << d.
visited().size() << endl;
369 cerr <<
"vertices: " << optimizer.
vertices().size() << endl;
373 cerr <<
CL_RED(
"# Note: this variant performs batch steps in each time step") << endl;
374 cerr <<
CL_RED(
"# For a variant which updates the Cholesky factor use the binary g2o_incremental") << endl;
375 int incIterations = maxIterations;
377 cerr <<
"# Setting default number of iterations" << endl;
380 int updateDisplayEveryN = updateGraphEachN;
383 cerr <<
"# incremental settings" << endl;
384 cerr <<
"#\t solve every " << updateGraphEachN << endl;
385 cerr <<
"#\t iterations " << incIterations << endl;
388 for (SparseOptimizer::VertexIDMap::const_iterator it = vertices.begin(); it != vertices.end(); ++it) {
389 const SparseOptimizer::Vertex* v =
static_cast<const SparseOptimizer::Vertex*
>(it->second);
390 maxDim = max(maxDim, v->dimension());
393 vector<SparseOptimizer::Edge*> edges;
394 for (SparseOptimizer::EdgeSet::iterator it = optimizer.
edges().begin(); it != optimizer.
edges().end(); ++it) {
395 SparseOptimizer::Edge* e =
dynamic_cast<SparseOptimizer::Edge*
>(*it);
398 optimizer.
edges().clear();
407 int lastOptimizedVertexCount = 0;
408 int lastVisUpdateVertexCount = 0;
409 bool freshlyOptimized=
false;
410 bool firstRound =
true;
413 for (vector<SparseOptimizer::Edge*>::iterator it = edges.begin(); it != edges.end(); ++it) {
414 SparseOptimizer::Edge* e = *it;
417 SparseOptimizer::Vertex* v1 = optimizer.
vertex(e->vertices()[0]->id());
418 SparseOptimizer::Vertex* v2 = optimizer.
vertex(e->vertices()[1]->id());
421 SparseOptimizer::Vertex* v = v1 =
dynamic_cast<SparseOptimizer::Vertex*
>(e->vertices()[0]);
426 cerr <<
"Error adding vertex " << v->id() << endl;
428 verticesAdded.insert(v);
430 if (v->dimension() == maxDim)
435 SparseOptimizer::Vertex* v = v2 =
dynamic_cast<SparseOptimizer::Vertex*
>(e->vertices()[1]);
440 cerr <<
"Error adding vertex " << v->id() << endl;
442 verticesAdded.insert(v);
444 if (v->dimension() == maxDim)
452 cerr <<
"Unable to add edge " << e->vertices()[0]->id() <<
" -> " << e->vertices()[1]->id() << endl;
454 edgesAdded.insert(e);
465 if (e->initialEstimatePossible(toSet, from) > 0.) {
469 e->initialEstimate(toSet, from);
471 assert(0 &&
"Added unitialized variable to the graph");
478 fromSet.insert(from);
479 if (e->initialEstimatePossible(fromSet, to) > 0.) {
483 e->initialEstimate(fromSet, to);
485 assert(0 &&
"Added unitialized variable to the graph");
489 default: cerr <<
"doInit wrong value\n";
496 freshlyOptimized=
false;
499 if (vertexCount - lastOptimizedVertexCount >= updateGraphEachN) {
502 cerr <<
"initialization failed" << endl;
507 cerr <<
"updating initialization failed" << endl;
511 verticesAdded.clear();
514 int currentIt=optimizer.
optimize(incIterations, !firstRound);
520 double chi2 = optimizer.
chi2();
521 cerr <<
"nodes= " << optimizer.
vertices().size() <<
"\t edges= " << optimizer.
edges().size() <<
"\t chi2= " << chi2
522 <<
"\t time= " << dts <<
"\t iterations= " << currentIt <<
"\t cumTime= " << cumTime << endl;
524 lastOptimizedVertexCount = vertexCount;
525 freshlyOptimized =
true;
528 if (vertexCount - lastVisUpdateVertexCount >= updateDisplayEveryN) {
530 lastVisUpdateVertexCount = vertexCount;
542 if (! freshlyOptimized) {
544 int currentIt=optimizer.
optimize(incIterations, !firstRound);
549 double chi2 = optimizer.
chi2();
550 cerr <<
"nodes= " << optimizer.
vertices().size() <<
"\t edges= " << optimizer.
edges().size() <<
"\t chi2= " << chi2
551 <<
"\t time= " << dts <<
"\t iterations= " << currentIt <<
"\t cumTime= " << cumTime << endl;
566 double loadChi = optimizer.
chi2();
567 cerr <<
"Initial chi2 = " << FIXED(loadChi) << endl;
571 }
else if (initialGuessOdometry) {
575 double initChi = optimizer.
chi2();
578 int result=optimizer.
optimize(maxIterations);
579 if (maxIterations > 0 && result==OptimizationAlgorithm::Fail){
580 cerr <<
"Cholesky failed, result might be invalid" << endl;
581 }
else if (computeMarginals){
582 std::vector<std::pair<int, int> > blockIndices;
596 cerr <<
"Vertex id:" << v->
id() << endl;
612 double finalChi=optimizer.
chi2();
614 if (summaryFile!=
"") {
622 int maxDim = *vertexDimensions.rbegin();
623 for (HyperGraph::VertexIDMap::iterator it=optimizer.
vertices().begin(); it!=optimizer.
vertices().end(); it++){
630 set<string> edgeTypes;
631 for (HyperGraph::EdgeSet::iterator it=optimizer.
edges().begin(); it!=optimizer.
edges().end(); it++){
632 edgeTypes.insert(Factory::instance()->tag(*it));
634 stringstream edgeTypesString;
635 for (std::set<string>::iterator it=edgeTypes.begin(); it!=edgeTypes.end(); it++){
636 edgeTypesString << *it <<
" ";
650 os.open(summaryFile.c_str(), ios::app);
656 cerr <<
"writing stats to file \"" << statsFile <<
"\" ... ";
657 ofstream os(statsFile.c_str());
660 for (
int i=0; i<maxIterations; i++) {
661 os << bsc[i] << endl;
663 cerr <<
"done." << endl;
669 if (gnudump.size() > 0) {
670 bool gnuPlotStatus =
saveGnuplot(gnudump, optimizer);
671 if (! gnuPlotStatus) {
672 cerr <<
"Error while writing gnuplot files" << endl;
676 if (outputfilename.size() > 0) {
677 if (outputfilename ==
"-") {
678 cerr <<
"saving to stdout";
679 optimizer.
save(cout);
681 cerr <<
"saving " << outputfilename <<
" ... ";
682 optimizer.
save(outputfilename.c_str());
684 cerr <<
"done." << endl;
virtual bool updateInitialization(HyperGraph::VertexSet &vset, HyperGraph::EdgeSet &eset)
virtual void computeInitialGuess()
double get_monotonic_time()
const BatchStatisticsContainer & batchStatistics() const
int id() const
returns the id
#define __PRETTY_FUNCTION__
Command line parsing of argc and argv.
HyperGraph::VertexSet & visited()
Abstract interface for allocating a robust kernel.
describe the properties of a solver
void setComputeBatchStatistics(bool computeBatchStatistics)
bool dumpEdges(std::ostream &os, const OptimizableGraph &optimizer)
void loadStandardTypes(DlWrapper &dlTypesWrapper, int argc, char **argv)
std::set< Vertex * > VertexSet
int optimize(int iterations, bool online=false)
SparseMatrixBlock * block(int r, int c, bool alloc=false)
returns the block at location r,c. if alloc=true he block is created if it does not exist ...
stop iterating based on the gain which is (oldChi - currentChi) / currentChi.
OptimizationAlgorithm * solver()
int hessianIndex() const
temporary index of this node in the parameter vector obtained from linearization
bool addPostIterationAction(HyperGraphAction *action)
add an action to be executed after each iteration
void setMaxIterations(int maxit)
void computeActiveErrors()
create solvers based on their short name
const VertexIDMap & vertices() const
Vertex * vertex(int id)
returns the vertex number id appropriately casted
bool operator()(SparseOptimizer::Edge *const &e1, SparseOptimizer::Edge *const &e2)
utility functions for handling time related stuff
std::set< Edge * > EdgeSet
virtual Vertex * findGauge()
finds a gauge in the graph to remove the undefined dof.
int dimension() const
dimension of the estimated state belonging to this node
Protocol The SLAM executable accepts such as solving the and retrieving or vertices in the explicitly state the reprensentation poses are represented by poses by VERTEX_XYZRPY In the Quaternions and other representations could be but note that it is up to the SLAM algorithm to choose the internal representation of the angles The keyword is followed by a unique vertex ID and an optional initialization of the or edges in the explicitly state the type of the constraint pose constraints are given by pose constraints by EDGE_XYZRPY The keyword is followed by a unique edge the IDs of the referenced vertices
P * makeProperty(const std::string &name_, const typename P::ValueType &v)
double chi2() const
returns the chi2 of the current configuration
bool parseArgs(int argc, char **argv, bool exitOnError=true)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
bool isSolverSuitable(const OptimizationAlgorithmProperty &solverProperty, const std::set< int > &vertDims=std::set< int >()) const
void shortestPaths(HyperGraph::Vertex *v, HyperDijkstra::CostFunction *cost, double maxDistance=std::numeric_limits< double >::max(), double comparisonConditioner=1e-3, bool directed=false, double maxEdgeCost=std::numeric_limits< double >::max())
void setVerbose(bool verbose)
const EdgeSet & edges() const
void setForceStopFlag(bool *flag)
void paramLeftOver(const std::string &name, std::string &p, const std::string &defValue, const std::string &desc, bool optional=false)
void setAlgorithm(OptimizationAlgorithm *algorithm)
bool updatePropertiesFromString(const std::string &propString)
void param(const std::string &name, bool &p, bool defValue, const std::string &desc)
void writeToCSV(std::ostream &os) const
void setGainThreshold(double gainThreshold)
void listSolvers(std::ostream &os) const
list the known solvers into a stream
void loadStandardSolver(DlWrapper &dlSolverWrapper, int argc, char **argv)
A general case Vertex for optimization.
Loading libraries during run-time.
void setRenamedTypesFromString(const std::string &types)
virtual bool load(std::istream &is, bool createEdges=true)
load the graph from a stream. Uses the Factory singleton for creating the vertices and edges...
const VertexContainer & activeVertices() const
the vertices active in the current optimization
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
Sort Edges for inserting them sequentially.
bool saveGnuplot(const std::string &gnudump, const OptimizableGraph &optimizer)
bool requiresMarginalize
whether the solver requires marginalization of landmarks
virtual RobustKernel * construct()=0
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
cost for traversing only odometry edges.
void printProperties(std::ostream &os) const
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
a collection of properties mapping from name to the property itself
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
bool computeMarginals(SparseBlockMatrix< MatrixXD > &spinv, const std::vector< std::pair< int, int > > &blockIndices)
void sigquit_handler(int sig)
std::set< int > dimensions() const
std::vector< G2OBatchStatistics > BatchStatisticsContainer
Sparse matrix which uses blocks.
OptimizationAlgorithm * construct(const std::string &tag, OptimizationAlgorithmProperty &solverProperty) const
int main(int argc, char **argv)
bool parsedParam(const std::string ¶mFlag) const