27 #ifndef G2O_EDGE_SE3_PRIOR_H_ 28 #define G2O_EDGE_SE3_PRIOR_H_ 43 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
45 virtual bool read(std::istream& is);
46 virtual bool write(std::ostream& os)
const;
52 virtual void linearizeOplus();
56 _inverseMeasurement = m.inverse();
60 Eigen::Map<const Vector7d> v(d);
62 _inverseMeasurement = _measurement.inverse();
67 Eigen::Map<Vector7d> v(d);
74 virtual bool setMeasurementFromState() ;
84 virtual bool resolveCaches();
virtual bool setMeasurementData(const double *d)
caching the offset related to a vertex
Isometry3D fromVectorQT(const Vector7d &v)
std::set< Vertex * > VertexSet
ParameterSE3Offset * _offsetParam
virtual int measurementDimension() const
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
#define G2O_TYPES_SLAM3D_API
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
A general case Vertex for optimization.
virtual bool getMeasurementData(double *d) const
Isometry3D _inverseMeasurement
virtual void setMeasurement(const Isometry3D &m)
Vector7d toVectorQT(const Isometry3D &t)