g2o
Loading...
Searching...
No Matches
Classes | Functions | Variables
g2o-unfold.cpp File Reference
#include <algorithm>
#include <cassert>
#include <csignal>
#include <fstream>
#include <iostream>
#include <sstream>
#include <string>
#include "g2o/core/block_solver.h"
#include "g2o/core/estimate_propagator.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/stuff/command_args.h"
#include "g2o/stuff/filesys_tools.h"
#include "g2o/stuff/macros.h"
#include "g2o/stuff/string_tools.h"
#include "g2o/types/sba/types_sba.h"
#include "g2o/types/sba/types_six_dof_expmap.h"
#include "g2o/types/sim3/types_seven_dof_expmap.h"
#include "g2o/types/slam2d/types_three_dof.h"
#include "g2o/types/slam3d/types_six_dof_quat.h"
#include "tools.h"
#include "g2o/solvers/cholmod/linear_solver_cholmod.h"
#include "g2o/solvers/csparse/linear_solver_csparse.h"
#include "g2o/solvers/pcg/linear_solver_pcg.h"
Include dependency graph for g2o-unfold.cpp:

Go to the source code of this file.

Classes

struct  InvChi2CostFunction
 
struct  IncrementalEdgesCompare
 Sort Edges for inserting them sequentially. More...
 

Functions

void updateDisplay (ostream &os, const SparseOptimizer &optimizer)
 
SparseOptimizer::Method str2method (const std::string &strMethod)
 
template<typename T >
T::LinearSolverType * allocateLinearSolver (bool useCholmod)
 
Solverstr2solver (const std::string &strSolver_, SparseOptimizer *opt)
 
void gnudump_edges (const string &gnudump, const string &file_suffix, HyperGraph::EdgeSet::const_iterator begin, HyperGraph::EdgeSet::const_iterator end, bool dumpEdges, bool dumpFeatures)
 
void gnudump_features (const string &gnudump, const string &file_suffix, HyperGraph::EdgeSet::const_iterator begin, HyperGraph::EdgeSet::const_iterator end)
 
void sigquit_handler (int q __attribute__((unused)))
 
int main (int argc, char **argv)
 

Variables

bool hasToStop = false
 

Function Documentation

◆ allocateLinearSolver()

template<typename T >
T::LinearSolverType * allocateLinearSolver ( bool  useCholmod)

Definition at line 177 of file g2o-unfold.cpp.

177 {
178 if (useCholmod) {
179#ifdef GO_CHOLMOD_SUPPORT
181#else
182 return 0;
183#endif
184 } else {
186 }
187}
linear solver which uses CSparse
basic solver for Ax = b which has to reimplemented for different linear algebra libraries

◆ gnudump_edges()

void gnudump_edges ( const string &  gnudump,
const string &  file_suffix,
HyperGraph::EdgeSet::const_iterator  begin,
HyperGraph::EdgeSet::const_iterator  end,
bool  dumpEdges,
bool  dumpFeatures 
)

Definition at line 250 of file g2o-unfold.cpp.

253 {
254 // -------
255 if (gnudump.size() > 0) {
256 string baseName = getPureFilename(gnudump);
257 string extension = getFileExtension(gnudump);
258 string newFilename = formatString("%s_%s.%s", baseName.c_str(),
259 file_suffix.c_str(), extension.c_str());
260
261 cerr << "Gnudump (" << newFilename << ")... ";
262
263 ofstream fout(newFilename.c_str());
264
265 for (HyperGraph::EdgeSet::const_iterator eit = begin; eit != end; ++eit) {
267 const_cast<HyperGraph::Edge*>(*eit));
268 e->computeError();
269 if (e->robustKernel()) e->robustifyError();
270 double edgeChi2 = e->chi2();
271
272 const VertexSE2* from = dynamic_cast<const VertexSE2*>((*eit)->vertex(0));
273 const VertexSE2* to = dynamic_cast<const VertexSE2*>((*eit)->vertex(1));
274
275 if (dumpEdges) {
276 if (from && to) {
277 Vector3d p1 = from->estimate().toVector();
278 Vector3d p2 = to->estimate().toVector();
279 fout << p1[0] << " " << p1[1] << " " << p1[2] << " " << edgeChi2
280 << " " << endl;
281 fout << p2[0] << " " << p2[1] << " " << p1[2] << " " << edgeChi2
282 << " " << endl;
283 fout << endl;
284 continue;
285 }
286 }
287
288 if (dumpFeatures) {
289 const VertexPointXY* tox =
290 dynamic_cast<const VertexPointXY*>((*eit)->vertex(1));
291 if (from && tox) {
292 Vector3d p1 = from->estimate().toVector();
293 Vector2d p2 = tox->estimate();
294 fout << p1[0] << " " << p1[1] << " " << p1[2] << " " << edgeChi2
295 << " " << endl;
296 fout << p2[0] << " " << p2[1] << " " << edgeChi2 << " " << endl;
297 fout << endl;
298 continue;
299 }
300 }
301 }
302 fout.close();
303 cerr << " done" << endl;
304 }
305}
const EstimateType & estimate() const
return the current estimate of the vertex
virtual double chi2() const =0
virtual void computeError()=0
RobustKernel * robustKernel() const
if NOT NULL, error of this edge will be robustifed with the kernel
Vector3 toVector() const
convert to a 3D vector (x, y, theta)
Definition se2.h:105
2D pose Vertex, (x,y,theta)
Definition vertex_se2.h:41
bool dumpEdges(std::ostream &os, const OptimizableGraph &optimizer)
std::string getFileExtension(const std::string &filename)
std::string getPureFilename(const std::string &filename)
std::string formatString(const char *fmt,...)

References g2o::OptimizableGraph::Edge::chi2(), g2o::OptimizableGraph::Edge::computeError(), g2o::dumpEdges(), g2o::BaseVertex< D, T >::estimate(), g2o::formatString(), g2o::getFileExtension(), g2o::getPureFilename(), g2o::OptimizableGraph::Edge::robustKernel(), and g2o::SE2::toVector().

Referenced by main().

◆ gnudump_features()

void gnudump_features ( const string &  gnudump,
const string &  file_suffix,
HyperGraph::EdgeSet::const_iterator  begin,
HyperGraph::EdgeSet::const_iterator  end 
)

Definition at line 307 of file g2o-unfold.cpp.

309 {
310 // -------
311 if (gnudump.size() > 0) {
312 string baseName = getPureFilename(gnudump);
313 string extension = getFileExtension(gnudump);
314 string newFilename = formatString("%s_%s.%s", baseName.c_str(),
315 file_suffix.c_str(), extension.c_str());
316
317 cerr << "Gnudump (" << newFilename << ")... ";
318
319 ofstream fout(newFilename.c_str());
320
321 for (HyperGraph::EdgeSet::const_iterator eit = begin; eit != end; ++eit) {
322 OptimizableGraph::Edge* e = static_cast<OptimizableGraph::Edge*>(*eit);
323 e->computeError();
324 if (e->robustKernel()) e->robustifyError();
325 double edgeChi2 = e->chi2();
326
327 const VertexPointXY* tox =
328 dynamic_cast<const VertexPointXY*>((*eit)->vertex(1));
329 if (tox) {
330 Vector2d p2 = tox->estimate();
331 fout << p2[0] << " " << p2[1] << " " << edgeChi2 << " " << endl;
332 continue;
333 }
334 }
335 fout.close();
336 cerr << " done" << endl;
337 }
338}

References g2o::OptimizableGraph::Edge::chi2(), g2o::OptimizableGraph::Edge::computeError(), g2o::BaseVertex< D, T >::estimate(), g2o::formatString(), g2o::getFileExtension(), g2o::getPureFilename(), and g2o::OptimizableGraph::Edge::robustKernel().

Referenced by main().

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 344 of file g2o-unfold.cpp.

344 {
345 int maxIterations;
346 bool verbose;
347 string inputFilename;
348 string gnudump;
349 string outputfilename;
350 string strMethod;
351 string strSolver;
352 string loadLookup;
353 bool initialGuess;
354 bool marginalize;
355 bool listTypes;
356 bool incremental;
357 bool guiOut;
358 double lambdaInit;
359 int updateGraphEachN = 10;
360 string statsFile;
361 // command line parsing
362 CommandArgs arg;
363 arg.param("i", maxIterations, 5, "perform n iterations");
364 arg.param("v", verbose, false, "verbose output of the optimization process");
365 arg.param("guess", initialGuess, false,
366 "initial guess based on spanning tree");
367 arg.param("inc", incremental, false, "run incremetally");
368 arg.param("update", updateGraphEachN, 10,
369 "updates afert x odometry nodes, (default: 10)");
370 arg.param("guiOut", guiOut, false, "gui output while running incrementally");
371 arg.param("lambdaInit", lambdaInit, 0,
372 "user specified lambda init for levenberg");
373 arg.param("marginalize", marginalize, false, "on or off");
374 arg.param("method", strMethod, "Gauss", "Gauss or Levenberg");
375 arg.param("gnudump", gnudump, "", "dump to gnuplot data file");
376 arg.param("o", outputfilename, "", "output final version of the graph");
377 arg.param("solver", strSolver, "var",
378 "specify which solver to use underneat\n\t {var, fix3_2, fix6_3, "
379 "fix_7_3}");
380 arg.param("stats", statsFile, "", "specify a file for the statistics");
381 arg.param("listTypes", listTypes, false, "list the registered types");
382 arg.param("renameTypes", loadLookup, "",
383 "create a lookup for loading types into other types,\n\t "
384 "TAG_IN_FILE=INTERNAL_TAG_FOR_TYPE,TAG2=INTERNAL2\n\t e.g., "
385 "VERTEX_CAM=VERTEX_SE3:EXPMAP");
386 arg.paramLeftOver("graph-input", inputFilename, "",
387 "graph file which will be processed");
388
389 arg.parseArgs(argc, argv);
390
391 if (listTypes) {
392 OptimizableGraph::printRegisteredTypes(cout, true);
393 }
394
395 SparseOptimizer optimizer;
396 optimizer.verbose() = verbose;
397 optimizer.setForceStopFlag(&hasToStop);
398
399 optimizer.method() = str2method(strMethod);
400 optimizer.solver() = str2solver(strSolver, &optimizer);
401 if (!optimizer.solver()) {
402 cerr << "Error allocating solver" << endl;
403 return 0;
404 }
405 optimizer.userLambdaInit() = lambdaInit;
406
407 assert(optimizer.solver());
408 ActivePathCostFunction* guessCostFunction = 0;
409 if (initialGuess) guessCostFunction = new ActivePathCostFunction(&optimizer);
410
411 cerr << "Read input from " << inputFilename << endl;
412 ifstream ifs(inputFilename.c_str());
413 if (!ifs) {
414 cerr << "Failed to open file" << endl;
415 return 1;
416 }
417
418 if (loadLookup.size() > 0) {
419 optimizer.setRenamedTypesFromString(loadLookup);
420 }
421
422 if (!optimizer.load(ifs)) {
423 cerr << "Error loading graph" << endl;
424 return 2;
425 }
426
427 cerr << "Loaded " << optimizer.vertices().size() << " vertices" << endl;
428 cerr << "Loaded " << optimizer.edges().size() << " edges" << endl;
429
430 if (optimizer.vertices().size() == 0) {
431 cerr << "HyperGraph contains no vertices" << endl;
432 return 1;
433 }
434
435 // HACK if schur, we wanna marginalize the landmarks...
436 if (marginalize) {
437 cerr << "Preparing Marginalization of the Landmarks ... ";
438 int maxDim = -1;
439 for (HyperGraph::VertexIDMap::iterator it = optimizer.vertices().begin();
440 it != optimizer.vertices().end(); ++it) {
442 static_cast<OptimizableGraph::Vertex*>(it->second);
443 maxDim = (max)(v->dimension(), maxDim);
444 }
445 for (HyperGraph::VertexIDMap::iterator it = optimizer.vertices().begin();
446 it != optimizer.vertices().end(); ++it) {
448 static_cast<OptimizableGraph::Vertex*>(it->second);
449 if (v->dimension() != maxDim) {
450 // cerr << "m";
451 v->marginalized() = true;
452 }
453 }
454 cerr << "done." << endl;
455 }
456
457 // sanity check
458 // HyperDijkstra d(&optimizer);
459 // UniformCostFunction f;
460 // d.shortestPaths(optimizer.findOneOrigin(),&f);
461 // cerr << PVAR(d.visited().size()) << endl;
462 // assert (d.visited().size()==optimizer.vertices().size());
463
464 if (incremental) {
465 int incIterations = 1;
466 int updateDisplayEveryN = updateGraphEachN;
467 int maxDim = 0;
468
469 SparseOptimizer::VertexIDMap vertices = optimizer.vertices();
470 for (SparseOptimizer::VertexIDMap::const_iterator it = vertices.begin();
471 it != vertices.end(); ++it) {
472 const SparseOptimizer::Vertex* v =
473 static_cast<const SparseOptimizer::Vertex*>(it->second);
474 maxDim = (max)(maxDim, v->dimension());
475 }
476
477 vector<SparseOptimizer::Edge*> edges;
478 for (SparseOptimizer::EdgeSet::iterator it = optimizer.edges().begin();
479 it != optimizer.edges().end(); ++it) {
480 SparseOptimizer::Edge* e = dynamic_cast<SparseOptimizer::Edge*>(*it);
481 edges.push_back(e);
482 }
483 optimizer.edges().clear();
484 optimizer.vertices().clear();
485 optimizer.verbose() = false;
486
487 // sort the edges in a way that inserting them makes sense
488 sort(edges.begin(), edges.end(), IncrementalEdgesCompare());
489
490 double cumTime = 0.;
491 int vertexCount = 0;
492 int lastOptimizedVertexCount = 0;
493 int lastVisUpdateVertexCount = 0;
494 bool addNextEdge = true;
495 bool freshlyOptimized = false;
496 for (vector<SparseOptimizer::Edge*>::iterator it = edges.begin();
497 it != edges.end(); ++it) {
498 SparseOptimizer::Edge* e = *it;
499 bool optimize = false;
500
501 if (addNextEdge && !optimizer.vertices().empty()) {
502 int maxInGraph = optimizer.vertices().rbegin()->first;
503 int idMax = max(e->vertex(0)->id(), e->vertex(1)->id());
504 if (maxInGraph < idMax && !freshlyOptimized) {
505 addNextEdge = false;
506 optimize = true;
507 } else {
508 addNextEdge = true;
509 optimize = false;
510 }
511 }
512
513 int doInit = 0;
514 SparseOptimizer::Vertex* v1 = optimizer.vertex(e->vertex(0)->id());
515 SparseOptimizer::Vertex* v2 = optimizer.vertex(e->vertex(1)->id());
516 if (!v1 && addNextEdge) {
517 // cerr << " adding vertex " << it->id1 << endl;
518 SparseOptimizer::Vertex* v =
519 dynamic_cast<SparseOptimizer::Vertex*>(e->vertex(0));
520 bool v1Added = optimizer.addVertex(v);
521 assert(v1Added);
522 doInit = 2;
523 if (v->dimension() == maxDim) vertexCount++;
524 }
525
526 if (!v2 && addNextEdge) {
527 // cerr << " adding vertex " << it->id2 << endl;
528 SparseOptimizer::Vertex* v =
529 dynamic_cast<SparseOptimizer::Vertex*>(e->vertex(1));
530 bool v2Added = optimizer.addVertex(v);
531 assert(v2Added);
532 doInit = 1;
533 if (v->dimension() == maxDim) vertexCount++;
534 }
535
536 if (addNextEdge) {
537 // cerr << " adding edge " << it->id1 << " " << it->id2 << " " <<
538 // it->mean << endl;
539 if (!optimizer.addEdge(e)) {
540 cerr << "Unable to add edge " << e->vertex(0)->id() << " -> "
541 << e->vertex(1)->id() << endl;
542 }
543
544 if (doInit) {
546 static_cast<OptimizableGraph::Vertex*>(e->vertex(0));
548 static_cast<OptimizableGraph::Vertex*>(e->vertex(1));
549 switch (doInit) {
550 case 1: // initialize v1 from v2
551 if (e->initialEstimatePossible(to, from)) {
552 // cerr << "init: "
553 // << to->id() << "(" << to->dimension() << ") -> "
554 // << from->id() << "(" << from->dimension() << ") " <<
555 // endl;
556 e->initialEstimate(to, from);
557 }
558 break;
559 case 2:
560 if (e->initialEstimatePossible(from, to)) {
561 // cerr << "init: "
562 // << from->id() << "(" << from->dimension() << ") -> "
563 // << to->id() << "(" << to->dimension() << ") " << endl;
564 e->initialEstimate(from, to);
565 }
566 break;
567 default:
568 cerr << "doInit wrong value\n";
569 }
570 }
571 }
572
573 freshlyOptimized = false;
574 if (optimize) {
575 // cerr << "Optimize" << endl;
576 if (vertexCount - lastOptimizedVertexCount >= updateGraphEachN) {
577 double ts = get_monotonic_time();
578 int currentIt = optimizer.optimize(incIterations);
579 double dts = get_monotonic_time() - ts;
580 cumTime += dts;
581 // optimizer->setOptimizationTime(cumTime);
582 if (verbose) {
583 double chi2 = optimizer.chi2();
584 cerr << "nodes= " << optimizer.vertices().size()
585 << "\t edges= " << optimizer.edges().size()
586 << "\t chi2= " << chi2 << "\t time= " << dts
587 << "\t iterations= " << currentIt << "\t cumTime= " << cumTime
588 << endl;
589 }
590 lastOptimizedVertexCount = vertexCount;
591 }
592
593 if (!verbose) cerr << ".";
594 addNextEdge = true;
595 freshlyOptimized = true;
596 --it;
597 }
598
599 if (guiOut) {
600 if (vertexCount - lastVisUpdateVertexCount >= updateDisplayEveryN) {
601 updateDisplay(cout, optimizer);
602 lastVisUpdateVertexCount = vertexCount;
603 }
604 }
605
606 } // for all edges
607
608 } else {
609 if (gnudump.size() > 0)
610 gnudump_edges(gnudump, "inputtraj", optimizer.edges().begin(),
611 optimizer.edges().end(), true, false);
612 if (gnudump.size() > 0)
613 gnudump_features(gnudump, "inputfeatures", optimizer.edges().begin(),
614 optimizer.edges().end());
615 if (gnudump.size() > 0)
616 gnudump_edges(gnudump, "input", optimizer.edges().begin(),
617 optimizer.edges().end(), true, true);
618
619 // BATCH optimization
620 // signal(SIGINT, sigquit_handler);
621 cerr << "Initial chi2 = " << optimizer.chi2() << endl;
622
623 if (statsFile != "") {
624 // allocate buffer for statistics;
625 optimizer._statistics = new G2OBatchStatistics[maxIterations];
626 }
627
628 int i = optimizer.optimize(maxIterations, guessCostFunction);
629 if (!i) {
630 cerr << "Cholesky failed, result might be invalid" << endl;
631 }
632
633 if (gnudump.size() > 0)
634 gnudump_edges(gnudump, "regularopttraj", optimizer.edges().begin(),
635 optimizer.edges().end(), true, false);
636 if (gnudump.size() > 0)
637 gnudump_features(gnudump, "regularoptfeatures", optimizer.edges().begin(),
638 optimizer.edges().end());
639 if (gnudump.size() > 0)
640 gnudump_edges(gnudump, "regularopt", optimizer.edges().begin(),
641 optimizer.edges().end(), true, true);
642
643 cerr << "Computing chi2 statistics ";
644 double sumChi2 = 0.0;
645 double chi2Thres = 0.0;
646 int cnt = 0;
647
648 for (HyperGraph::EdgeSet::const_iterator it = optimizer.edges().begin();
649 it != optimizer.edges().end(); ++it) {
650 OptimizableGraph::Edge* e = static_cast<OptimizableGraph::Edge*>(*it);
651 e->computeError();
652 if (e->robustKernel()) e->robustifyError();
653 sumChi2 += e->chi2();
654 cnt++;
655 }
656 chi2Thres = sumChi2 / cnt * 1.4;
657 cerr << " threshold=" << chi2Thres << " done" << endl;
658
659 cerr << "Searching for high error edges .. ";
660 HyperGraph::EdgeSet highErrorEdges;
661 HyperGraph::EdgeSet highErrorEdgesToFeatures;
662 HyperGraph::EdgeSet edgesToOptimize;
663
664 HyperGraph::EdgeSet edgesToOptimize_selected;
665 HyperGraph::EdgeSet edgesToOptimize_border;
666
667 for (HyperGraph::EdgeSet::const_iterator it = optimizer.edges().begin();
668 it != optimizer.edges().end(); ++it) {
669 OptimizableGraph::Edge* e = static_cast<OptimizableGraph::Edge*>(*it);
670 e->computeError();
671 if (e->robustKernel()) e->robustifyError();
672 double edgeChi2 = e->chi2();
673 if (edgeChi2 > chi2Thres) {
674 const VertexSE2* from = dynamic_cast<const VertexSE2*>(e->vertex(0));
675 const VertexSE2* to = dynamic_cast<const VertexSE2*>(e->vertex(1));
676
677 if (from && to) {
678 highErrorEdges.insert(*it);
679 continue;
680 }
681 const VertexPointXY* tox =
682 dynamic_cast<const VertexPointXY*>(e->vertex(1));
683 if (from && tox) {
684 highErrorEdgesToFeatures.insert(*it);
685 continue;
686 }
687 }
688 }
689 cerr << " found=" << highErrorEdges.size() << "/"
690 << highErrorEdgesToFeatures.size() << " edges with high errors .. done"
691 << endl;
692
693 if (gnudump.size() > 0)
694 gnudump_edges(gnudump, "hee", highErrorEdges.begin(),
695 highErrorEdges.end(), true, false);
696
697 if (gnudump.size() > 0)
698 gnudump_edges(gnudump, "heef_", highErrorEdgesToFeatures.begin(),
699 highErrorEdgesToFeatures.end(), true, true);
700
701 // fix all vertices
702 cerr << "Fixing the whole graph ";
703 for (std::map<int, HyperGraph::Vertex*>::iterator vit =
704 optimizer.vertices().begin();
705 vit != optimizer.vertices().end(); ++vit) {
707 static_cast<OptimizableGraph::Vertex*>((*vit).second);
708 v->fixed() = true;
709 }
710 cerr << " done" << endl;
711
712 typedef std::pair<HyperGraph::EdgeSet, HyperGraph::EdgeSet> EdgeSetPair;
713 typedef std::vector<EdgeSetPair> EdgeSetPairVector;
714
715 EdgeSetPairVector myEdgeStack;
716
717 cerr << "Collecting clusters...";
718
719 while (!highErrorEdges.empty()) {
720 HyperGraph::EdgeSet::iterator it = highErrorEdges.begin();
721
722 HyperGraph::EdgeSet selected;
723 HyperGraph::EdgeSet border;
724 InvChi2CostFunction c2cost;
725
726 HyperGraph::Edge* start = *it;
727 bool edgesSelected = false;
728
729 findConnectedEdgesWithCostLimit(selected, border, start, &c2cost,
730 2.0 / chi2Thres);
731
732 if (selected.size() > 10) {
733 edgesSelected = true;
734 cerr << " (" << selected.size() << ", " << border.size() << ")";
735
736 // high error edges and their neighbor edges will be considered for
737 // optimization
738
739 edgesToOptimize_selected.insert(selected.begin(), selected.end());
740 edgesToOptimize_border.insert(border.begin(), border.end());
741 edgesToOptimize.insert(selected.begin(), selected.end());
742 edgesToOptimize.insert(border.begin(), border.end());
743 } else {
744 cerr << " [" << selected.size() << ", " << border.size() << "]";
745 }
746
747 // removed edges from that cluster from the open list of high error edges
748 for (HyperGraph::EdgeSet::iterator eit = selected.begin();
749 eit != selected.end(); ++eit) {
750 HyperGraph::EdgeSet::iterator removeMe = highErrorEdges.find(*eit);
751 if (removeMe != highErrorEdges.end()) {
752 highErrorEdges.erase(removeMe);
753 }
754 }
755
756 if (edgesSelected) {
757 myEdgeStack.push_back(EdgeSetPair(selected, border));
758 }
759 }
760 cerr << " done" << endl;
761
762 cerr << "Found " << myEdgeStack.size() << " clusters in sum with "
763 << edgesToOptimize_selected.size() << " high error edges"
764 << " and " << edgesToOptimize_border.size() << " border edges."
765 << endl;
766
767 if (gnudump.size() > 0)
768 gnudump_edges(gnudump, "selected", edgesToOptimize_selected.begin(),
769 edgesToOptimize_selected.end(), true, false);
770
771 if (gnudump.size() > 0)
772 gnudump_edges(gnudump, "border", edgesToOptimize_border.begin(),
773 edgesToOptimize_border.end(), true, false);
774
775 if (gnudump.size() > 0)
776 gnudump_edges(gnudump, "reoptimizeme", edgesToOptimize.begin(),
777 edgesToOptimize.end(), true, false);
778
779 cerr << "Unfixing high error edges ";
780 for (EdgeSetPairVector::iterator it = myEdgeStack.begin();
781 it != myEdgeStack.end(); ++it) {
782 // un-fix bad vertices
783 for (HyperGraph::EdgeSet::iterator eit = (*it).first.begin();
784 eit != (*it).first.end(); ++eit) {
785 OptimizableGraph::Edge* e = static_cast<OptimizableGraph::Edge*>(*eit);
786
788 static_cast<OptimizableGraph::Vertex*>(e->vertex(0));
789 vfrom->fixed() = false;
791 static_cast<OptimizableGraph::Vertex*>(e->vertex(1));
792 vto->fixed() = false;
793 }
794 }
795 cerr << "done" << endl;
796
797 // generate that for all nodes in all clusters
798 cerr << "Initialize optimization of subgraphs .. ";
799 optimizer.initializeOptimization(edgesToOptimize);
800 cerr << "done" << endl;
801
802 if (guessCostFunction == 0)
803 guessCostFunction = new ActivePathCostFunction(&optimizer);
804
805 cerr << "Searching for init nodes and re-initialize subgraphs .. ";
806 for (EdgeSetPairVector::iterator it = myEdgeStack.begin();
807 it != myEdgeStack.end(); ++it) {
808 // determine good node for initialization (one out of the borders!)
809 cerr << "S";
810 HyperGraph::EdgeSet::iterator eit = (*it).second.begin();
811
812 OptimizableGraph::Vertex* initNode = 0;
814 static_cast<OptimizableGraph::Vertex*>((*eit)->vertex(0));
816 static_cast<OptimizableGraph::Vertex*>((*eit)->vertex(1));
817
818 if (vfrom && vfrom->fixed())
819 initNode = vfrom;
820 else if (vto && vto->fixed())
821 initNode = vto;
822 else
823 initNode = vfrom;
824
825 // reinitialize bad vertices
826 cerr << "I";
827 optimizer.initializeActiveSubsetViaMeasurements(initNode,
828 guessCostFunction);
829 cerr << "-";
830 }
831 cerr << " .. done" << endl;
832
833 if (gnudump.size() > 0)
834 gnudump_edges(gnudump, "subsetinitialized", optimizer.edges().begin(),
835 optimizer.edges().end(), true, false);
836
837 // run all local optimization
838 cerr << "Optimize subgraphs .. " << endl;
839 optimizer.optimizeLoop(maxIterations);
840 cerr << "done" << endl;
841
842 if (gnudump.size() > 0)
843 gnudump_edges(gnudump, "subsetoptimized", optimizer.edges().begin(),
844 optimizer.edges().end(), true, false);
845
846 if (0) // no effect visible, why??
847 if (highErrorEdgesToFeatures.size() > 0) {
848 HyperGraph::EdgeSet edgesToBadFeatures;
849
850 // fix all vertices
851 cerr << "Fixing the whole graph ";
852 for (std::map<int, HyperGraph::Vertex*>::iterator vit =
853 optimizer.vertices().begin();
854 vit != optimizer.vertices().end(); ++vit) {
856 static_cast<OptimizableGraph::Vertex*>((*vit).second);
857 v->fixed() = true;
858 }
859 cerr << " done" << endl;
860
861 cerr << "Unfixing bad features";
862 for (HyperGraph::EdgeSet::iterator eit =
863 highErrorEdgesToFeatures.begin();
864 eit != highErrorEdgesToFeatures.end(); ++eit) {
866 dynamic_cast<OptimizableGraph::Vertex*>((*eit)->vertex(1));
867 v->fixed() = false;
868
869 edgesToBadFeatures.insert(v->edges().begin(), v->edges().end());
870 }
871
872 cerr << " considering " << edgesToBadFeatures.size()
873 << " edges .. done" << endl;
874
875 if (gnudump.size() > 0)
876 gnudump_edges(gnudump, "featurereinit", edgesToBadFeatures.begin(),
877 edgesToBadFeatures.end(), true, true);
878 if (gnudump.size() > 0)
879 gnudump_features(gnudump, "featurereinitfeatures",
880 edgesToBadFeatures.begin(),
881 edgesToBadFeatures.end());
882
883 cerr << "Initialize optimization of bad features .. ";
884 optimizer.initializeOptimization(edgesToBadFeatures);
885 cerr << "done" << endl;
886
887 // run all local optimization
888 cerr << "Optimize bad features .. " << endl;
889 optimizer.optimizeLoop(maxIterations / 2);
890 cerr << "done" << endl;
891
892 if (gnudump.size() > 0)
893 gnudump_edges(gnudump, "subgraphsfinal", optimizer.edges().begin(),
894 optimizer.edges().end(), true, false);
895 }
896
897 // un-fix all vertices
898 for (std::map<int, HyperGraph::Vertex*>::iterator vit =
899 optimizer.vertices().begin();
900 vit != optimizer.vertices().end(); ++vit) {
902 static_cast<OptimizableGraph::Vertex*>((*vit).second);
903 v->fixed() = false;
904 }
905
906 // final global optimization
907 cerr << "Initialize final optimization .. ";
908 optimizer.initializeOptimization(optimizer.edges()); // ALLLL
909 cerr << "done" << endl;
910 cerr << "Optimize .. " << endl;
911 optimizer.optimizeLoop(maxIterations);
912 cerr << "done" << endl;
913 }
914
915 if (gnudump.size() > 0)
916 gnudump_edges(gnudump, "finaltraj", optimizer.edges().begin(),
917 optimizer.edges().end(), true, false);
918 if (gnudump.size() > 0)
919 gnudump_features(gnudump, "finalfeatures", optimizer.edges().begin(),
920 optimizer.edges().end());
921 if (gnudump.size() > 0)
922 gnudump_edges(gnudump, "final", optimizer.edges().begin(),
923 optimizer.edges().end(), true, true);
924
925 if (statsFile != "") {
926 cerr << "writing stats to file \"" << statsFile << "\"";
927 ofstream os(statsFile.c_str());
928 for (int i = 0; i < maxIterations; i++) {
929 os << optimizer._statistics[i] << endl;
930 }
931 }
932
933 // // HACK write landmarks to anotherfile
934 // # if 1
935 // bool hasLandmarks = false;
936 // for (HyperGraph::EdgeSet::const_iterator it =
937 // optimizer.edges().begin(); it != optimizer.edges().end(); ++it) {
938 // const VertexSE2* from = dynamic_cast<const
939 // VertexSE2*>((*it)->vertex(0]); const VertexPointXY* to =
940 // dynamic_cast<const VertexPointXY*>((*it)->vertex(1]); if (from && to)
941 // {
942 // hasLandmarks = true;
943 // break;
944 // }
945 // }
946 // if (hasLandmarks) {
947 // string baseName = getPureFilename(gnudump);
948 // string extension = getFileExtension(gnudump);
949 // string landmarkFilename = formatString("%s_landmarks.%s",
950 // baseName.c_str(), extension.c_str()); cerr << "saving " <<
951 // landmarkFilename << " ... "; fout.open(landmarkFilename.c_str()); for
952 // (HyperGraph::EdgeSet::const_iterator it = optimizer.edges().begin();
953 // it != optimizer.edges().end(); ++it) {
954 // const VertexPointXY* to = dynamic_cast<const
955 // VertexPointXY*>((*it)->vertex(1]); if (to) {
956 // const Vector2d& p2 = to->estimate();
957 // fout << p2[0] << " " << p2[1] << endl;
958 // fout << endl;
959 // }
960 // }
961 // cerr << "done." << endl;
962 // }
963 // # endif
964
965 //}
966
967 if (outputfilename.size() > 0) {
968 cerr << "saving " << outputfilename << " ... ";
969 optimizer.save(outputfilename.c_str());
970 cerr << "done." << endl;
971 }
972
973 return 0;
974}
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)
const Vertex * vertex(size_t i) const
const EdgeSet & edges() const
returns the set of hyper-edges that are leaving/entering in this vertex
std::set< Edge * > EdgeSet
const EdgeSet & edges() const
const VertexIDMap & vertices() const
A general case Vertex for optimization.
bool marginalized() const
true => this node is marginalized out during the optimization
int dimension() const
dimension of the estimated state belonging to this node
bool fixed() const
true => this node is fixed during the optimization
int optimize(int iterations, bool online=false)
void setForceStopFlag(bool *flag)
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
bool verbose() const
verbose information during optimization
OptimizationAlgorithm * solver()
void updateDisplay(ostream &os, const SparseOptimizer &optimizer)
SparseOptimizer::Method str2method(const std::string &strMethod)
void gnudump_features(const string &gnudump, const string &file_suffix, HyperGraph::EdgeSet::const_iterator begin, HyperGraph::EdgeSet::const_iterator end)
Solver * str2solver(const std::string &strSolver_, SparseOptimizer *opt)
bool hasToStop
void gnudump_edges(const string &gnudump, const string &file_suffix, HyperGraph::EdgeSet::const_iterator begin, HyperGraph::EdgeSet::const_iterator end, bool dumpEdges, bool dumpFeatures)
void findConnectedEdgesWithCostLimit(HyperGraph::EdgeSet &selected, HyperGraph::EdgeSet &border, HyperGraph::Edge *start, HyperDijkstra::CostFunction *cost, double maxEdgeCost, double comparisonConditioner)
Definition tools.cpp:41
double get_monotonic_time()
Definition timeutil.cpp:43
Sort Edges for inserting them sequentially.
Definition g2o.cpp:66
statistics about the optimization
Definition batch_stats.h:40
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
virtual bool load(std::istream &is)
double chi2() const
returns the chi2 of the current configuration
Vertex * vertex(int id)
returns the vertex number id appropriately casted
void setRenamedTypesFromString(const std::string &types)

References g2o::OptimizableGraph::addEdge(), g2o::OptimizableGraph::addVertex(), g2o::OptimizableGraph::chi2(), g2o::OptimizableGraph::Edge::chi2(), g2o::OptimizableGraph::Edge::computeError(), g2o::OptimizableGraph::Vertex::dimension(), g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::edges(), g2o::findConnectedEdgesWithCostLimit(), g2o::OptimizableGraph::Vertex::fixed(), g2o::get_monotonic_time(), gnudump_edges(), gnudump_features(), hasToStop, g2o::HyperGraph::Vertex::id(), g2o::SparseOptimizer::initializeOptimization(), g2o::OptimizableGraph::load(), g2o::OptimizableGraph::Vertex::marginalized(), g2o::SparseOptimizer::optimize(), g2o::CommandArgs::param(), g2o::CommandArgs::paramLeftOver(), g2o::CommandArgs::parseArgs(), g2o::OptimizableGraph::Edge::robustKernel(), g2o::OptimizableGraph::save(), g2o::SparseOptimizer::setForceStopFlag(), g2o::OptimizableGraph::setRenamedTypesFromString(), g2o::SparseOptimizer::solver(), str2method(), str2solver(), updateDisplay(), g2o::SparseOptimizer::verbose(), g2o::OptimizableGraph::vertex(), g2o::HyperGraph::Edge::vertex(), and g2o::HyperGraph::vertices().

◆ sigquit_handler()

void sigquit_handler ( int q   __attribute__(unused))

Definition at line 342 of file g2o-unfold.cpp.

342{ hasToStop = 1; }

References hasToStop.

◆ str2method()

SparseOptimizer::Method str2method ( const std::string &  strMethod)

Definition at line 162 of file g2o-unfold.cpp.

162 {
163 if (strMethod == "Gauss") {
164 cerr << "# Doing Gauss" << endl;
165 return SparseOptimizer::GaussNewton;
166 }
167 if (strMethod == "Levenberg") {
168 cerr << "# Doing Levenberg-Marquardt" << endl;
169 return SparseOptimizer::LevenbergMarquardt;
170 }
171 cerr << "# Unknown optimization method: " << strMethod
172 << ", setting default to Levenberg" << endl;
173 return SparseOptimizer::LevenbergMarquardt;
174}

Referenced by main().

◆ str2solver()

Solver * str2solver ( const std::string &  strSolver_,
SparseOptimizer opt 
)

Definition at line 189 of file g2o-unfold.cpp.

189 {
190 string strSolver = strSolver_;
191 bool useCholmod = false;
192 if (strEndsWith(strSolver, "_cholmod")) {
193 string::size_type idx = strSolver.rfind("_cholmod");
194 strSolver.resize(idx);
195 useCholmod = true;
196 }
197#ifndef GO_CHOLMOD_SUPPORT
198 if (useCholmod) {
199 cerr << "Error: Cholmod is not supported in this build" << endl;
200 return 0;
201 }
202#endif
203 if (!strStartsWith(strSolver, "pcg"))
204 cerr << "# Using " << (useCholmod ? "cholmod" : "CSparse") << " "
205 << strSolver << endl;
206 else
207 cerr << "# Using PCG " << strSolver << endl;
208
209 if (strSolver == "var") {
210 BlockSolverX::LinearSolverType* linearSolver =
211 allocateLinearSolver<BlockSolverX>(useCholmod);
212 return new BlockSolverX(opt, linearSolver);
213 }
214 if (strSolver == "fix3_2") {
215 BlockSolver_3_2::LinearSolverType* linearSolver =
216 allocateLinearSolver<BlockSolver_3_2>(useCholmod);
217 return new BlockSolver_3_2(opt, linearSolver);
218 }
219 if (strSolver == "fix6_3") {
220 BlockSolver_6_3::LinearSolverType* linearSolver =
221 allocateLinearSolver<BlockSolver_6_3>(useCholmod);
222 return new BlockSolver_6_3(opt, linearSolver);
223 }
224 if (strSolver == "fix7_3") {
225 BlockSolver_7_3::LinearSolverType* linearSolver =
226 allocateLinearSolver<BlockSolver_7_3>(useCholmod);
227 return new BlockSolver_7_3(opt, linearSolver);
228 }
229 if (strSolver == "pcg") {
230 BlockSolverX::LinearSolverType* linearSolver =
232 return new BlockSolverX(opt, linearSolver);
233 }
234 if (strSolver == "pcg6_3") {
235 BlockSolver_6_3::LinearSolverType* linearSolver =
237 return new BlockSolver_6_3(opt, linearSolver);
238 }
239 if (strSolver == "pcg3_2") {
240 BlockSolver_3_2::LinearSolverType* linearSolver =
242 return new BlockSolver_3_2(opt, linearSolver);
243 }
244 cerr << "Unknown solver, setting the general but slower \"var\" " << endl;
245 BlockSolverX::LinearSolverType* linearSolver =
246 allocateLinearSolver<BlockSolverX>(useCholmod);
247 return new BlockSolverX(opt, linearSolver);
248}
linear solver using PCG, pre-conditioner is block Jacobi
BlockSolverPL< 7, 3 > BlockSolver_7_3
BlockSolverPL< 6, 3 > BlockSolver_6_3
BlockSolverPL< Eigen::Dynamic, Eigen::Dynamic > BlockSolverX
bool strEndsWith(const std::string &s, const std::string &end)
bool strStartsWith(const std::string &s, const std::string &start)
BlockSolverPL< 3, 2 > BlockSolver_3_2

References g2o::strEndsWith(), and g2o::strStartsWith().

Referenced by main().

◆ updateDisplay()

void updateDisplay ( ostream &  os,
const SparseOptimizer optimizer 
)

Definition at line 105 of file g2o-unfold.cpp.

105 {
106 // TODO edges missing
107 // TODO other than 2D types missing
108 for (SparseOptimizer::VertexIDMap::const_iterator it =
109 optimizer.vertices().begin();
110 it != optimizer.vertices().end(); ++it) {
111 const SparseOptimizer::Vertex* v =
112 static_cast<const SparseOptimizer::Vertex*>(it->second);
113 Eigen::Quaterniond quat;
114 Eigen::Vector3d trans;
115
116 bool writeVertex = false;
117 bool writePoint = false;
118
119 const VertexSE2* v2se = dynamic_cast<const VertexSE2*>(v);
120 if (v2se) {
121 writeVertex = true;
122 trans[0] = v2se->estimate().translation()[0];
123 trans[1] = v2se->estimate().translation()[1];
124 trans[2] = 0.0;
125 static Eigen::Vector3d axis(0, 0, 1);
126 quat = AngleAxis<double>(v2se->estimate().rotation().angle(), axis);
127 }
128
129 const VertexPointXY* v2point = dynamic_cast<const VertexPointXY*>(v);
130 if (v2point) {
131 writePoint = true;
132 trans[0] = v2point->estimate()[0];
133 trans[1] = v2point->estimate()[1];
134 trans[2] = 0.0;
135 }
136
137 if (writeVertex) {
138 os.put('V');
139 int id = v->id();
140 os.write((char*)&id, sizeof(int));
141 os.write((char*)&trans.x(), sizeof(double));
142 os.write((char*)&trans.y(), sizeof(double));
143 os.write((char*)&trans.z(), sizeof(double));
144 os.write((char*)&quat.w(), sizeof(double));
145 os.write((char*)&quat.x(), sizeof(double));
146 os.write((char*)&quat.y(), sizeof(double));
147 os.write((char*)&quat.z(), sizeof(double));
148 }
149
150 if (writePoint) {
151 os.put('P');
152 os.write((char*)&trans.x(), sizeof(double));
153 os.write((char*)&trans.y(), sizeof(double));
154 os.write((char*)&trans.z(), sizeof(double));
155 }
156 }
157
158 // done
159 os << "F" << flush;
160}
const Vector2 & translation() const
translational component
Definition se2.h:57
const Rotation2D & rotation() const
rotational component
Definition se2.h:61
Eigen::AngleAxis< double > AngleAxis
Definition eigen_types.h:82

References g2o::BaseVertex< D, T >::estimate(), g2o::HyperGraph::Vertex::id(), g2o::SE2::rotation(), g2o::SE2::translation(), and g2o::HyperGraph::vertices().

Referenced by main().

Variable Documentation

◆ hasToStop

bool hasToStop = false

Definition at line 340 of file g2o-unfold.cpp.

Referenced by main(), and sigquit_handler().