41 J.block<3, 3>(0, 0) = -Matrix3::Identity();
71 perr.head<2>() = p.head<2>() / p(2);
88 J(0, 4) = -2 * Zcam(2);
89 J(0, 5) = 2 * Zcam(1);
91 J(1, 3) = 2 * Zcam(2);
93 J(1, 5) = -2 * Zcam(0);
95 J(2, 3) = -2 * Zcam(1);
96 J(2, 4) = 2 * Zcam(0);
99 J.block<3, 3>(0, 6) =
cache->
w2l().rotation();
101 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jprime =
105 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jhom;
106 Jhom.block<2, 9>(0, 0) = 1 / (Zprime(2) * Zprime(2)) *
107 (Jprime.block<2, 9>(0, 0) * Zprime(2) -
108 Zprime.head<2>() * Jprime.block<1, 9>(2, 0));
109 Jhom.block<1, 9>(2, 0) = Jprime.block<1, 9>(2, 0);
124 perr.head<2>() = p.head<2>() / p(2);
134 assert(from.size() == 1 && from.count(
_vertices[0]) == 1 &&
135 "Can not initialize VertexDepthCam position by VertexTrackXYZ");
139 const Eigen::Matrix<double, 3, 3, Eigen::ColMajor>& invKcam =
BaseFixedSizedEdge< D, Vector3, VertexSE3, VertexPointXYZ >::template JacobianType< D, VertexXj::Dimension > & _jacobianOplusXj
BaseFixedSizedEdge< D, Vector3, VertexSE3, VertexPointXYZ >::template JacobianType< D, VertexXi::Dimension > & _jacobianOplusXi
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
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
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 Affine3 & w2i() const
return the world to image transform
const Isometry3 & w2l() const
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
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()
virtual bool resolveCaches()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZDepth()
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool setMeasurementFromState()
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 Matrix3 & invKcam() const
const Matrix3 & Kcam_inverseOffsetR() const
const Isometry3 & offset() const
rotation of the offset as 3x3 rotation matrix
Vertex for a tracked point in space.
3D pose Vertex, represented as an Isometry3
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
std::vector< Parameter * > ParameterVector