27#ifndef G2O_EDGE_SE3_PRIOR_H_
28#define G2O_EDGE_SE3_PRIOR_H_
45 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 virtual bool read(std::istream& is);
48 virtual bool write(std::ostream& os)
const;
54 virtual void linearizeOplus();
58 _inverseMeasurement = m.inverse();
62 Eigen::Map<const Vector7> v(d);
63 _measurement = internal::fromVectorQT(v);
64 _inverseMeasurement = _measurement.inverse();
69 Eigen::Map<Vector7> v(d);
70 v = internal::toVectorQT(_measurement);
76 virtual bool setMeasurementFromState();
89 virtual bool resolveCaches();
caching the offset related to a vertex
virtual bool setMeasurementData(const double *d)
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *)
ParameterSE3Offset * _offsetParam
virtual void setMeasurement(const Isometry3 &m)
virtual int measurementDimension() const
virtual bool getMeasurementData(double *d) const
Isometry3 _inverseMeasurement
std::set< Vertex * > VertexSet
A general case Vertex for optimization.
#define G2O_TYPES_SLAM3D_API
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3