52 "CACHE_SE3_OFFSET", pv);
95 assert(v &&
"Vertex for the Prior edge is not set");
99 if (
_information.block<3, 3>(0, 0).array().abs().sum() == 0) {
100 newEstimate.translation() = v->
estimate().translation();
103 if (
_information.block<3, 3>(3, 3).array().abs().sum() == 0) {
104 newEstimate.matrix().block<3, 3>(0, 0) =
bool writeInformationMatrix(std::ostream &os) const
write the upper trinagular part of the information matrix into the stream
bool readInformationMatrix(std::istream &is)
bool readParamIds(std::istream &is)
reads the param IDs from the stream
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
InformationType _information
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
bool writeParamIds(std::ostream &os) const
write the param IDs that are potentially used by the edge
Measurement _measurement
the measurement of the edge
BaseFixedSizedEdge< D, Isometry3, VertexSE3 >::template JacobianType< D, VertexXi::Dimension > & _jacobianOplusXi
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
const Isometry3 & n2w() const
const ParameterSE3Offset * offsetParam() const
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual void linearizeOplus()
ParameterSE3Offset * _offsetParam
virtual void setMeasurement(const Isometry3 &m)
virtual bool setMeasurementFromState()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3Prior()
virtual bool resolveCaches()
Isometry3 _inverseMeasurement
virtual bool write(std::ostream &os) const
write the vertex to a stream
VertexContainer _vertices
std::set< Vertex * > VertexSet
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
void resizeParameters(size_t newSize)
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters)
A general case Vertex for optimization.
const Isometry3 & offset() const
rotation of the offset as 3x3 rotation matrix
3D pose Vertex, represented as an Isometry3
Isometry3 fromVectorQT(const Vector7 &v)
Vector6 toVectorMQT(const Isometry3 &t)
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
void computeEdgeSE3PriorGradient(Isometry3 &E, const Eigen::MatrixBase< Derived > &JConstRef, const Isometry3 &Z, const Isometry3 &X, const Isometry3 &P=Isometry3::Identity())
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Vector7 toVectorQT(const Isometry3 &t)
Isometry3::ConstLinearPart extractRotation(const Isometry3 &A)
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
std::vector< Parameter * > ParameterVector