#include <optimizable_graph.h>
Public Member Functions | |
virtual double | chi2 () const =0 |
computes the chi2 based on the cached error value, only valid after computeError has been called. | |
virtual Edge * | clone () const |
virtual void | computeError ()=0 |
virtual void | constructQuadraticForm ()=0 |
virtual Vertex * | createFrom () |
virtual Vertex * | createTo () |
int | dimension () const |
returns the dimensions of the error function | |
Edge () | |
virtual const double * | errorData () const =0 |
returns the error vector cached after calling the computeError; | |
virtual double * | errorData ()=0 |
virtual bool | getMeasurementData (double *m) const |
double | huberWidth () const |
width of the robust huber kernel | |
virtual const double * | informationData () const =0 |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd> | |
virtual double * | informationData ()=0 |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)=0 |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
long long | internalId () const |
the internal ID of the edge | |
int | level () const |
returns the level of the edge | |
virtual void | linearizeOplus ()=0 |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor)=0 |
virtual int | measurementDimension () const |
virtual bool | read (std::istream &is)=0 |
read the vertex from a stream, i.e., the internal state of the vertex | |
virtual void | robustifyError ()=0 |
bool | robustKernel () const |
if true, error will be robustifed (not for computing Jacobians) | |
void | setHuberWidth (double hw) |
void | setLevel (int l) |
sets the level of the edge | |
virtual bool | setMeasurementData (const double *m) |
virtual bool | setMeasurementFromState () |
void | setRobustKernel (bool rk) |
virtual bool | write (std::ostream &os) const =0 |
write the vertex to a stream | |
Protected Member Functions | |
double | sqrtOfHuberByNrm (double delta, double b) const |
Protected Attributes | |
int | _dimension |
double | _huberWidth |
long long | _internalId |
int | _level |
bool | _robustKernel |
Friends | |
struct | OptimizableGraph |
Definition at line 264 of file optimizable_graph.h.
Definition at line 89 of file optimizable_graph.cpp.
virtual double g2o::OptimizableGraph::Edge::chi2 | ( | ) | const [pure virtual] |
computes the chi2 based on the cached error value, only valid after computeError has been called.
Implemented in g2o::BaseEdge< D, E >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
OptimizableGraph::Edge * g2o::OptimizableGraph::Edge::clone | ( | void | ) | const [virtual] |
Definition at line 115 of file optimizable_graph.cpp.
virtual void g2o::OptimizableGraph::Edge::computeError | ( | ) | [pure virtual] |
Implemented in g2o::EdgeProjectXYZ2UV, g2o::EdgeProjectXYZ2UV, g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectXYZ2UVU, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVQ, g2o::EdgeProjectXYZ2UV, g2o::Edge_V_V_GICP, g2o::EdgeProjectP2MC, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSE3Expmap, g2o::EdgeSim3, g2o::EdgeSE3, g2o::EdgeSE2Multi, g2o::tutorial::EdgeSE2, g2o::EdgeSE2PointXYCalib, g2o::tutorial::EdgeSE2PointXY, g2o::EdgeSE2, g2o::EdgeSE2Prior, g2o::EdgeSE2PointXY, and g2o::EdgeSE2PointXYBearing.
virtual void g2o::OptimizableGraph::Edge::constructQuadraticForm | ( | ) | [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::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 2, Vector2d >, g2o::BaseMultiEdge< 2, Eigen::Vector2d >, g2o::BaseUnaryEdge< D, E, VertexXi >, and g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
virtual Vertex* g2o::OptimizableGraph::Edge::createFrom | ( | ) | [inline, virtual] |
Reimplemented in g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, and g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >.
Definition at line 359 of file optimizable_graph.h.
virtual Vertex* g2o::OptimizableGraph::Edge::createTo | ( | ) | [inline, virtual] |
Reimplemented in g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, and g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >.
Definition at line 360 of file optimizable_graph.h.
int g2o::OptimizableGraph::Edge::dimension | ( | ) | const [inline] |
returns the dimensions of the error function
Definition at line 357 of file optimizable_graph.h.
virtual const double* g2o::OptimizableGraph::Edge::errorData | ( | ) | const [pure virtual] |
returns the error vector cached after calling the computeError;
Implemented in g2o::BaseEdge< D, E >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
virtual double* g2o::OptimizableGraph::Edge::errorData | ( | ) | [pure virtual] |
bool g2o::OptimizableGraph::Edge::getMeasurementData | ( | double * | m | ) | const [virtual] |
writes the measurement to an array of double
Reimplemented in g2o::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, and g2o::EdgeSE2Prior.
Definition at line 100 of file optimizable_graph.cpp.
double g2o::OptimizableGraph::Edge::huberWidth | ( | ) | const [inline] |
width of the robust huber kernel
Definition at line 303 of file optimizable_graph.h.
virtual const double* g2o::OptimizableGraph::Edge::informationData | ( | ) | const [pure virtual] |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd>
Implemented in g2o::BaseEdge< D, E >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
virtual double* g2o::OptimizableGraph::Edge::informationData | ( | ) | [pure virtual] |
virtual void g2o::OptimizableGraph::Edge::initialEstimate | ( | const OptimizableGraph::VertexSet & | from, |
OptimizableGraph::Vertex * | to | ||
) | [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::EdgeSim3, g2o::BaseEdge< D, E >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, g2o::BaseEdge< D, Eigen::Vector2d >, g2o::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2PointXY, g2o::EdgeSE2Prior, g2o::BaseUnaryEdge< D, E, VertexXi >, g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >, g2o::OnlineEdgeSE3, g2o::OnlineEdgeSE2, and g2o::EdgeSE2PointXYCalib.
virtual double g2o::OptimizableGraph::Edge::initialEstimatePossible | ( | const OptimizableGraph::VertexSet & | from, |
OptimizableGraph::Vertex * | to | ||
) | [inline, virtual] |
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, g2o::EdgeSim3, g2o::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2Prior, and g2o::EdgeSE2PointXYCalib.
Definition at line 349 of file optimizable_graph.h.
long long g2o::OptimizableGraph::Edge::internalId | ( | ) | const [inline] |
the internal ID of the edge
Definition at line 368 of file optimizable_graph.h.
int g2o::OptimizableGraph::Edge::level | ( | ) | const [inline] |
returns the level of the edge
Definition at line 352 of file optimizable_graph.h.
virtual void g2o::OptimizableGraph::Edge::linearizeOplus | ( | ) | [pure virtual] |
Linearizes the constraint in the edge in the manifold space, and stores the result in temporary variables _jacobianOplusXi and _jacobianOplusXj (see base_edge).
Implemented in g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectP2SC, g2o::Edge_V_V_GICP, g2o::EdgeProjectXYZ2UVQ, g2o::EdgeProjectP2MC, g2o::EdgeProjectXYZ2UV, g2o::EdgeSE3Expmap, g2o::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2PointXY, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 2, Vector2d >, g2o::BaseMultiEdge< 2, Eigen::Vector2d >, g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseUnaryEdge< D, E, VertexXi >, and g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
virtual void g2o::OptimizableGraph::Edge::mapHessianMemory | ( | double * | d, |
int | i, | ||
int | j, | ||
bool | rowMajor | ||
) | [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::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 1, double, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSCam >, g2o::BaseBinaryEdge< 3, Vector3d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, EdgeGICP, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 1, double, VertexSE2, VertexPointXY >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3, VertexSE3 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexCam, VertexCam >, g2o::BaseBinaryEdge< 3, SE2, VertexSE2, VertexSE2 >, g2o::BaseBinaryEdge< 6, SE3Quat, VertexSE3Expmap, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexCam >, g2o::BaseBinaryEdge< 2, Vector2d, VertexPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Eigen::Vector2d, VertexSE2, VertexPointXY >, g2o::BaseMultiEdge< D, E >, g2o::BaseMultiEdge< 3, SE2 >, g2o::BaseMultiEdge< 2, Vector2d >, g2o::BaseMultiEdge< 2, Eigen::Vector2d >, g2o::BaseUnaryEdge< D, E, VertexXi >, and g2o::BaseUnaryEdge< 3, SE2, VertexSE2 >.
int g2o::OptimizableGraph::Edge::measurementDimension | ( | ) | const [virtual] |
returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;
Reimplemented in g2o::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2Prior, g2o::EdgeSE2PointXY, and g2o::EdgeSE2PointXYBearing.
Definition at line 105 of file optimizable_graph.cpp.
virtual bool g2o::OptimizableGraph::Edge::read | ( | std::istream & | is | ) | [pure virtual] |
read the vertex from a stream, i.e., the internal state of the vertex
Implemented in g2o::EdgeProjectXYZ2UV, g2o::EdgeProjectXYZ2UV, g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectXYZ2UVU, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVQ, g2o::EdgeProjectXYZ2UV, g2o::Edge_V_V_GICP, g2o::EdgeProjectP2MC, g2o::EdgeSE3Expmap, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSim3, g2o::EdgeSE3, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2Prior, g2o::tutorial::EdgeSE2, g2o::EdgeSE2PointXYCalib, g2o::tutorial::EdgeSE2PointXY, g2o::EdgeSE2, and g2o::EdgeSE2Multi.
virtual void g2o::OptimizableGraph::Edge::robustifyError | ( | ) | [pure virtual] |
robustify the error of the edge using an robust kernel/M-estimator this is only called if robustKernel==true
Implemented in g2o::BaseEdge< D, E >, g2o::BaseEdge< D, SE3Quat >, g2o::BaseEdge< D, double >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, g2o::BaseEdge< D, EdgeGICP >, g2o::BaseEdge< D, Sim3 >, g2o::BaseEdge< D, SE2 >, and g2o::BaseEdge< D, Eigen::Vector2d >.
bool g2o::OptimizableGraph::Edge::robustKernel | ( | ) | const [inline] |
if true, error will be robustifed (not for computing Jacobians)
Definition at line 299 of file optimizable_graph.h.
void g2o::OptimizableGraph::Edge::setHuberWidth | ( | double | hw | ) | [inline] |
Definition at line 304 of file optimizable_graph.h.
void g2o::OptimizableGraph::Edge::setLevel | ( | int | l | ) | [inline] |
sets the level of the edge
Definition at line 354 of file optimizable_graph.h.
bool g2o::OptimizableGraph::Edge::setMeasurementData | ( | const double * | m | ) | [virtual] |
sets the measurement from an array of double
Reimplemented in g2o::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2Prior, and g2o::EdgeSE2PointXY.
Definition at line 95 of file optimizable_graph.cpp.
bool g2o::OptimizableGraph::Edge::setMeasurementFromState | ( | ) | [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::EdgeSE3, g2o::EdgeSE2, g2o::EdgeSE2PointXY, and g2o::EdgeSE2PointXYBearing.
Definition at line 110 of file optimizable_graph.cpp.
void g2o::OptimizableGraph::Edge::setRobustKernel | ( | bool | rk | ) | [inline] |
Definition at line 300 of file optimizable_graph.h.
double g2o::OptimizableGraph::Edge::sqrtOfHuberByNrm | ( | double | delta, |
double | b | ||
) | const [inline, protected] |
Square root of huber cost function devided by delta
Let delta be the generalized 2-norm of the error e, thus delta = sqrt(e*Omega*e).
Let rho be the Huber cost function, rho(x) = if |x|<b : x^2 | else: 2b|x|-b^2 (Thus, b is the "width" of the quadratic component.)
This function computes "sqrt(rho(delta))/delta" which can be used as a weight to robustify the error e.
For details: See Hartley, Zisserman: "Multiple View Geometry in Computer Vision", 2nd edition, 2003, pp.616.
Definition at line 393 of file optimizable_graph.h.
virtual bool g2o::OptimizableGraph::Edge::write | ( | std::ostream & | os | ) | const [pure virtual] |
write the vertex to a stream
Implemented in g2o::EdgeProjectXYZ2UV, g2o::EdgeProjectXYZ2UV, g2o::Edge_XYZ_VSC, g2o::EdgeSBAScale, g2o::EdgeSBACam, g2o::EdgeProjectP2MC_Intrinsics, g2o::EdgeProjectXYZ2UVU, g2o::EdgeProjectP2SC, g2o::EdgeProjectXYZ2UVQ, g2o::EdgeProjectXYZ2UV, g2o::Edge_V_V_GICP, g2o::EdgeProjectP2MC, g2o::EdgeSE3Expmap, g2o::EdgeSim3ProjectXYZ, g2o::EdgeSim3, g2o::EdgeSE3, g2o::EdgeSE2PointXY, g2o::EdgeSE2PointXYBearing, g2o::EdgeSE2Prior, g2o::tutorial::EdgeSE2, g2o::EdgeSE2PointXYCalib, g2o::tutorial::EdgeSE2PointXY, g2o::EdgeSE2, and g2o::EdgeSE2Multi.
friend struct OptimizableGraph [friend] |
Definition at line 266 of file optimizable_graph.h.
int g2o::OptimizableGraph::Edge::_dimension [protected] |
Definition at line 371 of file optimizable_graph.h.
double g2o::OptimizableGraph::Edge::_huberWidth [protected] |
Definition at line 374 of file optimizable_graph.h.
long long g2o::OptimizableGraph::Edge::_internalId [protected] |
Definition at line 375 of file optimizable_graph.h.
int g2o::OptimizableGraph::Edge::_level [protected] |
Definition at line 372 of file optimizable_graph.h.
bool g2o::OptimizableGraph::Edge::_robustKernel [protected] |
Definition at line 373 of file optimizable_graph.h.