Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef G2O_SLAM_INTERFACE_H
00018 #define G2O_SLAM_INTERFACE_H
00019
00020 #include "g2o/core/optimizable_graph.h"
00021 #include "slam_parser/interface/abstract_slam_interface.h"
00022
00023 #include <map>
00024 #include <vector>
00025
00026 namespace g2o {
00027
00028 class SparseOptimizerOnline;
00029
00030 class G2oSlamInterface : public SlamParser::AbstractSlamInterface
00031 {
00032 public:
00033 G2oSlamInterface(SparseOptimizerOnline* optimizer);
00034
00035 bool addNode(const std::string& tag, int id, int dimension, const std::vector<double>& values);
00036
00037 bool addEdge(const std::string& tag, int id, int dimension, int v1, int v2, const std::vector<double>& measurement, const std::vector<double>& information);
00038
00039 bool fixNode(const std::vector<int>& nodes);
00040
00041 bool queryState(const std::vector<int>& nodes);
00042
00043 bool solveState();
00044
00045 int updatedGraphEachN() const { return _updateGraphEachN;}
00046 void setUpdateGraphEachN(int n);
00047
00048 protected:
00049 SparseOptimizerOnline* _optimizer;
00050 bool _firstOptimization;
00051 int _nodesAdded;
00052 int _incIterations;
00053 int _updateGraphEachN;
00054 int _batchEveryN;
00055 int _lastBatchStep;
00056 bool _initSolverDone;
00057
00058 HyperGraph::VertexSet _verticesAdded;
00059 HyperGraph::EdgeSet _edgesAdded;
00060
00061 OptimizableGraph::Vertex* addVertex(int dimension, int id);
00062 bool printVertex(OptimizableGraph::Vertex* v);
00063 };
00064
00065 }
00066
00067 #endif