34 namespace deprecated {
62 is >> pidFrom >> pidTo ;
69 for (
int i=0; i<7; i++)
76 for (
int i=0; i<
information().rows() && is.good(); i++)
77 for (
int j=i; j<
information().cols() && is.good(); j++){
91 for (
int i=0; i<7; i++) os <<
measurement()[i] <<
" ";
121 Eigen::Isometry3d Z, Xi, Xj, Pi, Pj;
149 if (from_.count(from) > 0) {
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const SE3Quat & offset() const
return the offset as SE3Quat
virtual bool resolveCaches()
CacheSE3Offset * _cacheTo
std::set< Vertex * > VertexSet
virtual void setMeasurement(const SE3Quat &m)
SE3Quat _inverseMeasurement
virtual bool write(std::ostream &os) const
write the vertex to a stream
Eigen::Matrix< double, 7, 1 > Vector7d
JacobianXiOplusType _jacobianOplusXi
bool setParameterId(int argNum, int paramId)
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters)
std::vector< Parameter * > ParameterVector
const SE3Quat & n2w() const
const Eigen::Quaterniond & rotation() const
ParameterSE3Offset * _offsetTo
3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vecto...
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
A general case Vertex for optimization.
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
ParameterSE3Offset * _offsetFrom
const EstimateType & estimate() const
return the current estimate of the vertex
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
JacobianXjOplusType _jacobianOplusXj
const SE3Quat & w2n() const
CacheSE3Offset * _cacheFrom
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
const ParameterSE3Offset * offsetParam() const
const Vector3D & translation() const
virtual bool setMeasurementFromState()
VertexContainer _vertices