60 is >> pidFrom >> pidTo;
67 for (
int i=0; i<3; i++)
73 for (
int i=0; i<
information().rows() && is.good(); i++)
74 for (
int j=i; j<
information().cols() && is.good(); j++){
88 for (
int i=0; i<3; i++) os <<
measurement()[i] <<
" ";
114 if (from_.count(from) > 0) {
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
virtual void setMeasurement(const SE2 &m)
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
CacheSE2Offset * _cacheFrom
std::set< Vertex * > VertexSet
const ParameterSE2Offset * offsetParam() const
2D pose Vertex, (x,y,theta)
ParameterSE2Offset * _offsetTo
virtual bool write(std::ostream &os) const
write the vertex to a stream
bool setParameterId(int argNum, int paramId)
const Eigen::Rotation2Dd & rotation() const
rotational component
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters)
std::vector< Parameter * > ParameterVector
const SE2 & offset() const
CacheSE2Offset * _cacheTo
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
A general case Vertex for optimization.
virtual bool resolveCaches()
void resizeParameters(size_t newSize)
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
ParameterSE2Offset * _offsetFrom
const EstimateType & estimate() const
return the current estimate of the vertex
virtual bool setMeasurementFromState()
SE2 inverse() const
invert :-)
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
const Vector2D & translation() const
translational component
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
VertexContainer _vertices