27 #ifndef G2O_EDGE_SE2_LINE2D_H 28 #define G2O_EDGE_SE2_LINE2D_H 30 #include "g2o/config.h" 42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51 prediction[0] += iT.
rotation().angle();
53 Vector2D n(cos(prediction[0]), sin(prediction[0]));
55 _error = prediction - _measurement;
66 d[0] = _measurement[0];
67 d[1] = _measurement[1];
78 prediction[0] += iT.
rotation().angle();
80 Vector2D n(cos(prediction[0]), sin(prediction[0]));
82 _measurement = prediction;
86 virtual bool read(std::istream& is);
87 virtual bool write(std::ostream& os)
const;
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
some general case utility functions
std::set< Vertex * > VertexSet
2D pose Vertex, (x,y,theta)
virtual bool setMeasurementData(const double *d)
const Eigen::Rotation2Dd & rotation() const
rotational component
virtual int measurementDimension() const
double normalize_theta(double theta)
A general case Vertex for optimization.
virtual bool setMeasurementFromState()
#define G2O_TYPES_SLAM2D_ADDONS_API
const EstimateType & estimate() const
return the current estimate of the vertex
SE2 inverse() const
invert :-)
const Vector2D & translation() const
translational component
virtual double initialEstimatePossible(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual bool getMeasurementData(double *d) const