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