37 assert(from.size() == 0); (void) from; (void) to;
45 is >> p[0] >> p[1] >> p[2];
48 for (
int i = 0; i < 3; ++i)
49 for (
int j = i; j < 3; ++j) {
60 os << p.x() <<
" " << p.y() <<
" " << p.z();
61 for (
int i = 0; i < 3; ++i)
62 for (
int j = i; j < 3; ++j)
virtual void setMeasurement(const SE2 &m)
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
std::set< Vertex * > VertexSet
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
2D pose Vertex, (x,y,theta)
virtual bool setMeasurementData(const double *d)
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
A general case Vertex for optimization.
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
SE2 inverse() const
invert :-)
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
VertexContainer _vertices