27#ifndef G2O_SLAM_INTERFACE_H
28#define G2O_SLAM_INTERFACE_H
39class SparseOptimizerOnline;
49 bool addNode(
const std::string& tag,
int id,
int dimension,
50 const std::vector<double>& values);
52 bool addEdge(
const std::string& tag,
int id,
int dimension,
int v1,
int v2,
53 const std::vector<double>& measurement,
54 const std::vector<double>& information);
56 bool fixNode(
const std::vector<int>& nodes);
58 bool queryState(
const std::vector<int>& nodes);
65 void setUpdateGraphEachN(
int n);
68 void setBatchSolveEachN(
int n);
interface for communicating with the SLAM algorithm
int updatedGraphEachN() const
int batchSolveEachN() const
HyperGraph::EdgeSet _edgesAdded
SparseOptimizerOnline * optimizer()
SparseOptimizerOnline * _optimizer
HyperGraph::VertexSet _verticesAdded
std::set< Edge * > EdgeSet
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
#define G2O_INTERACTIVE_API