g2o
g2o_slam_interface.h
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #ifndef G2O_SLAM_INTERFACE_H
28 #define G2O_SLAM_INTERFACE_H
29 
30 #include "g2o_interactive_api.h"
33 
34 #include <map>
35 #include <vector>
36 
37 namespace g2o {
38 
39  class SparseOptimizerOnline;
40 
42  {
43  public:
44  enum SolveResult { SOLVED, SOLVED_BATCH, NOOP, ERROR };
45 
46  public:
48 
49  bool addNode(const std::string& tag, int id, int dimension, const std::vector<double>& values);
50 
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);
52 
53  bool fixNode(const std::vector<int>& nodes);
54 
55  bool queryState(const std::vector<int>& nodes);
56 
57  bool solveState();
58 
59  SolveResult solve();
60 
61  int updatedGraphEachN() const { return _updateGraphEachN;}
62  void setUpdateGraphEachN(int n);
63 
64  int batchSolveEachN() const { return _batchEveryN;}
65  void setBatchSolveEachN(int n);
66 
67  protected:
76 
79 
80  OptimizableGraph::Vertex* addVertex(int dimension, int id);
81  bool printVertex(OptimizableGraph::Vertex* v);
82  };
83 
84 } // end namespace
85 
86 #endif
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
Definition: protocol.txt:7
HyperGraph::VertexSet _verticesAdded
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
interface for communicating with the SLAM algorithm
std::set< Edge * > EdgeSet
Definition: hyper_graph.h:135
SparseOptimizerOnline * _optimizer
A general case Vertex for optimization.
HyperGraph::EdgeSet _edgesAdded
#define G2O_INTERACTIVE_API