g2o
|
#include <optimizable_graph.h>
Public Member Functions | |
Edge () | |
virtual | ~Edge () |
virtual Edge * | clone () const |
virtual bool | allVerticesFixed () const =0 |
virtual void | computeError ()=0 |
virtual bool | setMeasurementData (const double *m) |
virtual bool | getMeasurementData (double *m) const |
virtual int | measurementDimension () const |
virtual bool | setMeasurementFromState () |
RobustKernel * | robustKernel () const |
if NOT NULL, error of this edge will be robustifed with the kernel More... | |
void | setRobustKernel (RobustKernel *ptr) |
virtual const double * | errorData () const =0 |
returns the error vector cached after calling the computeError; More... | |
virtual double * | errorData ()=0 |
virtual const double * | informationData () const =0 |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD> More... | |
virtual double * | informationData ()=0 |
virtual double | chi2 () const =0 |
computes the chi2 based on the cached error value, only valid after computeError has been called. More... | |
virtual void | constructQuadraticForm ()=0 |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor)=0 |
virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace)=0 |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)=0 |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
int | level () const |
returns the level of the edge More... | |
void | setLevel (int l) |
sets the level of the edge More... | |
int | dimension () const |
returns the dimensions of the error function More... | |
G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createFrom()) | |
G2O_ATTRIBUTE_DEPRECATED (virtual Vertex *createTo()) | |
virtual Vertex * | createVertex (int) |
virtual bool | read (std::istream &is)=0 |
read the vertex from a stream, i.e., the internal state of the vertex More... | |
virtual bool | write (std::ostream &os) const =0 |
write the vertex to a stream More... | |
long long | internalId () const |
the internal ID of the edge More... | |
OptimizableGraph * | graph () |
const OptimizableGraph * | graph () const |
bool | setParameterId (int argNum, int paramId) |
const Parameter * | parameter (int argNo) const |
size_t | numParameters () const |
void | resizeParameters (size_t newSize) |
Public Member Functions inherited from g2o::HyperGraph::Edge | |
Edge (int id=InvalidId) | |
creates and empty edge with no vertices More... | |
virtual void | resize (size_t size) |
const VertexContainer & | vertices () const |
VertexContainer & | vertices () |
const Vertex * | vertex (size_t i) const |
Vertex * | vertex (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 () |
HyperGraphElement * | clone () const |
Public Member Functions inherited from g2o::HyperGraph::DataContainer | |
DataContainer () | |
virtual | ~DataContainer () |
const Data * | userData () const |
the user data associated with this vertex More... | |
Data * | userData () |
void | setUserData (Data *obs) |
void | addUserData (Data *obs) |
Protected Member Functions | |
template<typename ParameterType > | |
bool | installParameter (ParameterType *&p, size_t argNo, int paramId=-1) |
template<typename CacheType > | |
void | resolveCache (CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters) |
bool | resolveParameters () |
virtual bool | resolveCaches () |
Protected Attributes | |
int | _dimension |
int | _level |
RobustKernel * | _robustKernel |
long long | _internalId |
std::vector< int > | _cacheIds |
std::vector< std::string > | _parameterTypes |
std::vector< Parameter ** > | _parameters |
std::vector< int > | _parameterIds |
Protected Attributes inherited from g2o::HyperGraph::Edge | |
VertexContainer | _vertices |
int | _id |
unique id More... | |
Protected Attributes inherited from g2o::HyperGraph::DataContainer | |
Data * | _userData |
Friends | |
struct | OptimizableGraph |
Definition at line 349 of file optimizable_graph.h.
g2o::OptimizableGraph::Edge::Edge | ( | ) |
Definition at line 120 of file optimizable_graph.cpp.
|
virtual |
Reimplemented from g2o::HyperGraph::Edge.
Definition at line 126 of file optimizable_graph.cpp.
References _robustKernel.
|
pure virtual |
Implemented 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 >.
Referenced by g2o::SparseOptimizer::initializeOptimization(), and g2o::SparseOptimizer::updateInitialization().
|
pure virtual |
computes the chi2 based on the cached error value, only valid after computeError has been called.
Implemented in g2o::BaseEdge<-1, E >, g2o::OnlineEdgeSE2, g2o::OnlineEdgeSE3, g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2D >, g2o::BaseEdge< D, Eigen::Vector3d >, g2o::BaseEdge< D, Vector3D >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Isometry3D >, g2o::BaseEdge< D, Vector4D >, g2o::BaseEdge< D, Plane3D >, g2o::BaseEdge< D, Vector6d >, g2o::BaseEdge< D, Line2D >, g2o::BaseEdge< D, Vector7d >, g2o::BaseEdge< D, OdomAndLaserMotion >, g2o::BaseEdge< D, VectorXD >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, VelocityMeasurement >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
Referenced by g2o::SparseOptimizer::activeChi2(), g2o::SparseOptimizer::activeRobustChi2(), g2o::activeVertexChi(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::OptimizableGraph::chi2(), gnudump_edges(), gnudump_features(), main(), and InvChi2CostFunction::operator()().
|
virtual |
Definition at line 212 of file optimizable_graph.cpp.
Referenced by g2o::OptimizableGraph::addGraph().
|
pure virtual |
Implemented in g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, EdgeObservationBAL, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVU, g2o::Edge_V_V_GICP, GPSObservationEdgePositionVelocity3D, g2o::EdgeProjectP2MC, g2o::EdgeProjectPSI2UV, g2o::EdgeProjectXYZ2UV, TargetOdometry3DEdge, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSE3Expmap, EdgePointOnCircle, EdgePointOnCurve, g2o::EdgeSim3, GPSObservationPosition3DEdge, EdgeCalib, g2o::EdgeSE2XYPrior, g2o::EdgeSE2PureCalib, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Segment2DPointLine, g2o::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE2Offset, g2o::EdgeSE2Segment2DLine, g2o::EdgeSE3Offset, g2o::EdgeSE3PointXYZ, g2o::tutorial::EdgeSE2PointXY, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE2Segment2D, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::tutorial::EdgeSE2, g2o::EdgeSE3Calib, g2o::EdgeSE2, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE3PlaneSensorCalib, g2o::EdgeSE2OdomDifferentialCalib, g2o::EdgeSE2SensorCalib, g2o::EdgeSE2Prior, g2o::EdgeLine2DPointXY, g2o::EdgeSE2Line2D, g2o::EdgeSE2PointXY, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeLine2D, g2o::EdgePointXYZ, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, g2o::EdgeSE3, and g2o::EdgeSE2TwoPointsXY.
Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizer::computeActiveErrors(), gnudump_edges(), gnudump_features(), g2o::EdgeLabeler::labelEdge(), main(), InvChi2CostFunction::operator()(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizerIncremental::updateInitialization().
|
pure virtual |
Linearizes the constraint in the edge. Makes side effect on the vertices of the graph by changing the parameter vector b and the hessian blocks ii and jj. The off diagoinal block is accesed via _hessian.
Implemented in g2o::BaseMultiEdge<-1, E >, 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::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::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 >.
Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizerIncremental::updateInitialization().
|
inlinevirtual |
Reimplemented in 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 444 of file optimizable_graph.h.
Referenced by g2o::OptimizableGraph::setFixed().
|
inline |
returns the dimensions of the error function
Definition at line 440 of file optimizable_graph.h.
Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::SparseOptimizer::computeActiveErrors(), g2o::SparseOptimizer::gaugeFreedom(), g2o::EdgeLabeler::labelEdge(), g2o::JacobianWorkspace::updateSize(), and g2o::OptimizableGraph::verifyInformationMatrices().
|
pure virtual |
returns the error vector cached after calling the computeError;
Implemented in g2o::BaseEdge<-1, E >, g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2D >, g2o::BaseEdge< D, Eigen::Vector3d >, g2o::BaseEdge< D, Vector3D >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Isometry3D >, g2o::BaseEdge< D, Vector4D >, g2o::BaseEdge< D, Plane3D >, g2o::BaseEdge< D, Vector6d >, g2o::BaseEdge< D, Line2D >, g2o::BaseEdge< D, Vector7d >, g2o::BaseEdge< D, OdomAndLaserMotion >, g2o::BaseEdge< D, VectorXD >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, VelocityMeasurement >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
Referenced by g2o::SparseOptimizer::computeActiveErrors(), and g2o::EdgeLabeler::labelEdge().
|
pure virtual |
Implemented in g2o::BaseEdge<-1, E >, g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2D >, g2o::BaseEdge< D, Eigen::Vector3d >, g2o::BaseEdge< D, Vector3D >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Isometry3D >, g2o::BaseEdge< D, Vector4D >, g2o::BaseEdge< D, Plane3D >, g2o::BaseEdge< D, Vector6d >, g2o::BaseEdge< D, Line2D >, g2o::BaseEdge< D, Vector7d >, g2o::BaseEdge< D, OdomAndLaserMotion >, g2o::BaseEdge< D, VectorXD >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, VelocityMeasurement >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
|
inline |
Definition at line 442 of file optimizable_graph.h.
|
inline |
Definition at line 443 of file optimizable_graph.h.
|
virtual |
writes the measurement to an array of double
Reimplemented in g2o::EdgeSBACam, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Segment2DPointLine, g2o::EdgeSE2Segment2DLine, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::EdgeSE2Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE2Segment2D, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeLine2D, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2Line2D, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE2Prior, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgePointXYZ, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2XYPrior, and g2o::EdgeSE3.
Definition at line 197 of file optimizable_graph.cpp.
OptimizableGraph * g2o::OptimizableGraph::Edge::graph | ( | ) |
Definition at line 131 of file optimizable_graph.cpp.
References g2o::HyperGraph::Edge::_vertices, and g2o::OptimizableGraph::Vertex::graph().
Referenced by resolveParameters().
const OptimizableGraph * g2o::OptimizableGraph::Edge::graph | ( | ) | const |
Definition at line 140 of file optimizable_graph.cpp.
References g2o::HyperGraph::Edge::_vertices, and g2o::OptimizableGraph::Vertex::graph().
|
pure virtual |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD>
Implemented in g2o::BaseEdge<-1, E >, g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2D >, g2o::BaseEdge< D, Eigen::Vector3d >, g2o::BaseEdge< D, Vector3D >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Isometry3D >, g2o::BaseEdge< D, Vector4D >, g2o::BaseEdge< D, Plane3D >, g2o::BaseEdge< D, Vector6d >, g2o::BaseEdge< D, Line2D >, g2o::BaseEdge< D, Vector7d >, g2o::BaseEdge< D, OdomAndLaserMotion >, g2o::BaseEdge< D, VectorXD >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, VelocityMeasurement >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
Referenced by g2o::EdgeLabeler::labelEdge(), and g2o::OptimizableGraph::verifyInformationMatrices().
|
pure virtual |
Implemented in g2o::BaseEdge<-1, E >, g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2D >, g2o::BaseEdge< D, Eigen::Vector3d >, g2o::BaseEdge< D, Vector3D >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Isometry3D >, g2o::BaseEdge< D, Vector4D >, g2o::BaseEdge< D, Plane3D >, g2o::BaseEdge< D, Vector6d >, g2o::BaseEdge< D, Line2D >, g2o::BaseEdge< D, Vector7d >, g2o::BaseEdge< D, OdomAndLaserMotion >, g2o::BaseEdge< D, VectorXD >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, VelocityMeasurement >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
|
pure virtual |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Implemented in g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::BaseEdge<-1, E >, TargetOdometry3DEdge, g2o::EdgeSim3, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Line2D, g2o::EdgeSE2, g2o::EdgeSE2Segment2D, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3Offset, g2o::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2Offset, g2o::EdgeSE2PointXYOffset, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::BaseEdge< D, E >, g2o::deprecated::EdgeSE3Prior, g2o::BaseEdge< D, Vector2D >, g2o::BaseEdge< D, Eigen::Vector3d >, g2o::BaseEdge< D, Vector3D >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Isometry3D >, g2o::BaseEdge< D, Vector4D >, g2o::BaseEdge< D, Plane3D >, g2o::BaseEdge< D, Vector6d >, g2o::BaseEdge< D, Line2D >, g2o::BaseEdge< D, Vector7d >, g2o::BaseEdge< D, OdomAndLaserMotion >, g2o::BaseEdge< D, VectorXD >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, VelocityMeasurement >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, g2o::BaseEdge< D, Eigen::Vector2d >, 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 >, g2o::BaseUnaryEdge< 6, SE3Quat, VertexSE3 >, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2PointXY, g2o::EdgeSE2Prior, g2o::EdgeSE2SensorCalib, g2o::OnlineEdgeSE2, g2o::OnlineEdgeSE3, g2o::EdgeSE3Offset, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE3, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, and g2o::EdgeSE2TwoPointsXY.
Referenced by g2o::SparseOptimizer::computeInitialGuess(), g2o::EstimatePropagator::PropagateAction::operator()(), and g2o::OptimizableGraph::setFixed().
|
inlinevirtual |
override in your class if it's possible to initialize the vertices in certain combinations. The return value may correspond to the cost for initiliaizng the vertex but should be positive if the initialization is possible and negative if not possible.
Reimplemented in g2o::EdgeSBAScale, g2o::EdgeSBACam, TargetOdometry3DEdge, g2o::EdgeSim3, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Line2D, g2o::EdgeSE2Segment2D, g2o::EdgeSE2, g2o::EdgeLine2D, g2o::EdgePlane, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeLine3D, g2o::EdgeSE2Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgePointXY, g2o::EdgeSE2PointXYOffset, g2o::EdgePointXYZ, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE2PointXY, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE2Prior, g2o::EdgeSE2SensorCalib, g2o::EdgeSE3Offset, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE3, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, and g2o::EdgeSE2TwoPointsXY.
Definition at line 432 of file optimizable_graph.h.
Referenced by g2o::SparseOptimizer::computeInitialGuess(), g2o::EstimatePropagatorCost::operator()(), and g2o::EstimatePropagatorCostOdometry::operator()().
|
inlineprotected |
Definition at line 473 of file optimizable_graph.h.
Referenced by g2o::EdgeProjectXYZ2UV::EdgeProjectXYZ2UV(), g2o::EdgeProjectXYZ2UVU::EdgeProjectXYZ2UVU(), g2o::EdgeSE2Offset::EdgeSE2Offset(), g2o::tutorial::EdgeSE2PointXY::EdgeSE2PointXY(), g2o::EdgeSE2PointXYOffset::EdgeSE2PointXYOffset(), g2o::EdgeSE3Line3D::EdgeSE3Line3D(), g2o::deprecated::EdgeSE3Offset::EdgeSE3Offset(), g2o::EdgeSE3Offset::EdgeSE3Offset(), g2o::EdgeSE3PointXYZ::EdgeSE3PointXYZ(), g2o::deprecated::EdgeSE3PointXYZ::EdgeSE3PointXYZ(), g2o::EdgeSE3PointXYZDepth::EdgeSE3PointXYZDepth(), g2o::deprecated::EdgeSE3PointXYZDepth::EdgeSE3PointXYZDepth(), g2o::EdgeSE3PointXYZDisparity::EdgeSE3PointXYZDisparity(), g2o::deprecated::EdgeSE3PointXYZDisparity::EdgeSE3PointXYZDisparity(), g2o::deprecated::EdgeSE3Prior::EdgeSE3Prior(), and g2o::EdgeSE3Prior::EdgeSE3Prior().
|
inline |
the internal ID of the edge
Definition at line 452 of file optimizable_graph.h.
References graph.
Referenced by g2o::OptimizableGraph::EdgeIDCompare::operator()().
|
inline |
returns the level of the edge
Definition at line 435 of file optimizable_graph.h.
Referenced by g2o::BackBoneTreeAction::init(), main(), g2o::EdgeTypesCostFunction::operator()(), and g2o::OptimizableGraph::save().
|
pure virtual |
Linearizes the constraint in the edge in the manifold space, and store the result in the given workspace
Implemented in g2o::BaseMultiEdge<-1, E >, 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::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::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 >.
Referenced by g2o::BlockSolver< Traits >::buildSystem(), g2o::StructureOnlySolver< PointDoF >::calc(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizerIncremental::updateInitialization().
|
pure virtual |
maps the internal matrix to some external memory location, you need to provide the memory before calling constructQuadraticForm
d | the memory location to which we map |
i | index of the vertex i |
j | index of the vertex j (j > i, upper triangular fashion) |
rowMajor | if true, will write in rowMajor order to the block. Since EIGEN is columnMajor by default, this results in writing the transposed |
Implemented in g2o::BaseMultiEdge<-1, E >, 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::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::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 >.
Referenced by g2o::BlockSolver< Traits >::buildStructure(), g2o::SparseOptimizerIncremental::updateInitialization(), and g2o::BlockSolver< Traits >::updateStructure().
|
virtual |
returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;
Reimplemented in g2o::EdgeSBACam, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Segment2DPointLine, g2o::EdgeSE2Segment2DLine, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeSE2, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3Line3D, g2o::EdgeSE2Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE2Segment2D, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeLine2D, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2Line2D, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE2Prior, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgePointXYZ, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2XYPrior, and g2o::EdgeSE3.
Definition at line 202 of file optimizable_graph.cpp.
|
inline |
Definition at line 459 of file optimizable_graph.h.
Referenced by g2o::EdgeCreator::createEdge().
|
inline |
Definition at line 458 of file optimizable_graph.h.
Referenced by g2o::EdgeProjectPSI2UV::computeError(), g2o::EdgeProjectXYZ2UV::linearizeOplus(), g2o::EdgeProjectPSI2UV::linearizeOplus(), and g2o::EdgeSE3Offset::write().
|
pure virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implemented in g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVU, GPSObservationEdgePositionVelocity3D, g2o::Edge_V_V_GICP, g2o::EdgeProjectPSI2UV, g2o::EdgeProjectP2MC, EdgeObservationBAL, TargetOdometry3DEdge, g2o::EdgeProjectXYZ2UV, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSE3Expmap, EdgePointOnCircle, g2o::EdgeSE2Segment2DPointLine, EdgeCalib, g2o::EdgeSE2Segment2DLine, EdgePointOnCurve, g2o::EdgeSim3, GPSObservationPosition3DEdge, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Line2D, g2o::EdgeSE2Segment2D, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2SensorCalib, g2o::EdgeSE2Prior, g2o::EdgeSE2OdomDifferentialCalib, g2o::EdgeSE2XYPrior, g2o::EdgeSE3PlaneSensorCalib, g2o::tutorial::EdgeSE2, g2o::EdgeSE2PureCalib, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE2, g2o::tutorial::EdgeSE2PointXY, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgeLine2D, g2o::EdgePointXYZ, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2Offset, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE3Offset, g2o::EdgeSE3Calib, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::EdgeSE3Euler, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, g2o::EdgeSE3, and g2o::EdgeSE2TwoPointsXY.
Referenced by g2o::OptimizableGraph::setFixed().
|
inline |
Definition at line 460 of file optimizable_graph.h.
Referenced by g2o::EdgeProjectXYZ2UV::EdgeProjectXYZ2UV(), g2o::EdgeProjectXYZ2UVU::EdgeProjectXYZ2UVU(), g2o::EdgeSE2Offset::EdgeSE2Offset(), g2o::tutorial::EdgeSE2PointXY::EdgeSE2PointXY(), g2o::EdgeSE2PointXYOffset::EdgeSE2PointXYOffset(), g2o::EdgeSE3Line3D::EdgeSE3Line3D(), g2o::deprecated::EdgeSE3Offset::EdgeSE3Offset(), g2o::EdgeSE3Offset::EdgeSE3Offset(), g2o::EdgeSE3PointXYZ::EdgeSE3PointXYZ(), g2o::deprecated::EdgeSE3PointXYZ::EdgeSE3PointXYZ(), g2o::EdgeSE3PointXYZDepth::EdgeSE3PointXYZDepth(), g2o::deprecated::EdgeSE3PointXYZDepth::EdgeSE3PointXYZDepth(), g2o::EdgeSE3PointXYZDisparity::EdgeSE3PointXYZDisparity(), g2o::deprecated::EdgeSE3PointXYZDisparity::EdgeSE3PointXYZDisparity(), g2o::deprecated::EdgeSE3Prior::EdgeSE3Prior(), and g2o::EdgeSE3Prior::EdgeSE3Prior().
|
protected |
Definition at line 122 of file cache.h.
References g2o::OptimizableGraph::Vertex::cacheContainer(), g2o::CacheContainer::createCache(), and g2o::CacheContainer::findCache().
Referenced by 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::deprecated::EdgeSE3Offset::resolveCaches(), g2o::EdgeSE3PointXYZ::resolveCaches(), g2o::EdgeSE3PointXYZDisparity::resolveCaches(), and g2o::deprecated::EdgeSE3PointXYZDisparity::resolveCaches().
|
protectedvirtual |
Reimplemented in g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeSE3PointXYZDisparity, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZ, g2o::EdgeSE2PointXYOffset, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE2Offset, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE3Line3D, g2o::EdgeSE3Offset, and g2o::tutorial::EdgeSE2PointXY.
Definition at line 188 of file optimizable_graph.cpp.
Referenced by g2o::OptimizableGraph::addEdge(), and g2o::OptimizableGraph::setEdgeVertex().
|
protected |
Definition at line 159 of file optimizable_graph.cpp.
References __PRETTY_FUNCTION__, _parameterIds, _parameters, _parameterTypes, graph(), and g2o::OptimizableGraph::parameter().
Referenced by g2o::OptimizableGraph::addEdge(), and g2o::OptimizableGraph::setEdgeVertex().
|
inline |
if NOT NULL, error of this edge will be robustifed with the kernel
Definition at line 383 of file optimizable_graph.h.
Referenced by g2o::SparseOptimizer::activeRobustChi2(), gnudump_edges(), gnudump_features(), main(), InvChi2CostFunction::operator()(), and MainWindow::setRobustKernel().
|
inline |
sets the level of the edge
Definition at line 437 of file optimizable_graph.h.
Referenced by g2o::assignHierarchicalEdges(), and g2o::computeSimpleStars().
|
virtual |
sets the measurement from an array of double
Reimplemented in g2o::EdgeSBACam, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Segment2DPointLine, g2o::EdgeSE2Segment2DLine, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2, g2o::EdgeSE2Offset, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE2Prior, g2o::EdgeSE2Segment2D, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeLine2D, g2o::EdgeSE3PointXYZ, g2o::EdgeSE2Line2D, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgePointXYZ, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2PointXY, g2o::EdgeSE2XYPrior, and g2o::EdgeSE3.
Definition at line 192 of file optimizable_graph.cpp.
|
virtual |
sets the estimate to have a zero error, based on the current value of the state variables returns false if not supported.
Reimplemented in g2o::EdgeSBACam, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Segment2DPointLine, g2o::EdgeSE2Segment2DLine, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeSE2, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE2Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE2Segment2D, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeLine2D, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3Prior, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2Line2D, g2o::EdgeSE3PointXYZDepth, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgePointXYZ, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE3Offset, g2o::EdgeSE3, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, and g2o::EdgeSE2TwoPointsXY.
Definition at line 207 of file optimizable_graph.cpp.
Referenced by g2o::EdgeLabeler::labelEdge().
bool g2o::OptimizableGraph::Edge::setParameterId | ( | int | argNum, |
int | paramId | ||
) |
Definition at line 149 of file optimizable_graph.cpp.
References _parameterIds, and _parameters.
Referenced by g2o::EdgeCreator::createEdge(), main(), Robot::move(), g2o::deprecated::EdgeSE3Prior::read(), g2o::EdgeSE3Prior::read(), g2o::EdgeSE3PointXYZDepth::read(), g2o::EdgeSE3PointXYZ::read(), g2o::deprecated::EdgeSE3PointXYZDepth::read(), g2o::deprecated::EdgeSE3Offset::read(), g2o::EdgeSE2Offset::read(), g2o::deprecated::EdgeSE3PointXYZ::read(), g2o::EdgeSE2PointXYOffset::read(), g2o::EdgeSE3Offset::read(), g2o::EdgeSE3Line3D::read(), g2o::EdgeSE3PointXYZDisparity::read(), g2o::deprecated::EdgeSE3PointXYZDisparity::read(), g2o::tutorial::EdgeSE2PointXY::read(), g2o::EdgeProjectXYZ2UV::read(), g2o::EdgeProjectPSI2UV::read(), g2o::SensorPose3DOffset::sense(), g2o::SensorPointXYZ::sense(), g2o::SensorPointXYZDepth::sense(), g2o::SensorSE3Prior::sense(), g2o::SensorPointXYZDisparity::sense(), and g2o::SensorPointXYOffset::sense().
void g2o::OptimizableGraph::Edge::setRobustKernel | ( | RobustKernel * | ptr | ) |
specify the robust kernel to be used in this edge
Definition at line 181 of file optimizable_graph.cpp.
References _robustKernel.
Referenced by main(), and MainWindow::setRobustKernel().
|
pure virtual |
write the vertex to a stream
Implemented in g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVU, GPSObservationEdgePositionVelocity3D, g2o::Edge_V_V_GICP, EdgeObservationBAL, g2o::EdgeProjectPSI2UV, g2o::EdgeProjectP2MC, TargetOdometry3DEdge, g2o::EdgeProjectXYZ2UV, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSE3Expmap, EdgePointOnCircle, g2o::EdgeSE2Segment2DPointLine, EdgeCalib, EdgePointOnCurve, g2o::EdgeSE2Segment2DLine, GPSObservationPosition3DEdge, g2o::EdgeSim3, g2o::deprecated::EdgeSE3, g2o::EdgeSE2Line2D, g2o::EdgeSE2Segment2D, g2o::EdgeLine2DPointXY, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2SensorCalib, g2o::EdgeSE2Prior, g2o::EdgeSE2OdomDifferentialCalib, g2o::EdgeSE2XYPrior, g2o::EdgeSE3PlaneSensorCalib, g2o::tutorial::EdgeSE2, g2o::EdgeSE2PureCalib, g2o::EdgeSE2PointXYCalib, g2o::EdgeSE2, g2o::tutorial::EdgeSE2PointXY, g2o::deprecated::EdgeSE3PointXYZDisparity, g2o::EdgeLine3D, g2o::EdgePlane, g2o::EdgePointXY, g2o::EdgeLine2D, g2o::EdgePointXYZ, g2o::EdgeSE3PointXYZDisparity, g2o::EdgeSE3Line3D, g2o::deprecated::EdgeSE3Offset, g2o::deprecated::EdgeSE3PointXYZ, g2o::EdgeSE2Offset, g2o::EdgeSE2PointXYOffset, g2o::EdgeSE3Offset, g2o::EdgeSE3Calib, g2o::deprecated::EdgeSE3PointXYZDepth, g2o::EdgeSE3PointXYZ, g2o::EdgeSE3PointXYZDepth, g2o::EdgeSE3Prior, g2o::EdgeSE3Euler, g2o::deprecated::EdgeSE3Prior, g2o::EdgeSE2LotsOfXY, g2o::EdgeSE3LotsOfXYZ, g2o::EdgeSE3, and g2o::EdgeSE2TwoPointsXY.
Referenced by g2o::OptimizableGraph::saveEdge().
|
friend |
Definition at line 351 of file optimizable_graph.h.
|
protected |
Definition at line 470 of file optimizable_graph.h.
|
protected |
Definition at line 466 of file optimizable_graph.h.
Referenced by g2o::BaseEdge< D, Eigen::Vector2d >::BaseEdge(), g2o::BaseEdge< D, Eigen::Vector2d >::rank(), and g2o::BaseEdge<-1, E >::rank().
|
protected |
Definition at line 469 of file optimizable_graph.h.
Referenced by g2o::OptimizableGraph::addEdge().
|
protected |
Definition at line 467 of file optimizable_graph.h.
|
protected |
Definition at line 492 of file optimizable_graph.h.
Referenced by resolveParameters(), and setParameterId().
|
protected |
Definition at line 491 of file optimizable_graph.h.
Referenced by g2o::OptimizableGraph::clearParameters(), resolveParameters(), g2o::OptimizableGraph::save(), g2o::OptimizableGraph::setFixed(), and setParameterId().
|
protected |
Definition at line 490 of file optimizable_graph.h.
Referenced by resolveParameters().
|
protected |
Definition at line 468 of file optimizable_graph.h.
Referenced by setRobustKernel(), and ~Edge().