g2o
Loading...
Searching...
No Matches
Classes | Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Protected Attributes | Private Member Functions | List of all members
g2o::HyperGraph Class Reference

#include <hyper_graph.h>

Inheritance diagram for g2o::HyperGraph:
Inheritance graph
[legend]

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
 
virtual ~HyperGraph ()
 destroys the hyper-graph and all the vertices of the graph
 
Vertexvertex (int id)
 
const Vertexvertex (int id) const
 
virtual bool removeVertex (Vertex *v, bool detach=false)
 
virtual bool removeEdge (Edge *e)
 
virtual void clear ()
 clears the graph and empties all structures.
 
const VertexIDMapvertices () const
 
VertexIDMapvertices ()
 
const EdgeSetedges () const
 
EdgeSetedges ()
 
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 &)
 
HyperGraphoperator= (const HyperGraph &)
 

Detailed Description

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 hyper 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 53 of file hyper_graph.h.

Member Typedef Documentation

◆ EdgeSet

typedef std::set<Edge*> g2o::HyperGraph::EdgeSet

Definition at line 141 of file hyper_graph.h.

◆ GraphElemBitset

typedef std::bitset<HyperGraph::HGET_NUM_ELEMS> g2o::HyperGraph::GraphElemBitset

Definition at line 70 of file hyper_graph.h.

◆ VertexContainer

Definition at line 145 of file hyper_graph.h.

◆ VertexIDMap

typedef std::unordered_map<int, Vertex*> g2o::HyperGraph::VertexIDMap

Definition at line 144 of file hyper_graph.h.

◆ VertexSet

typedef std::set<Vertex*> g2o::HyperGraph::VertexSet

Definition at line 142 of file hyper_graph.h.

Constructor & Destructor Documentation

◆ HyperGraph() [1/2]

g2o::HyperGraph::HyperGraph ( )

constructs an empty hyper graph

Definition at line 204 of file hyper_graph.cpp.

204{}

◆ ~HyperGraph()

g2o::HyperGraph::~HyperGraph ( )
virtual

destroys the hyper-graph and all the vertices of the graph

Definition at line 219 of file hyper_graph.cpp.

virtual void clear()
clears the graph and empties all structures.

References clear().

◆ HyperGraph() [2/2]

g2o::HyperGraph::HyperGraph ( const HyperGraph )
inlineprivate

Definition at line 302 of file hyper_graph.h.

302{}

Member Function Documentation

◆ addEdge()

bool g2o::HyperGraph::addEdge ( Edge e)
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 93 of file hyper_graph.cpp.

93 {
94 for (Vertex* v : e->vertices()) { // be sure that all vertices are set
95 if (!v) return false;
96 }
97
98 // check for duplicates in the vertices and do not add this edge
99 if (e->vertices().size() == 2) {
100 if (e->vertices()[0] == e->vertices()[1]) return false;
101 } else if (e->vertices().size() == 3) {
102 if (e->vertices()[0] == e->vertices()[1] ||
103 e->vertices()[0] == e->vertices()[2] ||
104 e->vertices()[1] == e->vertices()[2])
105 return false;
106 } else if (e->vertices().size() > 3) {
107 std::unordered_set<Vertex*> vertexPointer;
108 std::copy(e->vertices().begin(), e->vertices().end(),
109 std::inserter(vertexPointer, vertexPointer.begin()));
110 if (vertexPointer.size() != e->vertices().size()) return false;
111 }
112
113 std::pair<EdgeSet::iterator, bool> result = _edges.insert(e);
114 if (!result.second) return false;
115
116 for (Vertex* v : e->vertices()) { // connect the vertices to this edge
117 v->edges().insert(e);
118 }
119
120 return true;
121}
const VertexIDMap & vertices() const

References _edges, and g2o::HyperGraph::Edge::vertices().

Referenced by g2o::OptimizableGraph::addEdge().

◆ addVertex()

bool g2o::HyperGraph::addVertex ( Vertex v)
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 75 of file hyper_graph.cpp.

75 {
76 auto result = _vertices.insert(std::make_pair(v->id(), v));
77 return result.second;
78}
VertexIDMap _vertices

References _vertices, and g2o::HyperGraph::Vertex::id().

Referenced by g2o::OptimizableGraph::addVertex().

◆ changeId()

bool g2o::HyperGraph::changeId ( Vertex v,
int  newId 
)
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 84 of file hyper_graph.cpp.

84 {
85 Vertex* v2 = vertex(v->id());
86 if (v != v2) return false;
87 _vertices.erase(v->id());
88 v->setId(newId);
89 _vertices.insert(std::make_pair(v->id(), v));
90 return true;
91}
class G2O_CORE_API Vertex
Definition hyper_graph.h:74
Vertex * vertex(int id)

References _vertices, g2o::HyperGraph::Vertex::id(), g2o::HyperGraph::Vertex::setId(), and vertex().

◆ clear()

void g2o::HyperGraph::clear ( )
virtual

clears the graph and empties all structures.

Reimplemented in g2o::SparseOptimizer.

Definition at line 206 of file hyper_graph.cpp.

206 {
207#if G2O_DELETE_IMPLICITLY_OWNED_OBJECTS
208 for (VertexIDMap::iterator it = _vertices.begin(); it != _vertices.end();
209 ++it)
210 delete (it->second);
211 for (EdgeSet::iterator it = _edges.begin(); it != _edges.end(); ++it)
212 delete (*it);
213#endif
214
215 _vertices.clear();
216 _edges.clear();
217}

References _edges, and _vertices.

Referenced by g2o::SparseOptimizer::clear(), g2o::OptimizableGraph::clearParameters(), ~HyperGraph(), and g2o::OptimizableGraph::~OptimizableGraph().

◆ detachVertex()

bool g2o::HyperGraph::detachVertex ( Vertex v)
virtual

detaches a vertex from all connected edges

Definition at line 152 of file hyper_graph.cpp.

152 {
153 VertexIDMap::iterator it = _vertices.find(v->id());
154 if (it == _vertices.end()) return false;
155 assert(it->second == v);
156 EdgeSet tmp(v->edges());
157 for (EdgeSet::iterator it = tmp.begin(); it != tmp.end(); ++it) {
158 HyperGraph::Edge* e = *it;
159 for (size_t i = 0; i < e->vertices().size(); i++) {
160 if (v == e->vertex(i)) setEdgeVertex(e, i, 0);
161 }
162 }
163 return true;
164}
virtual bool setEdgeVertex(Edge *e, int pos, Vertex *v)
std::set< Edge * > EdgeSet

References _vertices, g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Vertex::id(), setEdgeVertex(), g2o::HyperGraph::Edge::vertex(), and g2o::HyperGraph::Edge::vertices().

Referenced by removeVertex().

◆ edges() [1/2]

EdgeSet & g2o::HyperGraph::edges ( )
inline
Returns
the set of edges of the hyper graph

Definition at line 255 of file hyper_graph.h.

255{ return _edges; }

◆ edges() [2/2]

const EdgeSet & g2o::HyperGraph::edges ( ) const
inline

◆ mergeVertices()

bool g2o::HyperGraph::mergeVertices ( Vertex vBig,
Vertex vSmall,
bool  erase 
)
virtual

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 132 of file hyper_graph.cpp.

132 {
133 VertexIDMap::iterator it = _vertices.find(vBig->id());
134 if (it == _vertices.end()) return false;
135
136 it = _vertices.find(vSmall->id());
137 if (it == _vertices.end()) return false;
138
139 EdgeSet tmp(vSmall->edges());
140 bool ok = true;
141 for (EdgeSet::iterator it = tmp.begin(); it != tmp.end(); ++it) {
142 HyperGraph::Edge* e = *it;
143 for (size_t i = 0; i < e->vertices().size(); i++) {
144 Vertex* v = e->vertex(i);
145 if (v == vSmall) ok &= setEdgeVertex(e, i, vBig);
146 }
147 }
148 if (erase) removeVertex(vSmall);
149 return ok;
150}
virtual bool removeVertex(Vertex *v, bool detach=false)

References _vertices, g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Vertex::id(), removeVertex(), setEdgeVertex(), g2o::HyperGraph::Edge::vertex(), and g2o::HyperGraph::Edge::vertices().

◆ operator=()

HyperGraph & g2o::HyperGraph::operator= ( const HyperGraph )
inlineprivate

Definition at line 303 of file hyper_graph.h.

303{ return *this; }

◆ removeEdge()

bool g2o::HyperGraph::removeEdge ( Edge e)
virtual

removes a vertex from the graph. Returns true on success (edge was present)

Definition at line 188 of file hyper_graph.cpp.

188 {
189 EdgeSet::iterator it = _edges.find(e);
190 if (it == _edges.end()) return false;
191 _edges.erase(it);
192 for (std::vector<Vertex*>::iterator vit = e->vertices().begin();
193 vit != e->vertices().end(); ++vit) {
194 Vertex* v = *vit;
195 if (!v) continue;
196 it = v->edges().find(e);
197 assert(it != v->edges().end());
198 v->edges().erase(it);
199 }
200 release(e);
201 return true;
202}
void release(T *obj)
Definition ownership.h:8

References _edges, g2o::HyperGraph::Vertex::edges(), g2o::release(), and g2o::HyperGraph::Edge::vertices().

Referenced by removeVertex().

◆ removeVertex()

bool g2o::HyperGraph::removeVertex ( Vertex v,
bool  detach = false 
)
virtual

removes a vertex from the graph. Returns true on success (vertex was present)

Reimplemented in g2o::SparseOptimizer.

Definition at line 166 of file hyper_graph.cpp.

166 {
167 if (detach) {
168 bool result = detachVertex(v);
169 if (!result) {
170 assert(0 && "inconsistency in detaching vertex, ");
171 }
172 }
173 VertexIDMap::iterator it = _vertices.find(v->id());
174 if (it == _vertices.end()) return false;
175 assert(it->second == v);
176 // remove all edges which are entering or leaving v;
177 EdgeSet tmp(v->edges());
178 for (EdgeSet::iterator it = tmp.begin(); it != tmp.end(); ++it) {
179 if (!removeEdge(*it)) {
180 assert(0 && "error in erasing vertex");
181 }
182 }
183 _vertices.erase(it);
184 release(v);
185 return true;
186}
virtual bool removeEdge(Edge *e)
virtual bool detachVertex(Vertex *v)

References _vertices, detachVertex(), g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Vertex::id(), g2o::release(), and removeEdge().

Referenced by mergeVertices(), and g2o::SparseOptimizer::removeVertex().

◆ setEdgeVertex()

bool g2o::HyperGraph::setEdgeVertex ( HyperGraph::Edge e,
int  pos,
HyperGraph::Vertex v 
)
virtual

Sets the vertex in 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 123 of file hyper_graph.cpp.

124 {
125 Vertex* vOld = e->vertex(pos);
126 if (vOld) vOld->edges().erase(e);
127 e->setVertex(pos, v);
128 if (v) v->edges().insert(e);
129 return true;
130}

References g2o::HyperGraph::Vertex::edges(), g2o::HyperGraph::Edge::setVertex(), and g2o::HyperGraph::Edge::vertex().

Referenced by detachVertex(), mergeVertices(), and g2o::OptimizableGraph::setEdgeVertex().

◆ vertex() [1/2]

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 63 of file hyper_graph.cpp.

63 {
64 VertexIDMap::iterator it = _vertices.find(id);
65 if (it == _vertices.end()) return nullptr;
66 return it->second;
67}

References _vertices.

Referenced by changeId().

◆ vertex() [2/2]

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 69 of file hyper_graph.cpp.

69 {
70 VertexIDMap::const_iterator it = _vertices.find(id);
71 if (it == _vertices.end()) return nullptr;
72 return it->second;
73}

References _vertices.

◆ vertices() [1/2]

VertexIDMap & g2o::HyperGraph::vertices ( )
inline
Returns
the map id -> vertex where the vertices are stored

Definition at line 250 of file hyper_graph.h.

250{ return _vertices; }

◆ vertices() [2/2]

const VertexIDMap & g2o::HyperGraph::vertices ( ) const
inline

Member Data Documentation

◆ _edges

EdgeSet g2o::HyperGraph::_edges
protected

Definition at line 298 of file hyper_graph.h.

Referenced by addEdge(), clear(), and removeEdge().

◆ _vertices

VertexIDMap g2o::HyperGraph::_vertices
protected

◆ Data

Definition at line 72 of file hyper_graph.h.

◆ DataContainer

Definition at line 73 of file hyper_graph.h.

◆ Edge

Definition at line 75 of file hyper_graph.h.

◆ InvalidId

const int g2o::HyperGraph::InvalidId = -2
static

Definition at line 68 of file hyper_graph.h.

◆ UnassignedId

const int g2o::HyperGraph::UnassignedId = -1
static

Definition at line 67 of file hyper_graph.h.

Referenced by g2o::OptimizableGraph::saveEdge().

◆ Vertex

Definition at line 74 of file hyper_graph.h.


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