g2o
|
#include <hyper_graph.h>
Classes | |
class | Data |
data packet for a vertex. Extend this class to store in the vertices the potential additional information you need (e.g. images, laser scans, ...). More... | |
class | DataContainer |
Container class that implements an interface for adding/removing Data elements in a linked list. More... | |
class | Edge |
struct | HyperGraphElement |
class | Vertex |
abstract Vertex, your types must derive from that one More... | |
Public Types | |
typedef std::bitset< HyperGraph::HGET_NUM_ELEMS > | GraphElemBitset |
typedef std::set< Edge * > | EdgeSet |
typedef std::set< Vertex * > | VertexSet |
typedef std::unordered_map< int, Vertex * > | VertexIDMap |
typedef std::vector< Vertex * > | VertexContainer |
Public Member Functions | |
HyperGraph () | |
constructs an empty hyper graph More... | |
virtual | ~HyperGraph () |
destroys the hyper-graph and all the vertices of the graph More... | |
Vertex * | vertex (int id) |
returns a vertex id in the hyper-graph, or 0 if the vertex id is not present More... | |
const Vertex * | vertex (int id) const |
returns a vertex id in the hyper-graph, or 0 if the vertex id is not present More... | |
virtual bool | removeVertex (Vertex *v, bool detach=false) |
removes a vertex from the graph. Returns true on success (vertex was present) More... | |
virtual bool | removeEdge (Edge *e) |
removes a vertex from the graph. Returns true on success (edge was present) More... | |
virtual void | clear () |
clears the graph and empties all structures. More... | |
const VertexIDMap & | vertices () const |
VertexIDMap & | vertices () |
const EdgeSet & | edges () const |
EdgeSet & | edges () |
virtual bool | addVertex (Vertex *v) |
virtual bool | addEdge (Edge *e) |
virtual bool | setEdgeVertex (Edge *e, int pos, Vertex *v) |
virtual bool | mergeVertices (Vertex *vBig, Vertex *vSmall, bool erase) |
virtual bool | detachVertex (Vertex *v) |
virtual bool | changeId (Vertex *v, int newId) |
Public Attributes | |
class G2O_CORE_API | Data |
class G2O_CORE_API | DataContainer |
class G2O_CORE_API | Vertex |
class G2O_CORE_API | Edge |
Static Public Attributes | |
static const int | UnassignedId = -1 |
static const int | InvalidId = -2 |
Protected Attributes | |
VertexIDMap | _vertices |
EdgeSet | _edges |
Private Member Functions | |
HyperGraph (const HyperGraph &) | |
HyperGraph & | operator= (const HyperGraph &) |
Class that models a directed Hyper-Graph. An hyper graph is a graph where an edge can connect one or more nodes. Both Vertices and Edges of an hyoper graph derive from the same class HyperGraphElement, thus one can implement generic algorithms that operate transparently on edges or vertices (see HyperGraphAction).
The vertices are uniquely identified by an int id, while the edges are identfied by their pointers.
Definition at line 55 of file hyper_graph.h.
typedef std::set<Edge*> g2o::HyperGraph::EdgeSet |
Definition at line 135 of file hyper_graph.h.
typedef std::bitset<HyperGraph::HGET_NUM_ELEMS> g2o::HyperGraph::GraphElemBitset |
Definition at line 74 of file hyper_graph.h.
typedef std::vector<Vertex*> g2o::HyperGraph::VertexContainer |
Definition at line 139 of file hyper_graph.h.
typedef std::unordered_map<int, Vertex*> g2o::HyperGraph::VertexIDMap |
Definition at line 138 of file hyper_graph.h.
typedef std::set<Vertex*> g2o::HyperGraph::VertexSet |
Definition at line 136 of file hyper_graph.h.
g2o::HyperGraph::HyperGraph | ( | ) |
|
virtual |
destroys the hyper-graph and all the vertices of the graph
Definition at line 239 of file hyper_graph.cpp.
References clear().
|
inlineprivate |
Definition at line 279 of file hyper_graph.h.
|
virtual |
Adds an edge to the graph. If the edge is already in the graph, it does nothing and returns false. Otherwise it returns true.
Reimplemented in g2o::OptimizableGraph.
Definition at line 117 of file hyper_graph.cpp.
References _edges, g2o::HyperGraph::Vertex::edges(), and g2o::HyperGraph::Edge::vertices().
Referenced by g2o::OptimizableGraph::addEdge().
|
virtual |
adds a vertex to the graph. The id of the vertex should be set before invoking this function. the function fails if another vertex with the same id is already in the graph. returns true, on success, or false on failure.
Reimplemented in g2o::OptimizableGraph.
Definition at line 94 of file hyper_graph.cpp.
References g2o::HyperGraph::Edge::_vertices, g2o::HyperGraph::Vertex::id(), and g2o::HyperGraph::Edge::vertex().
Referenced by g2o::OptimizableGraph::addVertex().
|
virtual |
changes the id of a vertex already in the graph, and updates the bookkeeping @ returns false if the vertex is not in the graph;
Definition at line 107 of file hyper_graph.cpp.
References g2o::HyperGraph::Edge::_vertices, g2o::HyperGraph::Vertex::id(), g2o::HyperGraph::Vertex::setId(), and g2o::HyperGraph::Edge::vertex().
|
virtual |
clears the graph and empties all structures.
Reimplemented in g2o::SparseOptimizer.
Definition at line 229 of file hyper_graph.cpp.
References _edges, and g2o::HyperGraph::Edge::_vertices.
Referenced by g2o::SparseOptimizer::clear(), g2o::OptimizableGraph::clearParameters(), ~HyperGraph(), and g2o::OptimizableGraph::~OptimizableGraph().
|
virtual |
detaches a vertex from all connected edges
Definition at line 166 of file hyper_graph.cpp.
References g2o::HyperGraph::Edge::_vertices, g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Vertex::id(), setEdgeVertex(), g2o::HyperGraph::Edge::vertex(), and g2o::HyperGraph::Edge::vertices().
Referenced by removeVertex().
|
inline |
Definition at line 230 of file hyper_graph.h.
Referenced by g2o::G2oSlamInterface::addEdge(), g2o::OptimizableGraph::addGraph(), g2o::addOdometryCalibLinksDifferential(), g2o::applyAction(), g2o::OptimizableGraph::chi2(), g2o::dumpEdges(), g2o::SparseOptimizerOnline::gnuplotVisualization(), g2o::BackBoneTreeAction::init(), g2o::SparseOptimizer::initializeOptimization(), main(), g2o::OptimizableGraph::save(), g2o::saveGnuplot(), MainWindow::setRobustKernel(), g2o::JacobianWorkspace::updateSize(), g2o::OptimizableGraph::verifyInformationMatrices(), and g2o::Gm2dlIO::writeGm2dl().
|
inline |
merges two (valid) vertices, adjusts the bookkeeping and relabels all edges. the observations of vSmall are retargeted to vBig. If erase = true, vSmall is deleted from the graph repeatedly calls setEdgeVertex(...)
Definition at line 141 of file hyper_graph.cpp.
References g2o::HyperGraph::Edge::_vertices, g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Vertex::id(), removeVertex(), setEdgeVertex(), g2o::HyperGraph::Edge::vertex(), and g2o::HyperGraph::Edge::vertices().
|
inlineprivate |
Definition at line 280 of file hyper_graph.h.
|
virtual |
removes a vertex from the graph. Returns true on success (edge was present)
Definition at line 206 of file hyper_graph.cpp.
References _edges, g2o::HyperGraph::Vertex::edges(), and g2o::HyperGraph::Edge::vertices().
Referenced by removeVertex().
|
virtual |
removes a vertex from the graph. Returns true on success (vertex was present)
Reimplemented in g2o::SparseOptimizer.
Definition at line 182 of file hyper_graph.cpp.
References g2o::HyperGraph::Edge::_vertices, detachVertex(), g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Vertex::id(), and removeEdge().
Referenced by mergeVertices(), and g2o::SparseOptimizer::removeVertex().
|
virtual |
Sets the vertex un position "pos" within the edge and keeps the bookkeeping consistent. If v ==0, the vertex is set to "invalid"
Reimplemented in g2o::OptimizableGraph.
Definition at line 130 of file hyper_graph.cpp.
References g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Edge::setVertex(), and g2o::HyperGraph::Edge::vertex().
Referenced by detachVertex(), mergeVertices(), and g2o::OptimizableGraph::setEdgeVertex().
HyperGraph::Vertex * g2o::HyperGraph::vertex | ( | int | id | ) |
returns a vertex id in the hyper-graph, or 0 if the vertex id is not present
Definition at line 78 of file hyper_graph.cpp.
References g2o::HyperGraph::Edge::_vertices.
Referenced by g2o::OptimizableGraph::vertex().
const HyperGraph::Vertex * g2o::HyperGraph::vertex | ( | int | id | ) | const |
returns a vertex id in the hyper-graph, or 0 if the vertex id is not present
Definition at line 86 of file hyper_graph.cpp.
References g2o::HyperGraph::Edge::_vertices.
|
inline |
Definition at line 225 of file hyper_graph.h.
Referenced by g2o::OptimizableGraph::addGraph(), g2o::applyAction(), g2o::Slam2DViewer::draw(), g2o::EstimatePropagator::EstimatePropagator(), g2o::SparseOptimizer::findGauge(), g2o::SparseOptimizer::gaugeFreedom(), g2o::HyperDijkstra::HyperDijkstra(), g2o::SparseOptimizer::initializeOptimization(), main(), g2o::SparseOptimizerOnline::optimize(), MainWindow::prepare(), g2o::G2oSlamInterface::queryState(), g2o::saveGnuplot(), g2o::SparseOptimizer::setToOrigin(), g2o::G2oSlamInterface::solve(), g2o::SolverSLAM2DLinear::solveOrientation(), updateDisplay(), g2o::Gm2dlIO::updateLaserData(), and g2o::Gm2dlIO::writeGm2dl().
|
inline |
Definition at line 227 of file hyper_graph.h.
|
protected |
Definition at line 275 of file hyper_graph.h.
Referenced by addEdge(), clear(), and removeEdge().
|
protected |
Definition at line 274 of file hyper_graph.h.
Definition at line 76 of file hyper_graph.h.
Definition at line 77 of file hyper_graph.h.
Definition at line 79 of file hyper_graph.h.
|
static |
Definition at line 72 of file hyper_graph.h.
|
static |
Definition at line 71 of file hyper_graph.h.
Referenced by g2o::OptimizableGraph::saveEdge(), and g2o::OptimizableGraph::setFixed().
Definition at line 78 of file hyper_graph.h.