g2o
Loading...
Searching...
No Matches
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
 
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 ()
 

Protected Attributes

VertexContainer _vertices
 
int _id
 unique id
 

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

Constructor & Destructor Documentation

◆ Edge()

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

creates and empty edge with no vertices

Definition at line 50 of file hyper_graph.cpp.

50: _id(id) {}

◆ ~Edge()

g2o::HyperGraph::Edge::~Edge ( )
virtual

Reimplemented in g2o::OptimizableGraph::Edge.

Definition at line 52 of file hyper_graph.cpp.

52{}

Member Function Documentation

◆ elementType()

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

returns the type of the graph element, see HyperGraphElementType

Implements g2o::HyperGraph::HyperGraphElement.

Definition at line 216 of file hyper_graph.h.

216{ return HGET_EDGE; }
HGET_EDGE
Definition hyper_graph.h:60

References HGET_EDGE.

◆ id()

int g2o::HyperGraph::Edge::id ( ) const
inline

Definition at line 214 of file hyper_graph.h.

214{ return _id; }

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

◆ numUndefinedVertices()

int g2o::HyperGraph::Edge::numUndefinedVertices ( ) const

Definition at line 54 of file hyper_graph.cpp.

54 {
55 return std::count_if(_vertices.begin(), _vertices.end(),
56 [](const Vertex* ptr) { return ptr == nullptr; });
57}
VertexContainer _vertices

References g2o::HyperGraph::_vertices.

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

◆ resize()

void g2o::HyperGraph::Edge::resize ( size_t  size)
virtual

resizes the number of vertices connected by this edge

Reimplemented in g2o::BaseFixedSizedEdge< D, E, VertexTypes >, g2o::BaseFixedSizedEdge< 2, Vector2, VertexPointXYZ, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseFixedSizedEdge< 3, SE2, VertexSE2, VertexSE2, VertexSE2 >, g2o::BaseFixedSizedEdge< 3, VelocityMeasurement, VertexSE2, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseFixedSizedEdge< D, double, PolynomialCoefficientVertex >, g2o::BaseFixedSizedEdge< D, double, VertexCam, VertexCam >, g2o::BaseFixedSizedEdge< D, double, VertexLine2D, VertexPointXY >, g2o::BaseFixedSizedEdge< D, double, VertexSE2, VertexPointXY >, g2o::BaseFixedSizedEdge< D, E, VertexXi >, g2o::BaseFixedSizedEdge< D, E, VertexXi, VertexXj >, g2o::BaseFixedSizedEdge< D, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseFixedSizedEdge< D, Eigen::Vector2d, VertexCircle >, g2o::BaseFixedSizedEdge< D, Eigen::Vector2d, VertexParams >, g2o::BaseFixedSizedEdge< D, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseFixedSizedEdge< D, Eigen::Vector3d, VertexPosition3D >, g2o::BaseFixedSizedEdge< D, Eigen::Vector3d, VertexPositionVelocity3D >, g2o::BaseFixedSizedEdge< D, Eigen::Vector3d, VertexPositionVelocity3D, VertexPositionVelocity3D >, g2o::BaseFixedSizedEdge< D, Eigen::VectorXd, FPolynomialCoefficientVertex, PPolynomialCoefficientVertex >, g2o::BaseFixedSizedEdge< D, g2o::Vector2, VertexCameraBAL, VertexPointBAL >, g2o::BaseFixedSizedEdge< D, Isometry3, VertexSE3 >, g2o::BaseFixedSizedEdge< D, Isometry3, VertexSE3, VertexSE3 >, g2o::BaseFixedSizedEdge< D, Line2D, VertexLine2D, VertexLine2D >, g2o::BaseFixedSizedEdge< D, Line2D, VertexSE2, VertexLine2D >, g2o::BaseFixedSizedEdge< D, Line3D, VertexSE3, VertexLine3D >, g2o::BaseFixedSizedEdge< D, OdomAndLaserMotion, VertexSE2, VertexBaseline >, g2o::BaseFixedSizedEdge< D, OdomAndLaserMotion, VertexSE2, VertexOdomDifferentialParams >, g2o::BaseFixedSizedEdge< D, SE2, VertexSE2 >, g2o::BaseFixedSizedEdge< D, SE2, VertexSE2, VertexSE2 >, g2o::BaseFixedSizedEdge< D, SE3Quat, VertexCam, VertexCam >, g2o::BaseFixedSizedEdge< D, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseFixedSizedEdge< D, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseFixedSizedEdge< D, Vector2, VertexPointXY >, g2o::BaseFixedSizedEdge< D, Vector2, VertexPointXY, VertexPointXY >, g2o::BaseFixedSizedEdge< D, Vector2, VertexPointXYZ, VertexCam >, g2o::BaseFixedSizedEdge< D, Vector2, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseFixedSizedEdge< D, Vector2, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseFixedSizedEdge< D, Vector2, VertexSE2 >, g2o::BaseFixedSizedEdge< D, Vector2, VertexSE2, VertexPointXY >, g2o::BaseFixedSizedEdge< D, Vector2, VertexSE2, VertexSegment2D >, g2o::BaseFixedSizedEdge< D, Vector2, VertexSE3Expmap >, g2o::BaseFixedSizedEdge< D, Vector3, VertexPointXYZ >, g2o::BaseFixedSizedEdge< D, Vector3, VertexPointXYZ, VertexCam >, g2o::BaseFixedSizedEdge< D, Vector3, VertexPointXYZ, VertexPointXYZ >, g2o::BaseFixedSizedEdge< D, Vector3, VertexPointXYZ, VertexSCam >, g2o::BaseFixedSizedEdge< D, Vector3, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseFixedSizedEdge< D, Vector3, VertexSE2, VertexSegment2D >, g2o::BaseFixedSizedEdge< D, Vector3, VertexSE3 >, g2o::BaseFixedSizedEdge< D, Vector3, VertexSE3, VertexPointXYZ >, g2o::BaseFixedSizedEdge< D, Vector3, VertexSE3Expmap >, g2o::BaseFixedSizedEdge< D, Vector4, VertexPlane, VertexPlane >, g2o::BaseFixedSizedEdge< D, Vector4, VertexSE2, VertexSegment2D >, g2o::BaseVariableSizedEdge< D, E >, g2o::BaseVariableSizedEdge< 2, Vector2 >, g2o::BaseVariableSizedEdge< 3, Plane3D >, g2o::BaseVariableSizedEdge< 4, Vector4 >, g2o::BaseVariableSizedEdge< 6, Isometry3 >, and g2o::BaseVariableSizedEdge<-1, VectorX >.

Definition at line 59 of file hyper_graph.cpp.

59{ _vertices.resize(size, 0); }

References g2o::HyperGraph::_vertices.

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

◆ setId()

void g2o::HyperGraph::Edge::setId ( int  id)

Definition at line 61 of file hyper_graph.cpp.

61{ _id = id; }

Referenced by main().

◆ setVertex()

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

209 {
210 assert(i < _vertices.size() && "index out of bounds");
211 _vertices[i] = v;
212 }

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

◆ vertex() [1/2]

Vertex * g2o::HyperGraph::Edge::vertex ( size_t  i)
inline

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

Definition at line 202 of file hyper_graph.h.

202 {
203 assert(i < _vertices.size() && "index out of bounds");
204 return _vertices[i];
205 }

◆ vertex() [2/2]

const Vertex * g2o::HyperGraph::Edge::vertex ( size_t  i) const
inline

◆ vertices() [1/2]

VertexContainer & g2o::HyperGraph::Edge::vertices ( )
inline

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

Definition at line 191 of file hyper_graph.h.

191{ return _vertices; }

◆ vertices() [2/2]

const VertexContainer & g2o::HyperGraph::Edge::vertices ( ) const
inline

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

Definition at line 186 of file hyper_graph.h.

186{ return _vertices; }

Referenced by g2o::G2oSlamInterface::addEdge(), g2o::HyperGraph::addEdge(), g2o::addOdometryCalibLinksDifferential(), g2o::EdgeLabeler::augmentSparsePattern(), g2o::BlockSolver< Traits >::buildStructure(), g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizer::computeInitialGuess(), g2o::computeSimpleStars(), g2o::EdgeCreator::createEdge(), g2o::HyperGraph::detachVertex(), g2o::edgeAllVertsSameDim(), g2o::BackBoneTreeAction::fillStar(), g2o::findConnectedEdgesWithCostLimit(), g2o::SparseOptimizer::gaugeFreedom(), g2o::SparseOptimizerOnline::gnuplotVisualization(), g2o::SparseOptimizer::initializeOptimization(), g2o::SparseOptimizer::initializeOptimization(), g2o::EdgeLabeler::labelEdge(), g2o::Star::labelStarEdges(), main(), main(), main(), g2o::HyperGraph::mergeVertices(), Robot::move(), g2o::EdgeSE3WriteGnuplotAction::operator()(), IncrementalEdgesCompare::operator()(), g2o::SparseOptimizerIncremental::optimize(), g2o::ThetaTreeAction::perform(), g2o::EstimatePropagator::propagate(), g2o::HyperGraph::removeEdge(), g2o::OptimizableGraph::saveEdge(), g2o::saveGnuplot(), LineSensor::sense(), PlaneSensor::sense(), MainWindow::setRobustKernel(), g2o::HyperDijkstra::shortestPaths(), g2o::SolverSLAM2DLinear::solveOrientation(), g2o::starsInEdge(), g2o::SparseOptimizerIncremental::updateInitialization(), g2o::JacobianWorkspace::updateSize(), g2o::BlockSolver< Traits >::updateStructure(), and g2o::OptimizableGraph::verifyInformationMatrices().

Member Data Documentation

◆ _id

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

unique id

Definition at line 222 of file hyper_graph.h.

◆ _vertices

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

Definition at line 221 of file hyper_graph.h.

Referenced by g2o::EdgeSE2PureCalib::computeError(), EdgeCalib::computeError(), PolynomialSingleValueEdge::computeError(), MultipleValueEdge::computeError(), GPSObservationPosition3DEdge::computeError(), TargetOdometry3DEdge::computeError(), GPSObservationEdgePositionVelocity3D::computeError(), g2o::tutorial::EdgeSE2PointXY::computeError(), g2o::EdgeProjectP2MC::computeError(), g2o::EdgeProjectP2SC::computeError(), g2o::EdgeStereoSE3ProjectXYZOnlyPose::computeError(), g2o::EdgeSE3ProjectXYZ::computeError(), g2o::EdgeProjectXYZ2UV::computeError(), g2o::EdgeProjectXYZ2UVU::computeError(), g2o::EdgeSE3ProjectXYZOnlyPose::computeError(), g2o::EdgeSBACam::computeError(), g2o::EdgeSBAScale::computeError(), g2o::EdgeSE3Expmap::computeError(), g2o::EdgeSE2LotsOfXY::computeError(), g2o::EdgeSE2PointXYOffset::computeError(), g2o::EdgeSE2TwoPointsXY::computeError(), g2o::EdgeLine2DPointXY::computeError(), g2o::EdgeSE2Segment2D::computeError(), g2o::EdgeSE2Segment2DLine::computeError(), g2o::EdgeSE3::computeError(), g2o::EdgeSE3LotsOfXYZ::computeError(), g2o::EdgeSE3PointXYZ::computeError(), g2o::EdgeSE3PointXYZDepth::computeError(), g2o::EdgeSE3PointXYZDisparity::computeError(), g2o::EdgeSE3XYZPrior::computeError(), g2o::EdgeXYZPrior::computeError(), g2o::EdgeSE3Calib::computeError(), g2o::EdgeSE3Line3D::computeError(), g2o::Edge_V_V_GICP::Edge_V_V_GICP(), g2o::EdgeSE2LotsOfXY::initialEstimate(), g2o::EdgeSE2TwoPointsXY::initialEstimate(), g2o::EdgeSE3LotsOfXYZ::initialEstimate(), g2o::EdgeSE3XYZPrior::initialEstimate(), g2o::EdgeSBACam::initialEstimate(), g2o::EdgeSE2SensorCalib::initialEstimate(), g2o::EdgeSE2::initialEstimate(), g2o::EdgeSE2Offset::initialEstimate(), g2o::EdgeSE2PointXY::initialEstimate(), g2o::EdgeSE2PointXYBearing::initialEstimate(), g2o::EdgeSE2PointXYCalib::initialEstimate(), g2o::EdgeSE2PointXYOffset::initialEstimate(), g2o::EdgeSE2Prior::initialEstimate(), g2o::EdgeSE2Line2D::initialEstimate(), g2o::EdgeSE2Segment2D::initialEstimate(), g2o::EdgeSE3::initialEstimate(), g2o::EdgeSE3Offset::initialEstimate(), g2o::EdgeSE3PointXYZ::initialEstimate(), g2o::EdgeSE3PointXYZDepth::initialEstimate(), g2o::EdgeSE3PointXYZDisparity::initialEstimate(), g2o::EdgeSE3Prior::initialEstimate(), g2o::EdgeSBAScale::initialEstimate(), g2o::EdgeSE2LotsOfXY::initialEstimatePossible(), g2o::EdgeSE2TwoPointsXY::initialEstimatePossible(), g2o::EdgeSE3LotsOfXYZ::initialEstimatePossible(), g2o::EdgeSE2Segment2D::initialEstimatePossible(), g2o::EdgeStereoSE3ProjectXYZOnlyPose::isDepthPositive(), g2o::EdgeSE3ProjectXYZ::isDepthPositive(), g2o::EdgeSE3ProjectXYZOnlyPose::isDepthPositive(), g2o::Edge_V_V_GICP::linearizeOplus(), g2o::EdgeProjectP2MC::linearizeOplus(), g2o::EdgeProjectP2SC::linearizeOplus(), g2o::EdgeStereoSE3ProjectXYZ::linearizeOplus(), g2o::EdgeStereoSE3ProjectXYZOnlyPose::linearizeOplus(), g2o::EdgeSE3ProjectXYZ::linearizeOplus(), g2o::EdgeProjectXYZ2UV::linearizeOplus(), g2o::EdgeSE3ProjectXYZOnlyPose::linearizeOplus(), g2o::EdgeSE3Expmap::linearizeOplus(), g2o::EdgeSE2::linearizeOplus(), g2o::EdgeSE2LotsOfXY::linearizeOplus(), g2o::EdgeSE2PointXY::linearizeOplus(), g2o::EdgeSE2PointXYOffset::linearizeOplus(), g2o::EdgeSE3::linearizeOplus(), g2o::EdgeSE3LotsOfXYZ::linearizeOplus(), g2o::EdgeSE3Offset::linearizeOplus(), g2o::EdgeSE3PointXYZ::linearizeOplus(), g2o::EdgeSE3PointXYZDepth::linearizeOplus(), g2o::EdgeSE3PointXYZDisparity::linearizeOplus(), g2o::EdgeSE3Prior::linearizeOplus(), g2o::EdgeSE3XYZPrior::linearizeOplus(), g2o::tutorial::EdgeSE2PointXY::resolveCaches(), g2o::EdgeSE2Offset::resolveCaches(), g2o::EdgeSE2PointXYOffset::resolveCaches(), g2o::EdgeSE3Offset::resolveCaches(), g2o::EdgeSE3PointXYZ::resolveCaches(), g2o::EdgeSE3PointXYZDepth::resolveCaches(), g2o::EdgeSE3PointXYZDisparity::resolveCaches(), g2o::EdgeSE3Prior::resolveCaches(), g2o::EdgeSE3XYZPrior::resolveCaches(), g2o::EdgeSE3Line3D::resolveCaches(), g2o::EdgeSBACam::setMeasurementFromState(), g2o::EdgeSE2LotsOfXY::setMeasurementFromState(), g2o::EdgeSE2PointXYOffset::setMeasurementFromState(), g2o::EdgeSE2TwoPointsXY::setMeasurementFromState(), g2o::EdgeLine2DPointXY::setMeasurementFromState(), g2o::EdgeSE2Segment2D::setMeasurementFromState(), g2o::EdgeSE2Segment2DLine::setMeasurementFromState(), g2o::EdgeSE3::setMeasurementFromState(), g2o::EdgeSE3LotsOfXYZ::setMeasurementFromState(), g2o::EdgeSE3PointXYZ::setMeasurementFromState(), g2o::EdgeSE3PointXYZDepth::setMeasurementFromState(), g2o::EdgeSE3PointXYZDisparity::setMeasurementFromState(), g2o::EdgeSE3XYZPrior::setMeasurementFromState(), g2o::EdgeXYZPrior::setMeasurementFromState(), g2o::BaseFixedSizedEdge< D, E, VertexTypes >::vertexXn(), and g2o::BaseFixedSizedEdge< D, E, VertexTypes >::vertexXn().


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