27 #ifndef RTAB_G2O_EDGE_SE3_PRIOR_XYZ_H 28 #define RTAB_G2O_EDGE_SE3_PRIOR_XYZ_H 30 #include "g2o/types/slam3d/vertex_se3.h" 31 #include "g2o/core/base_unary_edge.h" 32 #include "g2o/types/slam3d/parameter_se3_offset.h" 39 class EdgeSE3XYZPrior :
public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3>
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 Eigen::Map<const Eigen::Vector3d> v(d);
56 Eigen::Map<Eigen::Vector3d> v(d);
63 virtual bool read(std::istream& is);
64 virtual bool write(std::ostream& os)
const;
68 virtual double initialEstimatePossible(
const g2o::OptimizableGraph::VertexSet& , g2o::OptimizableGraph::Vertex* ) {
return 1.;}
69 virtual void initialEstimate(
const g2o::OptimizableGraph::VertexSet& , g2o::OptimizableGraph::Vertex* );
virtual bool read(std::istream &is)
g2o::ParameterSE3Offset * _offsetParam
virtual void setMeasurement(const Eigen::Vector3d &m)
virtual void initialEstimate(const g2o::OptimizableGraph::VertexSet &, g2o::OptimizableGraph::Vertex *)
Prior for a 3D pose with constraints only in xyz direction.
virtual bool setMeasurementData(const double *d)
g2o::CacheSE3Offset * _cache
virtual void computeError()
virtual bool write(std::ostream &os) const
virtual bool getMeasurementData(double *d) const
const g2o::ParameterSE3Offset * offsetParameter()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3XYZPrior()
virtual bool resolveCaches()
virtual bool setMeasurementFromState()
virtual double initialEstimatePossible(const g2o::OptimizableGraph::VertexSet &, g2o::OptimizableGraph::Vertex *)
virtual int measurementDimension() const