g2o
|
edge from a track to a depth camera node using a disparity measurement More...
#include <edge_se3_pointxyz_disparity.h>
Public Member Functions | |
EdgeSE3PointXYZDisparity () | |
virtual bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex More... | |
virtual bool | write (std::ostream &os) const |
write the vertex to a stream More... | |
void | computeError () |
virtual void | linearizeOplus () |
virtual void | setMeasurement (const Vector3D &m) |
virtual bool | setMeasurementData (const double *d) |
virtual bool | getMeasurementData (double *d) const |
virtual int | measurementDimension () const |
virtual bool | setMeasurementFromState () |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
const ParameterCamera * | cameraParameter () const |
Public Member Functions inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ > | |
BaseBinaryEdge () | |
virtual OptimizableGraph::Vertex * | createFrom () |
virtual OptimizableGraph::Vertex * | createTo () |
virtual OptimizableGraph::Vertex * | createVertex (int i) |
virtual void | resize (size_t size) |
virtual bool | allVerticesFixed () const |
virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace) |
const JacobianXiOplusType & | jacobianOplusXi () const |
returns the result of the linearization in the manifold space for the node xi More... | |
const JacobianXjOplusType & | jacobianOplusXj () const |
returns the result of the linearization in the manifold space for the node xj More... | |
virtual void | constructQuadraticForm () |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor) |
Public Member Functions inherited from g2o::BaseEdge< D, Vector3D > | |
BaseEdge () | |
virtual | ~BaseEdge () |
virtual double | chi2 () const |
computes the chi2 based on the cached error value, only valid after computeError has been called. More... | |
virtual const double * | errorData () const |
returns the error vector cached after calling the computeError; More... | |
virtual double * | errorData () |
const ErrorVector & | error () const |
ErrorVector & | error () |
EIGEN_STRONG_INLINE const InformationType & | information () const |
information matrix of the constraint More... | |
EIGEN_STRONG_INLINE InformationType & | information () |
EIGEN_STRONG_INLINE void | setInformation (const InformationType &information) |
virtual const double * | informationData () const |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXD> More... | |
virtual double * | informationData () |
EIGEN_STRONG_INLINE const Measurement & | measurement () const |
accessor functions for the measurement represented by the edge More... | |
virtual int | rank () const |
Public Member Functions inherited from g2o::OptimizableGraph::Edge | |
Edge () | |
virtual | ~Edge () |
virtual Edge * | clone () const |
RobustKernel * | robustKernel () const |
if NOT NULL, error of this edge will be robustifed with the kernel More... | |
void | setRobustKernel (RobustKernel *ptr) |
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()) | |
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... | |
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) |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | |
Private Member Functions | |
virtual bool | resolveCaches () |
Private Attributes | |
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > | J |
ParameterCamera * | params |
CacheCamera * | cache |
Additional Inherited Members | |
Public Types inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ > | |
typedef VertexSE3 | VertexXiType |
typedef VertexPointXYZ | VertexXjType |
typedef BaseEdge< D, Vector3D >::Measurement | Measurement |
typedef Eigen::Matrix< double, D, Di, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType | JacobianXiOplusType |
typedef Eigen::Matrix< double, D, Dj, D==1?Eigen::RowMajor:Eigen::ColMajor >::AlignedMapType | JacobianXjOplusType |
typedef BaseEdge< D, Vector3D >::ErrorVector | ErrorVector |
typedef BaseEdge< D, Vector3D >::InformationType | InformationType |
typedef Eigen::Map< Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Di, Dj, Di==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > | HessianBlockType |
typedef Eigen::Map< Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >, Eigen::Matrix< double, Dj, Di, Dj==1?Eigen::RowMajor:Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > | HessianBlockTransposedType |
Public Types inherited from g2o::BaseEdge< D, Vector3D > | |
typedef Vector3D | Measurement |
typedef Eigen::Matrix< double, D, 1, Eigen::ColMajor > | ErrorVector |
typedef Eigen::Matrix< double, D, D, Eigen::ColMajor > | InformationType |
Static Public Attributes inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ > | |
static const int | Di |
static const int | Dj |
static const int | Dimension |
Static Public Attributes inherited from g2o::BaseEdge< D, Vector3D > | |
static const int | Dimension |
Protected Member Functions inherited from g2o::BaseEdge< D, Vector3D > | |
InformationType | robustInformation (const Vector3D &rho) |
Protected Member Functions inherited from g2o::OptimizableGraph::Edge | |
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 () |
Protected Attributes inherited from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ > | |
bool | _hessianRowMajor |
HessianBlockType | _hessian |
HessianBlockTransposedType | _hessianTransposed |
JacobianXiOplusType | _jacobianOplusXi |
JacobianXjOplusType | _jacobianOplusXj |
Protected Attributes inherited from g2o::BaseEdge< D, Vector3D > | |
Measurement | _measurement |
InformationType | _information |
ErrorVector | _error |
Protected Attributes inherited from g2o::OptimizableGraph::Edge | |
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 |
edge from a track to a depth camera node using a disparity measurement
the disparity measurement is normalized: disparity / (focal_x * baseline)
Definition at line 45 of file edge_se3_pointxyz_disparity.h.
g2o::EdgeSE3PointXYZDisparity::EdgeSE3PointXYZDisparity | ( | ) |
Definition at line 42 of file edge_se3_pointxyz_disparity.cpp.
References g2o::BaseEdge< D, Vector3D >::information(), g2o::OptimizableGraph::Edge::installParameter(), J, params, and g2o::OptimizableGraph::Edge::resizeParameters().
|
inline |
Definition at line 87 of file edge_se3_pointxyz_disparity.h.
Referenced by initialEstimate().
|
virtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 97 of file edge_se3_pointxyz_disparity.cpp.
References g2o::BaseEdge< D, Vector3D >::_error, g2o::BaseEdge< D, Vector3D >::_measurement, g2o::HyperGraph::Edge::_vertices, cache, g2o::BaseVertex< D, T >::estimate(), and g2o::CacheCamera::w2i().
|
inlinevirtual |
writes the measurement to an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 69 of file edge_se3_pointxyz_disparity.h.
|
virtual |
set the estimate of the to vertex, based on the estimate of the from vertices in the edge.
Reimplemented from g2o::BaseEdge< D, Vector3D >.
Definition at line 195 of file edge_se3_pointxyz_disparity.cpp.
References g2o::BaseEdge< D, Vector3D >::_measurement, g2o::HyperGraph::Edge::_vertices, cameraParameter(), g2o::BaseVertex< D, T >::estimate(), g2o::ParameterCamera::invKcam(), LANDMARK_EDGE_COLOR, g2o::ParameterSE3Offset::offset(), params, g2o::BaseVertex< D, T >::setEstimate(), and g2o::HyperGraph::Edge::vertices().
|
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 from g2o::OptimizableGraph::Edge.
Definition at line 79 of file edge_se3_pointxyz_disparity.h.
|
virtual |
Linearizes the oplus operator in the vertex, and stores the result in temporary variables _jacobianOplusXi and _jacobianOplusXj
Reimplemented from g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >.
Definition at line 126 of file edge_se3_pointxyz_disparity.cpp.
References g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >::_jacobianOplusXi, g2o::BaseBinaryEdge< 3, Vector3D, VertexSE3, VertexPointXYZ >::_jacobianOplusXj, g2o::HyperGraph::Edge::_vertices, cache, g2o::BaseVertex< D, T >::estimate(), J, g2o::ParameterCamera::Kcam_inverseOffsetR(), params, g2o::CacheCamera::w2i(), and g2o::CacheSE3Offset::w2l().
|
inlinevirtual |
returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 75 of file edge_se3_pointxyz_disparity.h.
|
virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Edge.
Definition at line 60 of file edge_se3_pointxyz_disparity.cpp.
References g2o::BaseEdge< D, Vector3D >::information(), setMeasurement(), and g2o::OptimizableGraph::Edge::setParameterId().
|
privatevirtual |
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 52 of file edge_se3_pointxyz_disparity.cpp.
References g2o::HyperGraph::Edge::_vertices, cache, params, and g2o::OptimizableGraph::Edge::resolveCache().
|
inlinevirtual |
Reimplemented from g2o::BaseEdge< D, Vector3D >.
Definition at line 59 of file edge_se3_pointxyz_disparity.h.
Referenced by g2o::SensorPointXYZDisparity::addNoise(), main(), and read().
|
inlinevirtual |
sets the measurement from an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 63 of file edge_se3_pointxyz_disparity.h.
|
virtual |
sets the estimate to have a zero error, based on the current value of the state variables returns false if not supported.
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 173 of file edge_se3_pointxyz_disparity.cpp.
References g2o::BaseEdge< D, Vector3D >::_measurement, g2o::HyperGraph::Edge::_vertices, cache, g2o::BaseVertex< D, T >::estimate(), and g2o::CacheCamera::w2i().
Referenced by g2o::SensorPointXYZDisparity::sense().
|
virtual |
write the vertex to a stream
Implements g2o::OptimizableGraph::Edge.
Definition at line 86 of file edge_se3_pointxyz_disparity.cpp.
References g2o::Parameter::id(), g2o::BaseEdge< D, Vector3D >::information(), g2o::BaseEdge< D, Vector3D >::measurement(), and params.
|
private |
Definition at line 92 of file edge_se3_pointxyz_disparity.h.
Referenced by computeError(), linearizeOplus(), resolveCaches(), and setMeasurementFromState().
g2o::EdgeSE3PointXYZDisparity::EIGEN_MAKE_ALIGNED_OPERATOR_NEW |
Definition at line 47 of file edge_se3_pointxyz_disparity.h.
|
private |
Definition at line 89 of file edge_se3_pointxyz_disparity.h.
Referenced by EdgeSE3PointXYZDisparity(), and linearizeOplus().
|
private |
Definition at line 91 of file edge_se3_pointxyz_disparity.h.
Referenced by EdgeSE3PointXYZDisparity(), initialEstimate(), linearizeOplus(), resolveCaches(), and write().