30 namespace deprecated {
42 J.block<3,3>(0,0) = -Eigen::Matrix3d::Identity();
59 for (
int i=0; i<3; i++) is >> meas[i];
66 for (
int i=0; i<
information().rows() && is.good(); i++)
67 for (
int j=i; j<
information().cols() && is.good(); j++){
82 for (
int i=0; i<3; i++) os <<
measurement()[i] <<
" ";
98 perr.head<2>() = p.head<2>()/p(2);
111 const Eigen::Vector3d& pt = vp->
estimate();
130 Eigen::Vector3d Zprime =
cache->
w2i() * pt;
132 Eigen::Matrix<double, 3, 9> Jhom;
133 Jhom.block<2,9>(0,0) = 1/(Zprime(2)*Zprime(2)) * (Jprime.block<2,9>(0,0)*Zprime(2) - Zprime.head<2>() * Jprime.block<1,9>(2,0));
134 Jhom.block<1,9>(2,0) = Jprime.block<1,9>(2,0);
146 const Eigen::Vector3d& pt = point->
estimate();
148 Eigen::Vector3d p =
cache->
w2i() * pt;
149 Eigen::Vector3d perr;
150 perr.head<2>() = p.head<2>()/p(2);
160 assert(from.size() == 1 && from.count(
_vertices[0]) == 1 &&
"Can not initialize VertexDepthCam position by VertexTrackXYZ");
164 const Eigen::Matrix<double, 3, 3>& invKcam =
params->
invKcam();
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const Eigen::Matrix3d & invKcam() const
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual bool resolveCaches()
std::set< Vertex * > VertexSet
const Eigen::Affine3d & w2i() const
return the world to image transform
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZDepth()
JacobianXiOplusType _jacobianOplusXi
Eigen::Matrix< double, 3, 9 > J
bool setParameterId(int argNum, int paramId)
const Eigen::Isometry3d & offsetMatrix() const
rotation of the offset as 3x3 rotation matrix
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters)
std::vector< Parameter * > ParameterVector
const Eigen::Matrix3d & Kcam_inverseOffsetR() const
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 linearizeOplus()
const Eigen::Isometry3d & w2lMatrix() const
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
const EstimateType & estimate() const
return the current estimate of the vertex
JacobianXjOplusType _jacobianOplusXj
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool setMeasurementFromState()
virtual void setMeasurement(const Eigen::Vector3d &m)
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
VertexContainer _vertices