49 J.block<3, 3>(0, 0) = -Matrix3::Identity();
80 perr.head<2>() = p.head<2>() / p(2);
88#ifdef EDGE_PROJECT_DISPARITY_ANALYTIC_JACOBIAN
99 J(0, 4) = -2 * Zcam(2);
100 J(0, 5) = 2 * Zcam(1);
102 J(1, 3) = 2 * Zcam(2);
104 J(1, 5) = -2 * Zcam(0);
106 J(2, 3) = -2 * Zcam(1);
107 J(2, 4) = 2 * Zcam(0);
110 J.block<3, 3>(0, 6) =
cache->
w2l().rotation();
114 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jprime =
116 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jhom;
119 Jhom.block<2, 9>(0, 0) = 1 / (Zprime(2) * Zprime(2)) *
120 (Jprime.block<2, 9>(0, 0) * Zprime(2) -
121 Zprime.head<2>() * Jprime.block<1, 9>(2, 0));
122 Jhom.block<1, 9>(2, 0) =
123 -1 / (Zprime(2) * Zprime(2)) * Jprime.block<1, 9>(2, 0);
139 perr.head<2>() = p.head<2>() / p(2);
151 assert(from.size() == 1 && from.count(
_vertices[0]) == 1 &&
152 "Can not initialize VertexDepthCam position by VertexTrackXYZ");
156 const Eigen::Matrix<double, 3, 3, Eigen::ColMajor>& invKcam =
167#ifdef G2O_HAVE_OPENGL
168EdgeProjectDisparityDrawAction::EdgeProjectDisparityDrawAction()
171HyperGraphElementAction* EdgeProjectDisparityDrawAction::operator()(
172 HyperGraph::HyperGraphElement* element,
173 HyperGraphElementAction::Parameters* params_) {
174 if (
typeid(*element).name() != _typeName)
return nullptr;
175 refreshPropertyPtrs(params_);
176 if (!_previousParams)
return this;
178 if (_show && !_show->value())
return this;
179 EdgeSE3PointXYZDisparity* e =
static_cast<EdgeSE3PointXYZDisparity*
>(element);
180 VertexSE3* fromEdge =
static_cast<VertexSE3*
>(e->vertices()[0]);
181 VertexPointXYZ* toEdge =
static_cast<VertexPointXYZ*
>(e->vertices()[1]);
182 if (!fromEdge || !toEdge)
return this;
184 fromEdge->estimate() * e->cameraParameter()->offset();
186 glPushAttrib(GL_ENABLE_BIT);
187 glDisable(GL_LIGHTING);
189 glVertex3f((
float)fromTransform.translation().x(),
190 (
float)fromTransform.translation().y(),
191 (
float)fromTransform.translation().z());
192 glVertex3f((
float)toEdge->estimate().x(), (
float)toEdge->estimate().y(),
193 (
float)toEdge->estimate().z());
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
edge from a track to a depth camera node using a disparity measurement
EdgeSE3PointXYZDisparity()
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
virtual bool setMeasurementFromState()
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 write(std::ostream &os) const
write the vertex to a stream
virtual bool resolveCaches()
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
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)
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
std::vector< Parameter * > ParameterVector
#define LANDMARK_EDGE_COLOR