prior for an XYZ vertex (VertexPointXYZ) More...
#include <edge_xyz_prior.h>
Public Member Functions | |
void | computeError () |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | EdgeXYZPrior () |
virtual bool | getMeasurementData (double *d) const |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
virtual void | linearizeOplus () |
virtual int | measurementDimension () const |
virtual bool | read (std::istream &is) |
virtual void | setMeasurement (const Vector3d &m) |
virtual bool | setMeasurementData (const double *d) |
virtual bool | setMeasurementFromState () |
virtual bool | write (std::ostream &os) const |
prior for an XYZ vertex (VertexPointXYZ)
Provides a prior for a 3d point vertex. The measurement is represented by a Vector3d with a corresponding 3x3 upper triangle covariance matrix (upper triangle only).
Definition at line 48 of file edge_xyz_prior.h.
g2o::EdgeXYZPrior::EdgeXYZPrior | ( | ) |
Definition at line 86 of file edge_xyz_prior.h.
void g2o::EdgeXYZPrior::computeError | ( | ) |
Definition at line 116 of file edge_xyz_prior.h.
|
inlinevirtual |
Definition at line 70 of file edge_xyz_prior.h.
|
inlinevirtual |
Definition at line 80 of file edge_xyz_prior.h.
|
virtual |
Definition at line 121 of file edge_xyz_prior.h.
|
inlinevirtual |
Definition at line 76 of file edge_xyz_prior.h.
|
virtual |
Definition at line 90 of file edge_xyz_prior.h.
|
inlinevirtual |
Definition at line 60 of file edge_xyz_prior.h.
|
inlinevirtual |
Definition at line 64 of file edge_xyz_prior.h.
|
virtual |
Definition at line 125 of file edge_xyz_prior.h.
|
virtual |
Definition at line 107 of file edge_xyz_prior.h.