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

#include <optimizable_graph.h>

Inheritance diagram for g2o::OptimizableGraph:
Inheritance graph
[legend]
Collaboration diagram for g2o::OptimizableGraph:
Collaboration graph
[legend]

Classes

class  Edge
 
struct  EdgeIDCompare
 order edges based on the internal ID, which is assigned to the edge in addEdge() More...
 
class  Vertex
 A general case Vertex for optimization. More...
 
struct  VertexIDCompare
 order vertices based on their ID More...
 

Public Types

enum  ActionType { AT_PREITERATION , AT_POSTITERATION , AT_NUM_ELEMENTS }
 
typedef std::set< HyperGraphAction * > HyperGraphActionSet
 
typedef std::vector< OptimizableGraph::Vertex * > VertexContainer
 vector container for vertices
 
typedef std::vector< OptimizableGraph::Edge * > EdgeContainer
 vector container for edges
 
- Public Types inherited from g2o::HyperGraph
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

Vertexvertex (int id)
 returns the vertex number id appropriately casted
 
const Vertexvertex (int id) const
 returns the vertex number id appropriately casted
 
 OptimizableGraph ()
 empty constructor
 
virtual ~OptimizableGraph ()
 
virtual bool addVertex (HyperGraph::Vertex *v, Data *userData)
 
virtual bool addVertex (HyperGraph::Vertex *v)
 
bool addVertex (OptimizableGraph::Vertex *v, Data *userData)
 
bool addVertex (OptimizableGraph::Vertex *v)
 
virtual bool addEdge (HyperGraph::Edge *e)
 
bool addEdge (OptimizableGraph::Edge *e)
 
virtual bool setEdgeVertex (HyperGraph::Edge *e, int pos, HyperGraph::Vertex *v)
 
double chi2 () const
 returns the chi2 of the current configuration
 
int maxDimension () const
 return the maximum dimension of all vertices in the graph
 
void recomputeJacobianWorkspaceSize ()
 
std::set< int > dimensions () const
 
virtual int optimize (int iterations, bool online=false)
 
virtual void preIteration (int)
 
virtual void postIteration (int)
 
bool addPreIterationAction (HyperGraphAction *action)
 add an action to be executed before each iteration
 
bool addPostIterationAction (HyperGraphAction *action)
 add an action to be executed after each iteration
 
bool removePreIterationAction (HyperGraphAction *action)
 remove an action that should no longer be executed before each iteration
 
bool removePostIterationAction (HyperGraphAction *action)
 remove an action that should no longer be executed after each iteration
 
virtual void push ()
 push the estimate of all variables onto a stack
 
virtual void pop ()
 pop (restore) the estimate of all variables from the stack
 
virtual void discardTop ()
 
virtual bool load (std::istream &is)
 
bool load (const char *filename)
 
virtual bool save (std::ostream &os, int level=0) const
 save the graph to a stream. Again uses the Factory system.
 
bool save (const char *filename, int level=0) const
 function provided for convenience, see save() above
 
bool saveSubset (std::ostream &os, HyperGraph::VertexSet &vset, int level=0)
 save a subgraph to a stream. Again uses the Factory system.
 
bool saveSubset (std::ostream &os, HyperGraph::EdgeSet &eset)
 save a subgraph to a stream. Again uses the Factory system.
 
virtual void push (HyperGraph::VertexSet &vset)
 push the estimate of a subset of the variables onto a stack
 
virtual void pop (HyperGraph::VertexSet &vset)
 pop (restore) the estimate a subset of the variables from the stack
 
virtual void discardTop (HyperGraph::VertexSet &vset)
 
virtual void setFixed (HyperGraph::VertexSet &vset, bool fixed)
 fixes/releases a set of vertices
 
void setRenamedTypesFromString (const std::string &types)
 
bool isSolverSuitable (const OptimizationAlgorithmProperty &solverProperty, const std::set< int > &vertDims=std::set< int >()) const
 
virtual void clearParameters ()
 
bool addParameter (Parameter *p)
 
Parameterparameter (int id)
 
bool verifyInformationMatrices (bool verbose=false) const
 
bool saveVertex (std::ostream &os, Vertex *v) const
 
bool saveParameter (std::ostream &os, Parameter *v) const
 
bool saveEdge (std::ostream &os, Edge *e) const
 
bool saveUserData (std::ostream &os, HyperGraph::Data *v) const
 
JacobianWorkspacejacobianWorkspace ()
 the workspace for storing the Jacobians of the graph
 
const JacobianWorkspacejacobianWorkspace () const
 
ParameterContainerparameters ()
 
const ParameterContainerparameters () const
 
void forEachVertex (std::function< void(OptimizableGraph::Vertex *)> fn)
 apply a unary function to all vertices
 
void forEachVertex (HyperGraph::VertexSet &vset, std::function< void(OptimizableGraph::Vertex *)> fn)
 apply a unary function to the vertices in vset
 
- Public Member Functions inherited from g2o::HyperGraph
 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 mergeVertices (Vertex *vBig, Vertex *vSmall, bool erase)
 
virtual bool detachVertex (Vertex *v)
 
virtual bool changeId (Vertex *v, int newId)
 

Static Public Member Functions

static bool initMultiThreading ()
 

Public Attributes

class G2O_CORE_API Vertex
 
class G2O_CORE_API Edge
 
- Public Attributes inherited from g2o::HyperGraph
class G2O_CORE_API Data
 
class G2O_CORE_API DataContainer
 
class G2O_CORE_API Vertex
 
class G2O_CORE_API Edge
 

Protected Member Functions

void performActions (int iter, HyperGraphActionSet &actions)
 

Protected Attributes

std::map< std::string, std::string > _renamedTypesLookup
 
long long _nextEdgeId
 
std::vector< HyperGraphActionSet_graphActions
 
ParameterContainer _parameters
 
JacobianWorkspace _jacobianWorkspace
 
- Protected Attributes inherited from g2o::HyperGraph
VertexIDMap _vertices
 
EdgeSet _edges
 

Additional Inherited Members

- Static Public Attributes inherited from g2o::HyperGraph
static const int UnassignedId = -1
 
static const int InvalidId = -2
 

Detailed Description

This is an abstract class that represents one optimization problem. It specializes the general graph to contain special vertices and edges. The vertices represent parameters that can be optimized, while the edges represent constraints. This class also provides basic functionalities to handle the backup/restore of portions of the vertices.

Definition at line 62 of file optimizable_graph.h.

Member Typedef Documentation

◆ EdgeContainer

vector container for edges

Definition at line 102 of file optimizable_graph.h.

◆ HyperGraphActionSet

Definition at line 69 of file optimizable_graph.h.

◆ VertexContainer

vector container for vertices

Definition at line 100 of file optimizable_graph.h.

Member Enumeration Documentation

◆ ActionType

Enumerator
AT_PREITERATION 
AT_POSTITERATION 
AT_NUM_ELEMENTS 

Definition at line 63 of file optimizable_graph.h.

Constructor & Destructor Documentation

◆ OptimizableGraph()

g2o::OptimizableGraph::OptimizableGraph ( )

empty constructor

Definition at line 173 of file optimizable_graph.cpp.

173 {
174 _nextEdgeId = 0;
176}
std::vector< HyperGraphActionSet > _graphActions

References _graphActions, _nextEdgeId, and AT_NUM_ELEMENTS.

◆ ~OptimizableGraph()

g2o::OptimizableGraph::~OptimizableGraph ( )
virtual

Definition at line 178 of file optimizable_graph.cpp.

178 {
179 clear();
181}
virtual void clear()
clears the graph and empties all structures.

References g2o::HyperGraph::clear(), and clearParameters().

Member Function Documentation

◆ addEdge() [1/2]

bool g2o::OptimizableGraph::addEdge ( HyperGraph::Edge e)
virtual

adds a new edge. The edge should point to the vertices that it is connecting (setFrom/setTo).

Returns
false if the insertion does not work (incompatible types of the vertices/missing vertex). true otherwise.

Reimplemented from g2o::HyperGraph.

Definition at line 252 of file optimizable_graph.cpp.

252 {
253 OptimizableGraph::Edge* e = dynamic_cast<OptimizableGraph::Edge*>(e_);
254 assert(e && "Edge does not inherit from OptimizableGraph::Edge");
255 if (!e) return false;
256 return addEdge(e);
257}
virtual bool addEdge(HyperGraph::Edge *e)

References addEdge().

Referenced by g2o::G2oSlamInterface::addEdge(), addEdge(), g2o::addOdometryCalibLinksDifferential(), g2o::assignHierarchicalEdges(), g2o::computeSimpleStars(), main(), main(), main(), Robot::move(), g2o::Gm2dlIO::readGm2dl(), g2o::SensorOdometry< R, E, O >::sense(), g2o::SensorOdometry2D::sense(), g2o::SensorOdometry3D::sense(), g2o::SensorPointXY::sense(), g2o::SensorPointXYBearing::sense(), g2o::SensorPointXYOffset::sense(), g2o::SensorPointXYZ::sense(), g2o::SensorPointXYZDepth::sense(), g2o::SensorPointXYZDisparity::sense(), g2o::SensorPose2D::sense(), g2o::SensorPose3D::sense(), g2o::SensorPose3DOffset::sense(), g2o::SensorSE3Prior::sense(), g2o::SensorSegment2D::sense(), g2o::SensorSegment2DLine::sense(), g2o::SensorSegment2DPointLine::sense(), g2o::UnarySensor< RobotType_, EdgeType_ >::sense(), g2o::BinarySensor< RobotType_, EdgeType_, WorldObjectType_ >::sense(), LineSensor::sense(), and PlaneSensor::sense().

◆ addEdge() [2/2]

bool g2o::OptimizableGraph::addEdge ( OptimizableGraph::Edge e)

Definition at line 220 of file optimizable_graph.cpp.

220 {
221 OptimizableGraph* g = e->graph();
222
223 if (g != nullptr && g != this) {
224 G2O_ERROR(
225 "{}: FATAL, edge with ID {} has already registered with another graph "
226 "{}",
227 __PRETTY_FUNCTION__, e->id(), static_cast<void*>(g));
228 return false;
229 }
230
231 bool eresult = HyperGraph::addEdge(e);
232 if (!eresult) return false;
233
234 e->_internalId = _nextEdgeId++;
235 if (e->numUndefinedVertices()) return true;
236 if (!e->resolveParameters()) {
237 G2O_ERROR("{}: FATAL, cannot resolve parameters for edge {}",
238 static_cast<void*>(e));
239 return false;
240 }
241 if (!e->resolveCaches()) {
242 G2O_ERROR("{}: FATAL, cannot resolve caches for edge {}",
243 static_cast<void*>(e));
244 return false;
245 }
246
248
249 return true;
250}
virtual bool addEdge(Edge *e)
void updateSize(const HyperGraph::Edge *e, bool reset)
#define G2O_ERROR(...)
Definition logger.h:89
#define __PRETTY_FUNCTION__
Definition macros.h:90
JacobianWorkspace _jacobianWorkspace
OptimizableGraph()
empty constructor

References __PRETTY_FUNCTION__, g2o::OptimizableGraph::Edge::_internalId, _jacobianWorkspace, _nextEdgeId, g2o::HyperGraph::addEdge(), G2O_ERROR, g2o::OptimizableGraph::Edge::graph(), g2o::HyperGraph::Edge::id(), g2o::HyperGraph::Edge::numUndefinedVertices(), g2o::OptimizableGraph::Edge::resolveCaches(), g2o::OptimizableGraph::Edge::resolveParameters(), and g2o::JacobianWorkspace::updateSize().

◆ addParameter()

bool g2o::OptimizableGraph::addParameter ( Parameter p)
inline

Definition at line 715 of file optimizable_graph.h.

715{ return _parameters.addParameter(p); }
bool addParameter(Parameter *p)
add parameter to the container
ParameterContainer _parameters

Referenced by g2o::World::addParameter(), main(), main(), and main().

◆ addPostIterationAction()

bool g2o::OptimizableGraph::addPostIterationAction ( HyperGraphAction action)

add an action to be executed after each iteration

Definition at line 711 of file optimizable_graph.cpp.

711 {
712 std::pair<HyperGraphActionSet::iterator, bool> insertResult =
713 _graphActions[AT_POSTITERATION].insert(action);
714 return insertResult.second;
715}

References _graphActions, and AT_POSTITERATION.

Referenced by main().

◆ addPreIterationAction()

bool g2o::OptimizableGraph::addPreIterationAction ( HyperGraphAction action)

add an action to be executed before each iteration

Definition at line 717 of file optimizable_graph.cpp.

717 {
718 std::pair<HyperGraphActionSet::iterator, bool> insertResult =
719 _graphActions[AT_PREITERATION].insert(action);
720 return insertResult.second;
721}

References _graphActions, and AT_PREITERATION.

Referenced by g2o::RunG2OViewer::run().

◆ addVertex() [1/4]

virtual bool g2o::OptimizableGraph::addVertex ( HyperGraph::Vertex v)
inlinevirtual

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 from g2o::HyperGraph.

Definition at line 595 of file optimizable_graph.h.

595{ return addVertex(v, 0); }
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)

References addVertex().

Referenced by addVertex().

◆ addVertex() [2/4]

bool g2o::OptimizableGraph::addVertex ( HyperGraph::Vertex v,
Data userData 
)
virtual

adds a new vertex. The new vertex is then "taken".

Returns
false if a vertex with the same id as v is already in the graph, true otherwise.

Definition at line 212 of file optimizable_graph.cpp.

212 {
213 OptimizableGraph::Vertex* ov = dynamic_cast<OptimizableGraph::Vertex*>(v);
214 assert(ov && "Vertex does not inherit from OptimizableGraph::Vertex");
215 if (!ov) return false;
216
217 return addVertex(ov, userData);
218}

References addVertex().

Referenced by g2o::addOdometryCalibLinksDifferential(), addVertex(), g2o::G2oSlamInterface::addVertex(), g2o::World::addWorldObject(), LineItem::LineItem(), LineSensor::LineSensor(), main(), main(), main(), Robot::move(), PlaneItem::PlaneItem(), PlaneSensor::PlaneSensor(), and g2o::Gm2dlIO::readGm2dl().

◆ addVertex() [3/4]

bool g2o::OptimizableGraph::addVertex ( OptimizableGraph::Vertex v)
inline

Definition at line 597 of file optimizable_graph.h.

597{ return addVertex(v, 0); }

References addVertex().

Referenced by addVertex().

◆ addVertex() [4/4]

bool g2o::OptimizableGraph::addVertex ( OptimizableGraph::Vertex v,
Data userData 
)

Definition at line 183 of file optimizable_graph.cpp.

183 {
184 if (ov->id() < 0) {
185 G2O_ERROR(
186 "{}: FATAL, a vertex with (negative) ID {} cannot be inserted into the "
187 "graph",
188 __PRETTY_FUNCTION__, ov->id());
189 assert(0 && "Invalid vertex id");
190 return false;
191 }
192 Vertex* inserted = vertex(ov->id());
193 if (inserted) {
194 G2O_WARN(
195 "{}: a vertex with ID {} has already been registered with this "
196 "graph",
197 __PRETTY_FUNCTION__, ov->id());
198 return false;
199 }
200 if (ov->_graph != nullptr && ov->_graph != this) {
201 G2O_ERROR(
202 "{}: FATAL, vertex with ID {} has already been registered with another "
203 "graph {}",
204 __PRETTY_FUNCTION__, ov->id(), static_cast<void*>(ov->_graph));
205 return false;
206 }
207 if (userData) ov->setUserData(userData);
208 ov->_graph = this;
209 return HyperGraph::addVertex(ov);
210}
virtual bool addVertex(Vertex *v)
#define G2O_WARN(...)
Definition logger.h:88
class G2O_CORE_API Vertex
Vertex * vertex(int id)
returns the vertex number id appropriately casted

References __PRETTY_FUNCTION__, g2o::OptimizableGraph::Vertex::_graph, g2o::HyperGraph::addVertex(), G2O_ERROR, G2O_WARN, g2o::HyperGraph::Vertex::id(), g2o::HyperGraph::DataContainer::setUserData(), and vertex().

◆ chi2()

double g2o::OptimizableGraph::chi2 ( ) const

returns the chi2 of the current configuration

Definition at line 290 of file optimizable_graph.cpp.

290 {
291 double chi = 0.0;
292 for (OptimizableGraph::EdgeSet::const_iterator it = this->edges().begin();
293 it != this->edges().end(); ++it) {
294 const OptimizableGraph::Edge* e =
295 static_cast<const OptimizableGraph::Edge*>(*it);
296 chi += e->chi2();
297 }
298 return chi;
299}
const EdgeSet & edges() const

References g2o::OptimizableGraph::Edge::chi2(), and g2o::HyperGraph::edges().

Referenced by main(), and main().

◆ clearParameters()

void g2o::OptimizableGraph::clearParameters ( )
virtual

remove the parameters of the graph

Definition at line 793 of file optimizable_graph.cpp.

References _parameters, g2o::HyperGraph::clear(), and g2o::ParameterContainer::clear().

Referenced by ~OptimizableGraph().

◆ dimensions()

std::set< int > g2o::OptimizableGraph::dimensions ( ) const

iterates over all vertices and returns a set of all the vertex dimensions in the graph

Definition at line 682 of file optimizable_graph.cpp.

682 {
683 std::set<int> auxDims;
684 for (VertexIDMap::const_iterator it = vertices().begin();
685 it != vertices().end(); ++it) {
686 OptimizableGraph::Vertex* v =
687 static_cast<OptimizableGraph::Vertex*>(it->second);
688 auxDims.insert(v->dimension());
689 }
690 return auxDims;
691}
const VertexIDMap & vertices() const

References g2o::HyperGraph::vertices().

Referenced by isSolverSuitable(), MainWindow::load(), and main().

◆ discardTop() [1/2]

void g2o::OptimizableGraph::discardTop ( )
virtual

discard the last backup of the estimate for all variables by removing it from the stack

Reimplemented in g2o::SparseOptimizer, and g2o::SparseOptimizer.

Definition at line 309 of file optimizable_graph.cpp.

309 {
310 forEachVertex([](OptimizableGraph::Vertex* v) { v->discardTop(); });
311}
void forEachVertex(std::function< void(OptimizableGraph::Vertex *)> fn)
apply a unary function to all vertices

References g2o::OptimizableGraph::Vertex::discardTop(), and forEachVertex().

◆ discardTop() [2/2]

void g2o::OptimizableGraph::discardTop ( HyperGraph::VertexSet vset)
virtual

ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate

Reimplemented in g2o::SparseOptimizer.

Definition at line 321 of file optimizable_graph.cpp.

321 {
322 forEachVertex(vset, [](OptimizableGraph::Vertex* v) { v->discardTop(); });
323}

References g2o::OptimizableGraph::Vertex::discardTop(), and forEachVertex().

◆ forEachVertex() [1/2]

void g2o::OptimizableGraph::forEachVertex ( HyperGraph::VertexSet vset,
std::function< void(OptimizableGraph::Vertex *)>  fn 
)

apply a unary function to the vertices in vset

Definition at line 339 of file optimizable_graph.cpp.

341 {
342 for (auto it = vset.begin(); it != vset.end(); ++it) {
343 OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(*it);
344 fn(v);
345 }
346}

◆ forEachVertex() [2/2]

void g2o::OptimizableGraph::forEachVertex ( std::function< void(OptimizableGraph::Vertex *)>  fn)

apply a unary function to all vertices

Definition at line 330 of file optimizable_graph.cpp.

331 {
332 for (auto it = _vertices.begin(); it != _vertices.end(); ++it) {
333 OptimizableGraph::Vertex* v =
334 static_cast<OptimizableGraph::Vertex*>(it->second);
335 fn(v);
336 }
337}
VertexIDMap _vertices

References g2o::HyperGraph::_vertices.

Referenced by discardTop(), discardTop(), pop(), pop(), push(), push(), and setFixed().

◆ initMultiThreading()

bool g2o::OptimizableGraph::initMultiThreading ( )
static

Eigen starting from version 3.1 requires that we call an initialize function, if we perform calls to Eigen from several threads. Currently, this function calls Eigen::initParallel if g2o is compiled with OpenMP support and Eigen's version is at least 3.1

Definition at line 835 of file optimizable_graph.cpp.

835 {
836#if (defined G2O_OPENMP) && EIGEN_VERSION_AT_LEAST(3, 1, 0)
837 Eigen::initParallel();
838#endif
839 return true;
840}

Referenced by main().

◆ isSolverSuitable()

bool g2o::OptimizableGraph::isSolverSuitable ( const OptimizationAlgorithmProperty solverProperty,
const std::set< int > &  vertDims = std::set<int>() 
) const

test whether a solver is suitable for optimizing this graph.

Parameters
solverPropertythe solver property to evaluate.
vertDimsshould equal to the set returned by dimensions() to avoid re-evaluating.

Definition at line 656 of file optimizable_graph.cpp.

658 {
659 std::set<int> auxDims;
660 if (vertDims_.size() == 0) {
661 auxDims = dimensions();
662 }
663 const set<int>& vertDims = vertDims_.size() == 0 ? auxDims : vertDims_;
664 bool suitableSolver = true;
665 if (vertDims.size() == 2) {
666 if (solverProperty.requiresMarginalize) {
667 suitableSolver = vertDims.count(solverProperty.poseDim) == 1 &&
668 vertDims.count(solverProperty.landmarkDim) == 1;
669 } else {
670 suitableSolver = solverProperty.poseDim == -1;
671 }
672 } else if (vertDims.size() == 1) {
673 suitableSolver = vertDims.count(solverProperty.poseDim) == 1 ||
674 solverProperty.poseDim == -1;
675 } else {
676 suitableSolver =
677 solverProperty.poseDim == -1 && !solverProperty.requiresMarginalize;
678 }
679 return suitableSolver;
680}
std::set< int > dimensions() const

References dimensions().

Referenced by MainWindow::load(), and main().

◆ jacobianWorkspace() [1/2]

JacobianWorkspace & g2o::OptimizableGraph::jacobianWorkspace ( )
inline

the workspace for storing the Jacobians of the graph

Definition at line 740 of file optimizable_graph.h.

740{ return _jacobianWorkspace; }

Referenced by g2o::G2oSlamInterface::addEdge(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizerIncremental::updateInitialization().

◆ jacobianWorkspace() [2/2]

const JacobianWorkspace & g2o::OptimizableGraph::jacobianWorkspace ( ) const
inline

Definition at line 741 of file optimizable_graph.h.

741 {
742 return _jacobianWorkspace;
743 }

◆ load() [1/2]

bool g2o::OptimizableGraph::load ( const char *  filename)

Definition at line 533 of file optimizable_graph.cpp.

533 {
534 ifstream ifs(filename);
535 if (!ifs) {
536 G2O_ERROR("Unable to open file {}", filename);
537 return false;
538 }
539 return load(ifs);
540}
virtual bool load(std::istream &is)

References G2O_ERROR, and load().

◆ load() [2/2]

virtual bool g2o::OptimizableGraph::load ( std::istream &  is)
virtual

load the graph from a stream. Uses the Factory singleton for creating the vertices and edges.

Referenced by load(), and main().

◆ maxDimension()

int g2o::OptimizableGraph::maxDimension ( ) const

return the maximum dimension of all vertices in the graph

Definition at line 617 of file optimizable_graph.cpp.

617 {
618 int maxDim = 0;
619 for (HyperGraph::VertexIDMap::const_iterator it = vertices().begin();
620 it != vertices().end(); ++it) {
621 const OptimizableGraph::Vertex* v =
622 static_cast<const OptimizableGraph::Vertex*>(it->second);
623 maxDim = (std::max)(maxDim, v->dimension());
624 }
625 return maxDim;
626}

References g2o::OptimizableGraph::Vertex::dimension(), and g2o::HyperGraph::vertices().

Referenced by g2o::SparseOptimizer::findGauge(), and g2o::SparseOptimizer::gaugeFreedom().

◆ optimize()

int g2o::OptimizableGraph::optimize ( int  iterations,
bool  online = false 
)
virtual

carry out n iterations

Returns
the number of performed iterations

Reimplemented in g2o::SparseOptimizer, g2o::SparseOptimizerIncremental, and g2o::SparseOptimizerOnline.

Definition at line 286 of file optimizable_graph.cpp.

286 {
287 return 0;
288}

◆ parameter()

Parameter * g2o::OptimizableGraph::parameter ( int  id)
inline

Definition at line 717 of file optimizable_graph.h.

717{ return _parameters.getParameter(id); }
Parameter * getParameter(int id)
return a parameter based on its ID

Referenced by main().

◆ parameters() [1/2]

ParameterContainer & g2o::OptimizableGraph::parameters ( )
inline

Definition at line 753 of file optimizable_graph.h.

753{ return _parameters; }

◆ parameters() [2/2]

const ParameterContainer & g2o::OptimizableGraph::parameters ( ) const
inline

Definition at line 754 of file optimizable_graph.h.

754{ return _parameters; }

◆ performActions()

void g2o::OptimizableGraph::performActions ( int  iter,
HyperGraphActionSet actions 
)
protected

Definition at line 693 of file optimizable_graph.cpp.

693 {
694 if (actions.size() > 0) {
695 HyperGraphAction::ParametersIteration params(iter);
696 for (HyperGraphActionSet::iterator it = actions.begin();
697 it != actions.end(); ++it) {
698 (*(*it))(this, &params);
699 }
700 }
701}

Referenced by postIteration(), and preIteration().

◆ pop() [1/2]

void g2o::OptimizableGraph::pop ( )
virtual

pop (restore) the estimate of all variables from the stack

Reimplemented in g2o::SparseOptimizer.

Definition at line 305 of file optimizable_graph.cpp.

305 {
306 forEachVertex([](OptimizableGraph::Vertex* v) { v->pop(); });
307}

References forEachVertex(), and g2o::OptimizableGraph::Vertex::pop().

Referenced by g2o::SparseOptimizer::pop().

◆ pop() [2/2]

void g2o::OptimizableGraph::pop ( HyperGraph::VertexSet vset)
virtual

pop (restore) the estimate a subset of the variables from the stack

Reimplemented in g2o::SparseOptimizer.

Definition at line 317 of file optimizable_graph.cpp.

317 {
318 forEachVertex(vset, [](OptimizableGraph::Vertex* v) { v->pop(); });
319}

References forEachVertex(), and g2o::OptimizableGraph::Vertex::pop().

◆ postIteration()

void g2o::OptimizableGraph::postIteration ( int  iter)
virtual

called at the end of an iteration (argument is the number of the iteration)

Definition at line 707 of file optimizable_graph.cpp.

707 {
709}
void performActions(int iter, HyperGraphActionSet &actions)

References _graphActions, AT_POSTITERATION, and performActions().

Referenced by g2o::SparseOptimizer::initializeOptimization(), g2o::SparseOptimizer::initializeOptimization(), and g2o::SparseOptimizer::optimize().

◆ preIteration()

void g2o::OptimizableGraph::preIteration ( int  iter)
virtual

called at the beginning of an iteration (argument is the number of the iteration)

Definition at line 703 of file optimizable_graph.cpp.

703 {
705}

References _graphActions, AT_PREITERATION, and performActions().

Referenced by g2o::SparseOptimizer::initializeOptimization(), g2o::SparseOptimizer::initializeOptimization(), and g2o::SparseOptimizer::optimize().

◆ push() [1/2]

void g2o::OptimizableGraph::push ( )
virtual

push the estimate of all variables onto a stack

Reimplemented in g2o::SparseOptimizer.

Definition at line 301 of file optimizable_graph.cpp.

301 {
302 forEachVertex([](OptimizableGraph::Vertex* v) { v->push(); });
303}

References forEachVertex(), and g2o::OptimizableGraph::Vertex::push().

Referenced by g2o::SparseOptimizer::push().

◆ push() [2/2]

void g2o::OptimizableGraph::push ( HyperGraph::VertexSet vset)
virtual

push the estimate of a subset of the variables onto a stack

Reimplemented in g2o::SparseOptimizer.

Definition at line 313 of file optimizable_graph.cpp.

313 {
314 forEachVertex(vset, [](OptimizableGraph::Vertex* v) { v->push(); });
315}

References forEachVertex(), and g2o::OptimizableGraph::Vertex::push().

◆ recomputeJacobianWorkspaceSize()

void g2o::OptimizableGraph::recomputeJacobianWorkspaceSize ( )
inline

Recompute the size of the Jacobian workspace from all the edges in the graph.

Definition at line 626 of file optimizable_graph.h.

626 {
627 _jacobianWorkspace.updateSize(*this, true);
628 }

◆ removePostIterationAction()

bool g2o::OptimizableGraph::removePostIterationAction ( HyperGraphAction action)

remove an action that should no longer be executed after each iteration

Definition at line 727 of file optimizable_graph.cpp.

727 {
728 return _graphActions[AT_POSTITERATION].erase(action) > 0;
729}

References _graphActions, and AT_POSTITERATION.

◆ removePreIterationAction()

bool g2o::OptimizableGraph::removePreIterationAction ( HyperGraphAction action)

remove an action that should no longer be executed before each iteration

Definition at line 723 of file optimizable_graph.cpp.

723 {
724 return _graphActions[AT_PREITERATION].erase(action) > 0;
725}

References _graphActions, and AT_PREITERATION.

◆ save() [1/2]

bool g2o::OptimizableGraph::save ( const char *  filename,
int  level = 0 
) const

function provided for convenience, see save() above

Definition at line 542 of file optimizable_graph.cpp.

542 {
543 ofstream ofs(filename);
544 if (!ofs) return false;
545 return save(ofs, level);
546}
virtual bool save(std::ostream &os, int level=0) const
save the graph to a stream. Again uses the Factory system.

References save().

◆ save() [2/2]

virtual bool g2o::OptimizableGraph::save ( std::ostream &  os,
int  level = 0 
) const
virtual

save the graph to a stream. Again uses the Factory system.

Referenced by main(), main(), and save().

◆ saveEdge()

bool g2o::OptimizableGraph::saveEdge ( std::ostream &  os,
OptimizableGraph::Edge e 
) const

Definition at line 774 of file optimizable_graph.cpp.

775 {
776 Factory* factory = Factory::instance();
777 string tag = factory->tag(e);
778 if (tag.size() > 0) {
779 os << tag << " ";
780 for (vector<HyperGraph::Vertex*>::const_iterator it = e->vertices().begin();
781 it != e->vertices().end(); ++it) {
782 int vertexId = (*it) ? (*it)->id() : HyperGraph::UnassignedId;
783 os << vertexId << " ";
784 }
785 e->write(os);
786 os << endl;
787 saveUserData(os, e->userData());
788 return os.good();
789 }
790 return false;
791}
static Factory * instance()
return the instance
Definition factory.cpp:46
static const int UnassignedId
Definition hyper_graph.h:67
bool saveUserData(std::ostream &os, HyperGraph::Data *v) const

References g2o::Factory::instance(), saveUserData(), g2o::Factory::tag(), g2o::HyperGraph::UnassignedId, g2o::HyperGraph::DataContainer::userData(), g2o::HyperGraph::Edge::vertices(), and g2o::OptimizableGraph::Edge::write().

◆ saveParameter()

bool g2o::OptimizableGraph::saveParameter ( std::ostream &  os,
Parameter v 
) const

Definition at line 763 of file optimizable_graph.cpp.

763 {
764 Factory* factory = Factory::instance();
765 string tag = factory->tag(p);
766 if (tag.size() > 0) {
767 os << tag << " " << p->id() << " ";
768 p->write(os);
769 os << endl;
770 }
771 return os.good();
772}

References g2o::Parameter::id(), g2o::Factory::instance(), g2o::Factory::tag(), and g2o::Parameter::write().

◆ saveSubset() [1/2]

bool g2o::OptimizableGraph::saveSubset ( std::ostream &  os,
HyperGraph::EdgeSet eset 
)

save a subgraph to a stream. Again uses the Factory system.

◆ saveSubset() [2/2]

bool g2o::OptimizableGraph::saveSubset ( std::ostream &  os,
HyperGraph::VertexSet vset,
int  level = 0 
)

save a subgraph to a stream. Again uses the Factory system.

Referenced by g2o::computeSimpleStars(), and main().

◆ saveUserData()

bool g2o::OptimizableGraph::saveUserData ( std::ostream &  os,
HyperGraph::Data v 
) const

Definition at line 731 of file optimizable_graph.cpp.

732 {
733 Factory* factory = Factory::instance();
734 while (d) { // write the data packet for the vertex
735 string tag = factory->tag(d);
736 if (tag.size() > 0) {
737 os << tag << " ";
738 d->write(os);
739 os << endl;
740 }
741 d = d->next();
742 }
743 return os.good();
744}

References g2o::Factory::instance(), g2o::HyperGraph::Data::next(), g2o::Factory::tag(), and g2o::HyperGraph::Data::write().

Referenced by saveEdge(), and saveVertex().

◆ saveVertex()

bool g2o::OptimizableGraph::saveVertex ( std::ostream &  os,
OptimizableGraph::Vertex v 
) const

Definition at line 746 of file optimizable_graph.cpp.

747 {
748 Factory* factory = Factory::instance();
749 string tag = factory->tag(v);
750 if (tag.size() > 0) {
751 os << tag << " " << v->id() << " ";
752 v->write(os);
753 os << endl;
754 saveUserData(os, v->userData());
755 if (v->fixed()) {
756 os << "FIX " << v->id() << endl;
757 }
758 return os.good();
759 }
760 return false;
761}

References g2o::OptimizableGraph::Vertex::fixed(), g2o::HyperGraph::Vertex::id(), g2o::Factory::instance(), saveUserData(), g2o::Factory::tag(), g2o::HyperGraph::DataContainer::userData(), and g2o::OptimizableGraph::Vertex::write().

◆ setEdgeVertex()

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

overridden from HyperGraph, to maintain the bookkeeping of the caches/parameters and jacobian workspaces consistent upon a change in the vertex.

Returns
false if something goes wrong.

Reimplemented from g2o::HyperGraph.

Definition at line 259 of file optimizable_graph.cpp.

260 {
261 if (!HyperGraph::setEdgeVertex(e, pos, v)) {
262 return false;
263 }
264 if (!e->numUndefinedVertices()) {
265#ifndef NDEBUG
266 OptimizableGraph::Edge* ee = dynamic_cast<OptimizableGraph::Edge*>(e);
267 assert(ee && "Edge is not a OptimizableGraph::Edge");
268#else
269 OptimizableGraph::Edge* ee = static_cast<OptimizableGraph::Edge*>(e);
270#endif
271 if (!ee->resolveParameters()) {
272 G2O_ERROR("{}: FATAL, cannot resolve parameters for edge {}",
273 static_cast<void*>(e));
274 return false;
275 }
276 if (!ee->resolveCaches()) {
277 G2O_ERROR("{}: FATAL, cannot resolve caches for edge {}",
278 static_cast<void*>(e));
279 return false;
280 }
282 }
283 return true;
284}
virtual bool setEdgeVertex(Edge *e, int pos, Vertex *v)

References _jacobianWorkspace, G2O_ERROR, g2o::HyperGraph::Edge::numUndefinedVertices(), g2o::OptimizableGraph::Edge::resolveCaches(), g2o::OptimizableGraph::Edge::resolveParameters(), g2o::HyperGraph::setEdgeVertex(), and g2o::JacobianWorkspace::updateSize().

Referenced by anonymizeLandmarkEdge(), and anonymizePoseEdge().

◆ setFixed()

void g2o::OptimizableGraph::setFixed ( HyperGraph::VertexSet vset,
bool  fixed 
)
virtual

fixes/releases a set of vertices

Definition at line 325 of file optimizable_graph.cpp.

325 {
326 forEachVertex(vset,
327 [fixed](OptimizableGraph::Vertex* v) { v->setFixed(fixed); });
328}

References forEachVertex(), and g2o::OptimizableGraph::Vertex::setFixed().

Referenced by g2o::computeSimpleStars().

◆ setRenamedTypesFromString()

void g2o::OptimizableGraph::setRenamedTypesFromString ( const std::string &  types)

set the renamed types lookup from a string, format is for example: VERTEX_CAM=VERTEX_SE3:EXPMAP,EDGE_PROJECT_P2MC=EDGE_PROJECT_XYZ:EXPMAP This will change the occurrence of VERTEX_CAM in the file to VERTEX_SE3:EXPMAP

Definition at line 628 of file optimizable_graph.cpp.

628 {
629 Factory* factory = Factory::instance();
630 vector<string> typesMap = strSplit(types, ",");
631 for (size_t i = 0; i < typesMap.size(); ++i) {
632 vector<string> m = strSplit(typesMap[i], "=");
633 if (m.size() != 2) {
634 G2O_ERROR("{}: unable to extract type map from {}", __PRETTY_FUNCTION__,
635 typesMap[i]);
636 continue;
637 }
638 string typeInFile = trim(m[0]);
639 string loadedType = trim(m[1]);
640 if (!factory->knowsTag(loadedType)) {
641 G2O_ERROR("{}: unknown type {}", __PRETTY_FUNCTION__, loadedType);
642 continue;
643 }
644
645 _renamedTypesLookup[typeInFile] = loadedType;
646 }
647
648 G2O_DEBUG("Load look up table:");
649 for (std::map<std::string, std::string>::const_iterator it =
650 _renamedTypesLookup.begin();
651 it != _renamedTypesLookup.end(); ++it) {
652 G2O_DEBUG("{} -> {}", it->first, it->second);
653 }
654}
#define G2O_DEBUG(...)
Definition logger.h:90
std::string trim(const std::string &s)
std::vector< std::string > strSplit(const std::string &str, const std::string &delimiters)
std::map< std::string, std::string > _renamedTypesLookup

References __PRETTY_FUNCTION__, _renamedTypesLookup, G2O_DEBUG, G2O_ERROR, g2o::Factory::instance(), g2o::Factory::knowsTag(), g2o::strSplit(), and g2o::trim().

Referenced by main(), and g2o::RunG2OViewer::run().

◆ verifyInformationMatrices()

bool g2o::OptimizableGraph::verifyInformationMatrices ( bool  verbose = false) const

verify that all the information of the edges are semi positive definite, i.e., all Eigenvalues are >= 0.

Parameters
verboseoutput edges with not PSD information matrix by logging
Returns
true if all edges have PSD information matrix

Definition at line 798 of file optimizable_graph.cpp.

798 {
799 bool allEdgeOk = true;
800 Eigen::SelfAdjointEigenSolver<MatrixX> eigenSolver;
801 for (OptimizableGraph::EdgeSet::const_iterator it = edges().begin();
802 it != edges().end(); ++it) {
803 OptimizableGraph::Edge* e = static_cast<OptimizableGraph::Edge*>(*it);
804 MatrixX::MapType information(e->informationData(), e->dimension(),
805 e->dimension());
806 // test on symmetry
807 bool isSymmetric = information.transpose() == information;
808 bool okay = isSymmetric;
809 if (isSymmetric) {
810 // compute the eigenvalues
811 eigenSolver.compute(information, Eigen::EigenvaluesOnly);
812 bool isSPD = eigenSolver.eigenvalues()(0) >= 0.;
813 okay = okay && isSPD;
814 }
815 allEdgeOk = allEdgeOk && okay;
816 if (!okay) {
817 if (verbose) {
818 vector<int> ids(e->vertices().size());
819 for (size_t i = 0; i < e->vertices().size(); ++i)
820 ids[i] = e->vertex(i)->id();
821 if (!isSymmetric)
822 G2O_WARN("Information Matrix for an edge is not symmetric: {}",
823 fmt::join(ids, " "));
824 else
825 G2O_WARN("Information Matrix for an edge is not SPD: {}",
826 fmt::join(ids, " "));
827 if (isSymmetric)
828 G2O_WARN("eigenvalues: {}", eigenSolver.eigenvalues().transpose());
829 }
830 }
831 }
832 return allEdgeOk;
833}

References g2o::OptimizableGraph::Edge::dimension(), g2o::HyperGraph::edges(), G2O_WARN, g2o::HyperGraph::Vertex::id(), g2o::OptimizableGraph::Edge::informationData(), g2o::HyperGraph::Edge::vertex(), and g2o::HyperGraph::Edge::vertices().

◆ vertex() [1/2]

Vertex * g2o::OptimizableGraph::vertex ( int  id)
inline

◆ vertex() [2/2]

const Vertex * g2o::OptimizableGraph::vertex ( int  id) const
inline

returns the vertex number id appropriately casted

Definition at line 581 of file optimizable_graph.h.

581 {
582 return reinterpret_cast<const Vertex*>(HyperGraph::vertex(id));
583 }

Member Data Documentation

◆ _graphActions

std::vector<HyperGraphActionSet> g2o::OptimizableGraph::_graphActions
protected

◆ _jacobianWorkspace

JacobianWorkspace g2o::OptimizableGraph::_jacobianWorkspace
protected

◆ _nextEdgeId

long long g2o::OptimizableGraph::_nextEdgeId
protected

Definition at line 764 of file optimizable_graph.h.

Referenced by addEdge(), and OptimizableGraph().

◆ _parameters

ParameterContainer g2o::OptimizableGraph::_parameters
protected

◆ _renamedTypesLookup

std::map<std::string, std::string> g2o::OptimizableGraph::_renamedTypesLookup
protected

Definition at line 763 of file optimizable_graph.h.

Referenced by setRenamedTypesFromString().

◆ Edge

Definition at line 73 of file optimizable_graph.h.

◆ Vertex

Definition at line 72 of file optimizable_graph.h.


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