35 using namespace Eigen;
61 is >> pidFrom >> pidTo ;
68 for (
int i=0; i<7; i++)
71 Vector4D::MapType(meas.data()+3).
normalize();
77 for (
int i=0; i<
information().rows() && is.good(); i++)
78 for (
int j=i; j<
information().cols() && is.good(); j++){
94 for (
int i=0; i<7; i++) os << meas[i] <<
" ";
140 if (from_.count(from) > 0) {
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
ParameterSE3Offset * _offsetFrom
Isometry3D fromVectorQT(const Vector7d &v)
const ParameterSE3Offset * offsetParam() const
std::set< Vertex * > VertexSet
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual bool resolveCaches()
const Isometry3D & w2n() const
Eigen::Matrix< double, 7, 1 > Vector7d
CacheSE3Offset * _cacheTo
virtual bool setMeasurementFromState()
Edge between two 3D pose vertices.
JacobianXiOplusType _jacobianOplusXi
bool setParameterId(int argNum, int paramId)
virtual void setMeasurement(const Isometry3D &m)
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters)
std::vector< Parameter * > ParameterVector
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Eigen::Quaterniond & normalize(Eigen::Quaterniond &q)
Vector6d toVectorMQT(const Isometry3D &t)
CacheSE3Offset * _cacheFrom
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
const Parameter * parameter(int argNo) const
A general case Vertex for optimization.
ParameterSE3Offset * _offsetTo
void resizeParameters(size_t newSize)
Isometry3D _inverseMeasurement
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
const Isometry3D & n2w() const
const EstimateType & estimate() const
return the current estimate of the vertex
void computeEdgeSE3Gradient(Isometry3D &E, Eigen::MatrixBase< Derived > const &JiConstRef, Eigen::MatrixBase< Derived > const &JjConstRef, const Isometry3D &Z, const Isometry3D &Xi, const Isometry3D &Xj, const Isometry3D &Pi, const Isometry3D &Pj)
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
3D pose Vertex, represented as an Isometry3D
virtual bool write(std::ostream &os) const
write the vertex to a stream
JacobianXjOplusType _jacobianOplusXj
Vector7d toVectorQT(const Isometry3D &t)
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
VertexContainer _vertices