g2o
|
interface for communicating with the SLAM algorithm More...
#include <abstract_slam_interface.h>
Public Member Functions | |
virtual bool | addNode (const std::string &tag, int id, int dimension, const std::vector< double > &values)=0 |
virtual bool | addEdge (const std::string &tag, int id, int dimension, int v1, int v2, const std::vector< double > &measurement, const std::vector< double > &information)=0 |
virtual bool | fixNode (const std::vector< int > &nodes)=0 |
virtual bool | queryState (const std::vector< int > &nodes)=0 |
virtual bool | solveState ()=0 |
interface for communicating with the SLAM algorithm
This interface allows the parser to communicate with the SLAM algorithm.
Definition at line 40 of file abstract_slam_interface.h.
|
pure virtual |
adding an edge to the SLAM engine.
tag | the tag specifying the type of the vertex |
id | the unique id of the edge. |
dimension | the dimension of the edge. |
v1 | the unique id of the edge of the first vertex |
v2 | the unique id of the edge of the second vertex |
measurement | the measurement of the constraint |
information | the information matrix (inverse of the covariance) representing the uncertainty of the measurement (row-major upper triangular and diagonal) |
Implemented in g2o::G2oSlamInterface, and ExampleSlamInterface.
Referenced by SlamParser::SlamContextInterface::process().
|
pure virtual |
adding a node to the SLAM engine.
tag | the tag specifying the type of the vertex |
id | the unique id of the node. |
dimension | the dimension of the node. |
values | the pose of the node, may be empty (i.e., the engine should initialize the node itself) |
Implemented in g2o::G2oSlamInterface, and ExampleSlamInterface.
Referenced by SlamParser::SlamContextInterface::process().
|
pure virtual |
set some nodes to a fixed position
nodes | the list of vertex IDs to fix |
Implemented in g2o::G2oSlamInterface, and ExampleSlamInterface.
Referenced by SlamParser::SlamContextInterface::process().
|
pure virtual |
Ask the SLAM engine to print the current estimate of the variables
nodes | the list of vertex IDs to print, if empty print all variables |
Implemented in g2o::G2oSlamInterface, and ExampleSlamInterface.
Referenced by SlamParser::SlamContextInterface::process().
|
pure virtual |
ask the engine to solve
Implemented in g2o::G2oSlamInterface, and ExampleSlamInterface.
Referenced by SlamParser::SlamContextInterface::process().