39 J.block<3,3>(0,0) = -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);
127 J.block<3,3>(0,6) =
cache->
w2l().rotation();
132 Eigen::Matrix<double,3,9,Eigen::ColMajor> 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);
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, Eigen::ColMajor>& invKcam =
params->
invKcam();
virtual void setMeasurement(const Vector3D &m)
virtual bool setMeasurementFromState()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZDepth()
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const Affine3D & w2i() const
return the world to image transform
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
const Isometry3D & w2l() const
const Matrix3D & invKcam() const
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
virtual bool write(std::ostream &os) const
write the vertex to a stream
std::set< Vertex * > VertexSet
virtual bool resolveCaches()
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
JacobianXiOplusType _jacobianOplusXi
bool setParameterId(int argNum, int paramId)
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters)
std::vector< Parameter * > ParameterVector
Vertex for a tracked point in space.
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
A general case Vertex for optimization.
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
void resizeParameters(size_t newSize)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
const EstimateType & estimate() const
return the current estimate of the vertex
virtual void linearizeOplus()
3D pose Vertex, represented as an Isometry3D
const Matrix3D & Kcam_inverseOffsetR() const
JacobianXjOplusType _jacobianOplusXj
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
VertexContainer _vertices