g2o
Public Member Functions | Protected Attributes | List of all members
ExampleSlamInterface Class Reference

example for an interface to a SLAM algorithm More...

#include <example_slam_interface.h>

Inheritance diagram for ExampleSlamInterface:
Inheritance graph
[legend]
Collaboration diagram for ExampleSlamInterface:
Collaboration graph
[legend]

Public Member Functions

 ExampleSlamInterface ()
 
bool addNode (const std::string &tag, int id, int dimension, const std::vector< double > &values)
 
bool addEdge (const std::string &tag, int id, int dimension, int v1, int v2, const std::vector< double > &measurement, const std::vector< double > &information)
 
bool fixNode (const std::vector< int > &nodes)
 
bool queryState (const std::vector< int > &nodes)
 
bool solveState ()
 

Protected Attributes

std::map< int, std::pair< std::string, std::vector< double > > > _vertices
 the original value of the input (actually not needed if a real SLAM engine is running) More...
 

Detailed Description

example for an interface to a SLAM algorithm

Example for an interface to a SLAM algorithm. You may modify this class to fit your needs. The example class does not actually perform any optimization, it just keeps the input values and outputs the same values if asked. See the documentation of SlamParser::AbstractSlamInterface for details.

Definition at line 43 of file example_slam_interface.h.

Constructor & Destructor Documentation

ExampleSlamInterface::ExampleSlamInterface ( )

Definition at line 32 of file example_slam_interface.cpp.

33 {
34 }

Member Function Documentation

bool ExampleSlamInterface::addEdge ( const std::string &  tag,
int  id,
int  dimension,
int  v1,
int  v2,
const std::vector< double > &  measurement,
const std::vector< double > &  information 
)
virtual

adding an edge to the SLAM engine.

Parameters
tagthe tag specifying the type of the vertex
idthe unique id of the edge.
dimensionthe dimension of the edge.
v1the unique id of the edge of the first vertex
v2the unique id of the edge of the second vertex
measurementthe measurement of the constraint
informationthe information matrix (inverse of the covariance) representing the uncertainty of the measurement (row-major upper triangular and diagonal)
Returns
true, if adding was successful

Implements SlamParser::AbstractSlamInterface.

Definition at line 55 of file example_slam_interface.cpp.

56 {
57  cerr << "ADDING EDGE " << tag << " id=" << id << " dim=" << dimension
58  << " (" << v1 << " <-> " << v2 << ")" << " measurement=";
59  for (size_t i = 0; i < measurement.size(); ++i)
60  cerr << " " << measurement[i];
61  cerr << " information=";
62  for (size_t i = 0; i < information.size(); ++i)
63  cerr << " " << information[i];
64  cerr << endl;
65  return true;
66 }
bool ExampleSlamInterface::addNode ( const std::string &  tag,
int  id,
int  dimension,
const std::vector< double > &  values 
)
virtual

adding a node to the SLAM engine.

Parameters
tagthe tag specifying the type of the vertex
idthe unique id of the node.
dimensionthe dimension of the node.
valuesthe pose of the node, may be empty (i.e., the engine should initialize the node itself)
Returns
true, if adding was successful

Implements SlamParser::AbstractSlamInterface.

Definition at line 36 of file example_slam_interface.cpp.

37 {
38  cerr << "ADDING NODE " << tag << " id=" << id << " dim=" << dimension;
39  if (values.size()) {
40  cerr << "\tpose=";
41  for (size_t i = 0; i < values.size(); ++i)
42  cerr << " " << values[i];
43  }
44  cerr << endl;
45 
46  // store the values
47  if (values.size() == 0)
48  _vertices[id] = make_pair(tag, std::vector<double>(dimension));
49  else
50  _vertices[id] = make_pair(tag, values);
51 
52  return true;
53 }
std::map< int, std::pair< std::string, std::vector< double > > > _vertices
the original value of the input (actually not needed if a real SLAM engine is running) ...
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
Definition: protocol.txt:7
bool ExampleSlamInterface::fixNode ( const std::vector< int > &  nodes)
virtual

set some nodes to a fixed position

Parameters
nodesthe list of vertex IDs to fix
Returns
true, if successful

Implements SlamParser::AbstractSlamInterface.

Definition at line 68 of file example_slam_interface.cpp.

69 {
70  cerr << "FIXING NODE";
71  for (size_t i = 0; i < nodes.size(); ++i)
72  cerr << " " << nodes[i];
73  cerr << endl;
74  return true;
75 }
bool ExampleSlamInterface::queryState ( const std::vector< int > &  nodes)
virtual

Ask the SLAM engine to print the current estimate of the variables

Parameters
nodesthe list of vertex IDs to print, if empty print all variables
Returns
true, if successful

Implements SlamParser::AbstractSlamInterface.

Definition at line 77 of file example_slam_interface.cpp.

References values.

78 {
79  cerr << "QUERY STATE";
80  for (size_t i = 0; i < nodes.size(); ++i)
81  cerr << " " << nodes[i];
82  cerr << endl;
83 
84  // actually output the values to the evaluator
85  // If a SLAM algorithm is running we would need to copy its estimate
86  if (nodes.size() == 0) {
87  // print all nodes
88  for (std::map<int, std::pair<std::string, std::vector<double> > >::const_iterator it = _vertices.begin();
89  it != _vertices.end(); ++it) {
90  cout << it->second.first << " " << it->first;
91  const vector<double>& values = it->second.second;
92  for (size_t j = 0; j < values.size(); ++j)
93  cout << " " << values[j];
94  cout << endl;
95  }
96  } else {
97  for (size_t i = 0; i < nodes.size(); ++i) {
98  std::map<int, std::pair<std::string, std::vector<double> > >::const_iterator it = _vertices.find(nodes[i]);
99  if (it != _vertices.end()) {
100  cout << it->second.first << " " << it->first;
101  const vector<double>& values = it->second.second;
102  for (size_t j = 0; j < values.size(); ++j)
103  cout << " " << values[j];
104  cout << endl;
105  }
106  }
107  }
108 
109  return true;
110 }
std::map< int, std::pair< std::string, std::vector< double > > > _vertices
the original value of the input (actually not needed if a real SLAM engine is running) ...
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
Definition: protocol.txt:7
bool ExampleSlamInterface::solveState ( )
virtual

ask the engine to solve

Returns
true, if successful

Implements SlamParser::AbstractSlamInterface.

Definition at line 112 of file example_slam_interface.cpp.

113 {
114  cerr << "SOLVE STATE" << endl;
115  return true;
116 }

Member Data Documentation

std::map<int, std::pair<std::string, std::vector<double> > > ExampleSlamInterface::_vertices
protected

the original value of the input (actually not needed if a real SLAM engine is running)

Definition at line 60 of file example_slam_interface.h.


The documentation for this class was generated from the following files: