62 for (
int i=0; i<7; i++) is >> meas[i];
69 for (
int i=0; i<
information().rows() && is.good(); i++)
70 for (
int j=i; j<
information().cols() && is.good(); j++){
85 for (
int i=0; i<7; i++) os << meas[i] <<
" ";
118 assert(v &&
"Vertex for the Prior edge is not set");
121 if (
_information.block<3,3>(0,0).array().abs().sum() == 0){
122 newEstimate.translation()=v->
estimate().translation();
124 if (
_information.block<3,3>(3,3).array().abs().sum() == 0){
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
Isometry3D fromVectorQT(const Vector7d &v)
const ParameterSE3Offset * offsetParam() const
std::set< Vertex * > VertexSet
virtual bool setMeasurementFromState()
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
ParameterSE3Offset * _offsetParam
virtual bool write(std::ostream &os) const
write the vertex to a stream
InformationType _information
Eigen::Matrix< double, 7, 1 > Vector7d
JacobianXiOplusType _jacobianOplusXi
virtual bool resolveCaches()
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
bool setParameterId(int argNum, int paramId)
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
Vector6d toVectorMQT(const Isometry3D &t)
Isometry3D::ConstLinearPart extractRotation(const Isometry3D &A)
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)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
const Isometry3D & n2w() const
Isometry3D _inverseMeasurement
const EstimateType & estimate() const
return the current estimate of the vertex
3D pose Vertex, represented as an Isometry3D
virtual void setMeasurement(const Isometry3D &m)
void computeEdgeSE3PriorGradient(Isometry3D &E, const Eigen::MatrixBase< Derived > &JConstRef, const Isometry3D &Z, const Isometry3D &X, const Isometry3D &P=Isometry3D())
Vector7d toVectorQT(const Isometry3D &t)
virtual void linearizeOplus()
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3Prior()
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
VertexContainer _vertices