g2o
Public Member Functions | Protected Attributes | List of all members
g2o::HyperGraph::Edge Class Reference

#include <hyper_graph.h>

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

Public Member Functions

 Edge (int id=InvalidId)
 creates and empty edge with no vertices More...
 
virtual ~Edge ()
 
virtual void resize (size_t size)
 
const VertexContainervertices () const
 
VertexContainervertices ()
 
const Vertexvertex (size_t i) const
 
Vertexvertex (size_t i)
 
void setVertex (size_t i, Vertex *v)
 
int id () const
 
void setId (int id)
 
virtual HyperGraphElementType elementType () const
 
int numUndefinedVertices () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 
HyperGraphElementclone () const
 

Protected Attributes

VertexContainer _vertices
 
int _id
 unique id More...
 

Detailed Description

Abstract Edge class. Your nice edge classes should inherit from that one. An hyper-edge has pointers to the vertices it connects and stores them in a vector.

Definition at line 165 of file hyper_graph.h.

Constructor & Destructor Documentation

g2o::HyperGraph::Edge::Edge ( int  id = InvalidId)
explicit

creates and empty edge with no vertices

Definition at line 51 of file hyper_graph.cpp.

51  : _id(id)
52  {
53  }
int _id
unique id
Definition: hyper_graph.h:203
g2o::HyperGraph::Edge::~Edge ( )
virtual

Reimplemented in g2o::OptimizableGraph::Edge.

Definition at line 55 of file hyper_graph.cpp.

56  {
57  }

Member Function Documentation

virtual HyperGraphElementType g2o::HyperGraph::Edge::elementType ( ) const
inlinevirtual

returns the type of the graph element, see HyperGraphElementType

Implements g2o::HyperGraph::HyperGraphElement.

Definition at line 198 of file hyper_graph.h.

References HGET_EDGE.

198 { return HGET_EDGE;}
HGET_EDGE
Definition: hyper_graph.h:63
int g2o::HyperGraph::Edge::id ( ) const
inline

Definition at line 196 of file hyper_graph.h.

Referenced by g2o::OptimizableGraph::saveEdge(), g2o::OptimizableGraph::setFixed(), and setId().

196 {return _id;}
int _id
unique id
Definition: hyper_graph.h:203
int g2o::HyperGraph::Edge::numUndefinedVertices ( ) const

Definition at line 59 of file hyper_graph.cpp.

References _vertices.

Referenced by g2o::OptimizableGraph::addEdge(), g2o::SparseOptimizer::initializeOptimization(), g2o::EdgeSE2PointXYWriteGnuplotAction::operator()(), and g2o::OptimizableGraph::setEdgeVertex().

59  {
60  int undefined=0;
61  for (size_t i=0; i<_vertices.size(); i++){
62  if (!_vertices[i])
63  undefined++;
64  }
65  return undefined;
66  }
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::HyperGraph::Edge::resize ( size_t  size)
virtual

resizes the number of vertices connected by this edge

Reimplemented in g2o::BaseMultiEdge<-1, E >, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 6, Isometry3D >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 4, Vector4D >, g2o::BaseMultiEdge< 2, Vector2D >, g2o::BaseMultiEdge< 3, Plane3D >, g2o::BaseMultiEdge<-1, VectorXD >, g2o::BaseMultiEdge< 3, VelocityMeasurement >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 1, double, VertexLine2D, VertexPointXY >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 6, Eigen::Vector3d, VertexPositionVelocity3D, VertexPositionVelocity3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexCameraBAL, VertexPointBAL >, g2o::BaseBinaryEdge< 2, Vector2D, VertexPointXY, VertexPointXY >, g2o::BaseBinaryEdge< 4, Vector4D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Line2D, VertexLine2D, VertexLine2D >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, Isometry3D, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 3, Eigen::Vector3d, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 4, Vector4D, VertexPlane, VertexPlane >, g2o::BaseBinaryEdge< 2, Line2D, VertexSE2, VertexLine2D >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 7, Vector7d, VertexSE3, VertexLine3D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE2, VertexSegment2D >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, Vector3D, VertexPointXYZ, VertexPointXYZ >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >, g2o::BaseBinaryEdge< 2, Vector2D, VertexSBAPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexBaseline >, g2o::BaseBinaryEdge< 3, OdomAndLaserMotion, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseBinaryEdge< 3, Vector3D, VertexSBAPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, Vector6d, VertexLine3D, VertexLine3D >, g2o::BaseUnaryEdge< D, E, VertexXi >, g2o::BaseUnaryEdge< 6, Isometry3D, VertexSE3 >, g2o::BaseUnaryEdge< 3, Eigen::Vector3d, VertexPosition3D >, g2o::BaseUnaryEdge< 1, Eigen::Vector2d, VertexCircle >, g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >, g2o::BaseUnaryEdge< 2, Vector2D, VertexSE2 >, g2o::BaseUnaryEdge< 3, Eigen::Vector3d, VertexPositionVelocity3D >, g2o::BaseUnaryEdge< 1, Eigen::Vector2d, VertexParams >, and g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >.

Definition at line 68 of file hyper_graph.cpp.

References _vertices.

Referenced by g2o::OptimizableGraph::addGraph(), and g2o::OptimizableGraph::setFixed().

69  {
70  _vertices.resize(size, 0);
71  }
VertexContainer _vertices
Definition: hyper_graph.h:202
void g2o::HyperGraph::Edge::setId ( int  id)

Definition at line 73 of file hyper_graph.cpp.

References _id, and id().

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

74  {
75  _id = id;
76  }
int _id
unique id
Definition: hyper_graph.h:203
void g2o::HyperGraph::Edge::setVertex ( size_t  i,
Vertex v 
)
inline

set the ith vertex on the hyper-edge to the pointer supplied

Definition at line 194 of file hyper_graph.h.

Referenced by g2o::OptimizableGraph::addGraph(), main(), g2o::Gm2dlIO::readGm2dl(), g2o::HyperGraph::setEdgeVertex(), and g2o::OptimizableGraph::setFixed().

194 { assert(i < _vertices.size() && "index out of bounds"); _vertices[i]=v;}
VertexContainer _vertices
Definition: hyper_graph.h:202
const Vertex* g2o::HyperGraph::Edge::vertex ( size_t  i) const
inline

returns the pointer to the ith vertex connected to the hyper-edge.

Definition at line 186 of file hyper_graph.h.

Referenced by g2o::OptimizableGraph::addGraph(), g2o::HyperGraph::addVertex(), g2o::OptimizableGraph::addVertex(), g2o::BlockSolver< Traits >::buildStructure(), g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::HyperGraph::changeId(), g2o::SparseOptimizer::computeInitialGuess(), g2o::HyperGraph::detachVertex(), g2o::Edge_V_V_GICP::Edge_V_V_GICP(), g2o::EdgeSE3PointXYZ::initialEstimate(), g2o::deprecated::EdgeSE3PointXYZDisparity::initialEstimate(), main(), g2o::HyperGraph::mergeVertices(), g2o::UnarySensor< Robot3D, EdgeSE3Prior >::mkEdge(), g2o::BinarySensor< Robot2D, EdgeSE2PointXY, WorldObjectPointXY >::mkEdge(), g2o::EdgeSE2PointXYBearingWriteGnuplotAction::operator()(), g2o::EdgeSE2PointXYWriteGnuplotAction::operator()(), g2o::EdgeSE2WriteGnuplotAction::operator()(), g2o::deprecated::EdgeSE3WriteGnuplotAction::operator()(), g2o::EstimatePropagator::propagate(), g2o::HyperGraph::setEdgeVertex(), g2o::OptimizableGraph::setFixed(), MainWindow::setRobustKernel(), g2o::HyperDijkstra::shortestPaths(), g2o::JacobianWorkspace::updateSize(), g2o::BlockSolver< Traits >::updateStructure(), g2o::OptimizableGraph::verifyInformationMatrices(), g2o::EdgeSE3PlaneSensorCalib::write(), g2o::EdgeSE2OdomDifferentialCalib::write(), g2o::EdgeSE2SensorCalib::write(), and g2o::Gm2dlIO::writeGm2dl().

186 { assert(i < _vertices.size() && "index out of bounds"); return _vertices[i];}
VertexContainer _vertices
Definition: hyper_graph.h:202
Vertex* g2o::HyperGraph::Edge::vertex ( size_t  i)
inline

returns the pointer to the ith vertex connected to the hyper-edge.

Definition at line 190 of file hyper_graph.h.

190 { assert(i < _vertices.size() && "index out of bounds"); return _vertices[i];}
VertexContainer _vertices
Definition: hyper_graph.h:202
const VertexContainer& g2o::HyperGraph::Edge::vertices ( ) const
inline

returns the vector of pointers to the vertices connected by the hyper-edge.

Definition at line 178 of file hyper_graph.h.

Referenced by g2o::G2oSlamInterface::addEdge(), g2o::HyperGraph::addEdge(), g2o::OptimizableGraph::addGraph(), g2o::addOdometryCalibLinksDifferential(), g2o::EdgeLabeler::augmentSparsePattern(), g2o::BlockSolver< Traits >::buildStructure(), g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::EdgeSE3Line3D::computeError(), g2o::SparseOptimizer::computeInitialGuess(), g2o::computeSimpleStars(), g2o::EdgeCreator::createEdge(), g2o::HyperGraph::detachVertex(), g2o::OptimizableGraph::dimensions(), g2o::edgeAllVertsSameDim(), g2o::BackBoneTreeAction::fillStar(), g2o::findConnectedEdgesWithCostLimit(), g2o::SparseOptimizer::gaugeFreedom(), g2o::SparseOptimizerOnline::gnuplotVisualization(), g2o::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::SparseOptimizer::initializeOptimization(), g2o::EdgeLabeler::labelEdge(), g2o::Star::labelStarEdges(), main(), g2o::OptimizableGraph::maxDimension(), g2o::HyperGraph::mergeVertices(), g2o::UnarySensor< Robot3D, EdgeSE3Prior >::mkEdge(), g2o::BinarySensor< Robot2D, EdgeSE2PointXY, WorldObjectPointXY >::mkEdge(), Robot::move(), g2o::EdgeSE3WriteGnuplotAction::operator()(), g2o::SparseOptimizerIncremental::optimize(), g2o::ThetaTreeAction::perform(), g2o::EstimatePropagator::propagate(), g2o::HyperGraph::removeEdge(), g2o::OptimizableGraph::save(), g2o::OptimizableGraph::saveEdge(), g2o::saveGnuplot(), PlaneSensor::sense(), g2o::OptimizableGraph::setFixed(), MainWindow::setRobustKernel(), g2o::HyperDijkstra::shortestPaths(), g2o::SolverSLAM2DLinear::solveOrientation(), g2o::starsInEdge(), g2o::SparseOptimizerIncremental::updateInitialization(), g2o::JacobianWorkspace::updateSize(), g2o::BlockSolver< Traits >::updateStructure(), and g2o::OptimizableGraph::verifyInformationMatrices().

178 { return _vertices;}
VertexContainer _vertices
Definition: hyper_graph.h:202
VertexContainer& g2o::HyperGraph::Edge::vertices ( )
inline

returns the vector of pointers to the vertices connected by the hyper-edge.

Definition at line 182 of file hyper_graph.h.

182 { return _vertices;}
VertexContainer _vertices
Definition: hyper_graph.h:202

Member Data Documentation

int g2o::HyperGraph::Edge::_id
protected

unique id

Definition at line 203 of file hyper_graph.h.

Referenced by setId().

VertexContainer g2o::HyperGraph::Edge::_vertices
protected

Definition at line 202 of file hyper_graph.h.

Referenced by g2o::HyperGraph::addVertex(), g2o::HyperGraph::changeId(), g2o::HyperGraph::clear(), g2o::EdgeSE2TwoPointsXY::computeError(), g2o::EdgeSE3::computeError(), g2o::EdgeSE3LotsOfXYZ::computeError(), g2o::EdgeSE2LotsOfXY::computeError(), g2o::EdgeLine2DPointXY::computeError(), g2o::EdgeSE3Calib::computeError(), g2o::EdgeSE2Segment2D::computeError(), g2o::tutorial::EdgeSE2PointXY::computeError(), g2o::EdgeSE3PointXYZDepth::computeError(), g2o::EdgeSE3PointXYZ::computeError(), g2o::deprecated::EdgeSE3PointXYZDepth::computeError(), g2o::EdgeSE2Segment2DLine::computeError(), g2o::EdgeSE2PointXYOffset::computeError(), g2o::deprecated::EdgeSE3PointXYZ::computeError(), g2o::EdgeSE3PointXYZDisparity::computeError(), g2o::EdgeSE2PureCalib::computeError(), g2o::deprecated::EdgeSE3PointXYZDisparity::computeError(), g2o::EdgeProjectPSI2UV::computeError(), g2o::BaseUnaryEdge< D, E, VertexXi >::constructQuadraticForm(), g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::constructQuadraticForm(), g2o::HyperGraph::detachVertex(), g2o::OptimizableGraph::discardTop(), g2o::Edge_V_V_GICP::Edge_V_V_GICP(), g2o::OptimizableGraph::Edge::graph(), g2o::EdgeSE2TwoPointsXY::initialEstimate(), g2o::EdgeSE3LotsOfXYZ::initialEstimate(), g2o::EdgeSE2LotsOfXY::initialEstimate(), g2o::EdgeSE3::initialEstimate(), g2o::EdgeSE2PointXYCalib::initialEstimate(), g2o::EdgeSE3Offset::initialEstimate(), g2o::EdgeSE2SensorCalib::initialEstimate(), g2o::EdgeSE2PointXY::initialEstimate(), g2o::EdgeSE2Prior::initialEstimate(), g2o::EdgeSE2PointXYBearing::initialEstimate(), g2o::deprecated::EdgeSE3Prior::initialEstimate(), g2o::EdgeSE3Prior::initialEstimate(), g2o::EdgeSE3PointXYZDepth::initialEstimate(), g2o::EdgeSE3PointXYZ::initialEstimate(), g2o::deprecated::EdgeSE3PointXYZDepth::initialEstimate(), g2o::deprecated::EdgeSE3PointXYZ::initialEstimate(), g2o::EdgeSE2Offset::initialEstimate(), g2o::EdgeSE2PointXYOffset::initialEstimate(), g2o::deprecated::EdgeSE3Offset::initialEstimate(), g2o::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::deprecated::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::EdgeSE2::initialEstimate(), g2o::EdgeSE2Segment2D::initialEstimate(), g2o::EdgeSE2Line2D::initialEstimate(), g2o::deprecated::EdgeSE3::initialEstimate(), g2o::EdgeSBACam::initialEstimate(), g2o::EdgeSBAScale::initialEstimate(), g2o::EdgeSE2TwoPointsXY::initialEstimatePossible(), g2o::EdgeSE3LotsOfXYZ::initialEstimatePossible(), g2o::EdgeSE2LotsOfXY::initialEstimatePossible(), g2o::EdgeSE2Segment2D::initialEstimatePossible(), g2o::EdgeSE3::linearizeOplus(), g2o::EdgeSE3LotsOfXYZ::linearizeOplus(), g2o::EdgeSE2LotsOfXY::linearizeOplus(), g2o::deprecated::EdgeSE3Prior::linearizeOplus(), g2o::EdgeSE3PointXYZDepth::linearizeOplus(), g2o::EdgeSE3Prior::linearizeOplus(), g2o::EdgeSE3PointXYZ::linearizeOplus(), g2o::deprecated::EdgeSE3PointXYZDepth::linearizeOplus(), g2o::EdgeSE2PointXYOffset::linearizeOplus(), g2o::EdgeSE3Offset::linearizeOplus(), g2o::deprecated::EdgeSE3PointXYZ::linearizeOplus(), g2o::EdgeSE3PointXYZDisparity::linearizeOplus(), g2o::deprecated::EdgeSE3PointXYZDisparity::linearizeOplus(), g2o::deprecated::EdgeSE3Offset::linearizeOplus(), g2o::EdgeSE2PointXY::linearizeOplus(), g2o::EdgeSE2::linearizeOplus(), g2o::deprecated::EdgeSE3::linearizeOplus(), g2o::EdgeSE3Expmap::linearizeOplus(), g2o::EdgeProjectXYZ2UV::linearizeOplus(), g2o::EdgeProjectPSI2UV::linearizeOplus(), g2o::EdgeProjectP2MC::linearizeOplus(), g2o::Edge_V_V_GICP::linearizeOplus(), g2o::EdgeProjectP2SC::linearizeOplus(), g2o::EdgeProjectP2MC_Intrinsics::linearizeOplus(), g2o::HyperGraph::mergeVertices(), numUndefinedVertices(), g2o::OptimizableGraph::pop(), g2o::OptimizableGraph::push(), g2o::HyperGraph::removeVertex(), resize(), g2o::tutorial::EdgeSE2PointXY::resolveCaches(), g2o::EdgeSE3Offset::resolveCaches(), g2o::EdgeSE3Line3D::resolveCaches(), g2o::deprecated::EdgeSE3Prior::resolveCaches(), g2o::EdgeSE3Prior::resolveCaches(), g2o::EdgeSE3PointXYZDepth::resolveCaches(), g2o::EdgeSE2Offset::resolveCaches(), g2o::deprecated::EdgeSE3PointXYZDepth::resolveCaches(), g2o::EdgeSE2PointXYOffset::resolveCaches(), g2o::deprecated::EdgeSE3PointXYZ::resolveCaches(), g2o::EdgeSE3PointXYZ::resolveCaches(), g2o::deprecated::EdgeSE3Offset::resolveCaches(), g2o::deprecated::EdgeSE3PointXYZDisparity::resolveCaches(), g2o::EdgeSE3PointXYZDisparity::resolveCaches(), g2o::EdgeSE2TwoPointsXY::setMeasurementFromState(), g2o::EdgeSE3LotsOfXYZ::setMeasurementFromState(), g2o::EdgeSE2LotsOfXY::setMeasurementFromState(), g2o::EdgeSE3::setMeasurementFromState(), g2o::EdgeLine2DPointXY::setMeasurementFromState(), g2o::EdgeSE3PointXYZDepth::setMeasurementFromState(), g2o::EdgeSE3PointXYZ::setMeasurementFromState(), g2o::deprecated::EdgeSE3PointXYZDepth::setMeasurementFromState(), g2o::deprecated::EdgeSE3PointXYZ::setMeasurementFromState(), g2o::EdgeSE2PointXYOffset::setMeasurementFromState(), g2o::EdgeSE2Segment2D::setMeasurementFromState(), g2o::EdgeSE3PointXYZDisparity::setMeasurementFromState(), g2o::deprecated::EdgeSE3PointXYZDisparity::setMeasurementFromState(), g2o::EdgeSE2Segment2DLine::setMeasurementFromState(), g2o::deprecated::EdgeSE3::setMeasurementFromState(), g2o::EdgeSBACam::setMeasurementFromState(), and g2o::HyperGraph::vertex().


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