g2o
|
#include <edge_se2_segment2d_line.h>
Public Member Functions | |
G2O_TYPES_SLAM2D_ADDONS_API EIGEN_MAKE_ALIGNED_OPERATOR_NEW G2O_TYPES_SLAM2D_ADDONS_API | EdgeSE2Segment2DLine () |
G2O_TYPES_SLAM2D_ADDONS_API double | theta () const |
G2O_TYPES_SLAM2D_ADDONS_API double | rho () const |
G2O_TYPES_SLAM2D_ADDONS_API void | setTheta (double t) |
G2O_TYPES_SLAM2D_ADDONS_API void | setRho (double r) |
G2O_TYPES_SLAM2D_ADDONS_API void | computeError () |
virtual G2O_TYPES_SLAM2D_ADDONS_API bool | setMeasurementData (const double *d) |
virtual G2O_TYPES_SLAM2D_ADDONS_API bool | getMeasurementData (double *d) const |
virtual G2O_TYPES_SLAM2D_ADDONS_API int | measurementDimension () const |
virtual G2O_TYPES_SLAM2D_ADDONS_API bool | setMeasurementFromState () |
virtual G2O_TYPES_SLAM2D_ADDONS_API bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex More... | |
virtual G2O_TYPES_SLAM2D_ADDONS_API bool | write (std::ostream &os) const |
write the vertex to a stream More... | |
Public Member Functions inherited from g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D > | |
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) |
virtual void | linearizeOplus () |
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, Vector2D > | |
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 void | setMeasurement (const Measurement &m) |
virtual int | rank () const |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
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) |
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()) | |
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) |
Additional Inherited Members | |
Public Types inherited from g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D > | |
typedef VertexSE2 | VertexXiType |
typedef VertexSegment2D | VertexXjType |
typedef BaseEdge< D, Vector2D >::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, Vector2D >::ErrorVector | ErrorVector |
typedef BaseEdge< D, Vector2D >::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, Vector2D > | |
typedef Vector2D | 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< 2, Vector2D, VertexSE2, VertexSegment2D > | |
static const int | Di |
static const int | Dj |
static const int | Dimension |
Static Public Attributes inherited from g2o::BaseEdge< D, Vector2D > | |
static const int | Dimension |
Protected Member Functions inherited from g2o::BaseEdge< D, Vector2D > | |
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 () |
virtual bool | resolveCaches () |
Protected Attributes inherited from g2o::BaseBinaryEdge< 2, Vector2D, VertexSE2, VertexSegment2D > | |
bool | _hessianRowMajor |
HessianBlockType | _hessian |
HessianBlockTransposedType | _hessianTransposed |
JacobianXiOplusType | _jacobianOplusXi |
JacobianXjOplusType | _jacobianOplusXj |
Protected Attributes inherited from g2o::BaseEdge< D, Vector2D > | |
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 |
Definition at line 38 of file edge_se2_segment2d_line.h.
g2o::EdgeSE2Segment2DLine::EdgeSE2Segment2DLine | ( | ) |
Definition at line 43 of file edge_se2_segment2d_line.cpp.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 51 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_error, g2o::BaseEdge< D, Vector2D >::_measurement, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::VertexSegment2D::estimateP1(), g2o::VertexSegment2D::estimateP2(), g2o::SE2::inverse(), and g2o::normalize_theta().
|
inlinevirtual |
writes the measurement to an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 73 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_measurement.
|
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 79 of file edge_se2_segment2d_line.h.
|
virtual |
read the vertex from a stream, i.e., the internal state of the vertex
Implements g2o::OptimizableGraph::Edge.
Definition at line 48 of file edge_se2_segment2d_line.cpp.
References g2o::BaseEdge< D, Vector2D >::_information, and g2o::BaseEdge< D, Vector2D >::_measurement.
Referenced by setMeasurementFromState().
|
inline |
Definition at line 45 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_measurement.
|
inlinevirtual |
sets the measurement from an array of double
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 67 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_measurement.
|
inlinevirtual |
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 81 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_measurement, g2o::HyperGraph::Edge::_vertices, g2o::BaseVertex< D, T >::estimate(), g2o::VertexSegment2D::estimateP1(), g2o::VertexSegment2D::estimateP2(), G2O_TYPES_SLAM2D_ADDONS_API, g2o::SE2::inverse(), read(), and write().
Referenced by g2o::SensorSegment2DLine::sense().
|
inline |
Definition at line 48 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_measurement.
|
inline |
Definition at line 47 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_measurement.
|
inline |
Definition at line 44 of file edge_se2_segment2d_line.h.
References g2o::BaseEdge< D, Vector2D >::_measurement.
|
virtual |
write the vertex to a stream
Implements g2o::OptimizableGraph::Edge.
Definition at line 60 of file edge_se2_segment2d_line.cpp.
References g2o::BaseEdge< D, Vector2D >::_information, and g2o::BaseEdge< D, Vector2D >::_measurement.
Referenced by setMeasurementFromState().