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
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");
387 "graph file which will be processed");
388
390
391 if (listTypes) {
392 OptimizableGraph::printRegisteredTypes(cout, true);
393 }
394
398
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) {
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
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) {
444 }
445 for (HyperGraph::VertexIDMap::iterator it = optimizer.
vertices().begin();
446 it != optimizer.
vertices().end(); ++it) {
450
452 }
453 }
454 cerr << "done." << endl;
455 }
456
457
458
459
460
461
462
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();
486
487
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
518 SparseOptimizer::Vertex* v =
519 dynamic_cast<SparseOptimizer::Vertex*>(e->vertex(0));
521 assert(v1Added);
522 doInit = 2;
523 if (v->dimension() == maxDim) vertexCount++;
524 }
525
526 if (!v2 && addNextEdge) {
527
528 SparseOptimizer::Vertex* v =
529 dynamic_cast<SparseOptimizer::Vertex*>(e->vertex(1));
531 assert(v2Added);
532 doInit = 1;
533 if (v->dimension() == maxDim) vertexCount++;
534 }
535
536 if (addNextEdge) {
537
538
540 cerr << "Unable to add edge " << e->vertex(0)->id() << " -> "
541 << e->vertex(1)->id() << endl;
542 }
543
544 if (doInit) {
549 switch (doInit) {
550 case 1:
551 if (e->initialEstimatePossible(to, from)) {
552
553
554
555
556 e->initialEstimate(to, from);
557 }
558 break;
559 case 2:
560 if (e->initialEstimatePossible(from, to)) {
561
562
563
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
576 if (vertexCount - lastOptimizedVertexCount >= updateGraphEachN) {
578 int currentIt = optimizer.
optimize(incIterations);
580 cumTime += dts;
581
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) {
602 lastVisUpdateVertexCount = vertexCount;
603 }
604 }
605
606 }
607
608 } else {
609 if (gnudump.size() > 0)
611 optimizer.
edges().end(),
true,
false);
612 if (gnudump.size() > 0)
614 optimizer.
edges().end());
615 if (gnudump.size() > 0)
617 optimizer.
edges().end(),
true,
true);
618
619
620
621 cerr <<
"Initial chi2 = " << optimizer.
chi2() << endl;
622
623 if (statsFile != "") {
624
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)
635 optimizer.
edges().end(),
true,
false);
636 if (gnudump.size() > 0)
638 optimizer.
edges().end());
639 if (gnudump.size() > 0)
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) {
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 .. ";
663
666
667 for (HyperGraph::EdgeSet::const_iterator it = optimizer.
edges().begin();
668 it != optimizer.
edges().end(); ++it) {
672 double edgeChi2 = e->
chi2();
673 if (edgeChi2 > chi2Thres) {
676
677 if (from && to) {
678 highErrorEdges.insert(*it);
679 continue;
680 }
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)
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
702 cerr << "Fixing the whole graph ";
703 for (std::map<int, HyperGraph::Vertex*>::iterator vit =
705 vit != optimizer.
vertices().end(); ++vit) {
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
725
727 bool edgesSelected = false;
728
730 2.0 / chi2Thres);
731
732 if (selected.size() > 10) {
733 edgesSelected = true;
734 cerr << " (" << selected.size() << ", " << border.size() << ")";
735
736
737
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
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
783 for (HyperGraph::EdgeSet::iterator eit = (*it).first.begin();
784 eit != (*it).first.end(); ++eit) {
786
789 vfrom->
fixed() =
false;
792 vto->
fixed() =
false;
793 }
794 }
795 cerr << "done" << endl;
796
797
798 cerr << "Initialize optimization of subgraphs .. ";
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
809 cerr << "S";
810 HyperGraph::EdgeSet::iterator eit = (*it).second.begin();
811
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
826 cerr << "I";
827 optimizer.initializeActiveSubsetViaMeasurements(initNode,
828 guessCostFunction);
829 cerr << "-";
830 }
831 cerr << " .. done" << endl;
832
833 if (gnudump.size() > 0)
835 optimizer.
edges().end(),
true,
false);
836
837
838 cerr << "Optimize subgraphs .. " << endl;
839 optimizer.optimizeLoop(maxIterations);
840 cerr << "done" << endl;
841
842 if (gnudump.size() > 0)
844 optimizer.
edges().end(),
true,
false);
845
846 if (0)
847 if (highErrorEdgesToFeatures.size() > 0) {
849
850
851 cerr << "Fixing the whole graph ";
852 for (std::map<int, HyperGraph::Vertex*>::iterator vit =
854 vit != optimizer.
vertices().end(); ++vit) {
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) {
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)
880 edgesToBadFeatures.begin(),
881 edgesToBadFeatures.end());
882
883 cerr << "Initialize optimization of bad features .. ";
885 cerr << "done" << endl;
886
887
888 cerr << "Optimize bad features .. " << endl;
889 optimizer.optimizeLoop(maxIterations / 2);
890 cerr << "done" << endl;
891
892 if (gnudump.size() > 0)
894 optimizer.
edges().end(),
true,
false);
895 }
896
897
898 for (std::map<int, HyperGraph::Vertex*>::iterator vit =
900 vit != optimizer.
vertices().end(); ++vit) {
904 }
905
906
907 cerr << "Initialize final optimization .. ";
909 cerr << "done" << endl;
910 cerr << "Optimize .. " << endl;
911 optimizer.optimizeLoop(maxIterations);
912 cerr << "done" << endl;
913 }
914
915 if (gnudump.size() > 0)
917 optimizer.
edges().end(),
true,
false);
918 if (gnudump.size() > 0)
920 optimizer.
edges().end());
921 if (gnudump.size() > 0)
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
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
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)
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)
double get_monotonic_time()
Sort Edges for inserting them sequentially.
statistics about the optimization
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)