g2o
Loading...
Searching...
No Matches
edge_se3_pointxyz_disparity.cpp
Go to the documentation of this file.
1// g2o - General Graph Optimization
2// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
3// All rights reserved.
4//
5// Redistribution and use in source and binary forms, with or without
6// modification, are permitted provided that the following conditions are
7// met:
8//
9// * Redistributions of source code must retain the above copyright notice,
10// this list of conditions and the following disclaimer.
11// * Redistributions in binary form must reproduce the above copyright
12// notice, this list of conditions and the following disclaimer in the
13// documentation and/or other materials provided with the distribution.
14//
15// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21// TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22// PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23// LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24// NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26
28
29#include <cassert>
30
31#ifdef G2O_HAVE_OPENGL
34#endif
35
36namespace g2o {
37using namespace std;
38
39// point to camera projection, monocular
42 params(nullptr),
43 cache(nullptr) {
46 information().setIdentity();
47 information()(2, 2) = 1000.;
48 J.fill(0);
49 J.block<3, 3>(0, 0) = -Matrix3::Identity();
50}
51
53 ParameterVector pv(1);
54 pv[0] = params;
56 pv);
57 return cache != 0;
58}
59
60bool EdgeSE3PointXYZDisparity::read(std::istream& is) {
61 readParamIds(is);
63 return readInformationMatrix(is);
64}
65
66bool EdgeSE3PointXYZDisparity::write(std::ostream& os) const {
67 writeParamIds(os);
69 return writeInformationMatrix(os);
70}
71
73 // VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
74 VertexPointXYZ* point = static_cast<VertexPointXYZ*>(_vertices[1]);
75 const Vector3& pt = point->estimate();
76
77 Vector3 p = cache->w2i() * pt;
78
79 Vector3 perr;
80 perr.head<2>() = p.head<2>() / p(2);
81 perr(2) = 1 / p(2);
82
83 // error, which is backwards from the normal observed - calculated
84 // _measurement is the measured projection
85 _error = perr - _measurement;
86}
87
88#ifdef EDGE_PROJECT_DISPARITY_ANALYTIC_JACOBIAN
89
91 // VertexSE3 *cam = static_cast<VertexSE3 *>(_vertices[0]);
92 VertexPointXYZ* vp = static_cast<VertexPointXYZ*>(_vertices[1]);
93
94 const Vector3& pt = vp->estimate();
95
96 Vector3 Zcam = cache->w2l() * vp->estimate();
97
98 // J(0,3) = -0.0;
99 J(0, 4) = -2 * Zcam(2);
100 J(0, 5) = 2 * Zcam(1);
101
102 J(1, 3) = 2 * Zcam(2);
103 // J(1,4) = -0.0;
104 J(1, 5) = -2 * Zcam(0);
105
106 J(2, 3) = -2 * Zcam(1);
107 J(2, 4) = 2 * Zcam(0);
108 // J(2,5) = -0.0;
109
110 J.block<3, 3>(0, 6) = cache->w2l().rotation();
111
112 // Eigen::Matrix<double,3,9,Eigen::ColMajor> Jprime =
113 // vcache->params->Kcam_inverseOffsetR * J;
114 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jprime =
116 Eigen::Matrix<double, 3, 9, Eigen::ColMajor> Jhom;
117 Vector3 Zprime = cache->w2i() * pt;
118
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);
124
125 _jacobianOplusXi = Jhom.block<3, 6>(0, 0);
126 _jacobianOplusXj = Jhom.block<3, 3>(0, 6);
127}
128
129#endif
130
132 // VertexSE3 *cam = static_cast< VertexSE3*>(_vertices[0]);
133 VertexPointXYZ* point = static_cast<VertexPointXYZ*>(_vertices[1]);
134 const Vector3& pt = point->estimate();
135
136 Vector3 p = cache->w2i() * pt;
137
138 Vector3 perr;
139 perr.head<2>() = p.head<2>() / p(2);
140 perr(2) = 1 / p(2);
141
142 // error, which is backwards from the normal observed - calculated
143 // _measurement is the measured projection
144 _measurement = perr;
145 return true;
146}
147
150 (void)from;
151 assert(from.size() == 1 && from.count(_vertices[0]) == 1 &&
152 "Can not initialize VertexDepthCam position by VertexTrackXYZ");
153 VertexSE3* cam = dynamic_cast<VertexSE3*>(_vertices[0]);
154 VertexPointXYZ* point = dynamic_cast<VertexPointXYZ*>(_vertices[1]);
155
156 const Eigen::Matrix<double, 3, 3, Eigen::ColMajor>& invKcam =
157 params->invKcam();
158 Vector3 p;
159 double w = 1. / _measurement(2);
160 p.head<2>() = _measurement.head<2>() * w;
161 p(2) = w;
162 p = invKcam * p;
163 p = cam->estimate() * (params->offset() * p);
164 point->setEstimate(p);
165}
166
167#ifdef G2O_HAVE_OPENGL
168EdgeProjectDisparityDrawAction::EdgeProjectDisparityDrawAction()
169 : DrawAction(typeid(EdgeSE3PointXYZDisparity).name()) {}
170
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;
177
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;
183 Isometry3 fromTransform =
184 fromEdge->estimate() * e->cameraParameter()->offset();
185 glColor3f(LANDMARK_EDGE_COLOR);
186 glPushAttrib(GL_ENABLE_BIT);
187 glDisable(GL_LIGHTING);
188 glBegin(GL_LINES);
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());
194 glEnd();
195 glPopAttrib();
196 return this;
197}
198#endif
199
200} // namespace g2o
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
Definition base_edge.h:165
bool readInformationMatrix(std::istream &is)
Definition base_edge.h:173
bool readParamIds(std::istream &is)
reads the param IDs from the stream
Definition base_edge.h:187
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition base_edge.h:119
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition base_edge.h:107
bool writeParamIds(std::ostream &os) const
write the param IDs that are potentially used by the edge
Definition base_edge.h:182
Measurement _measurement
the measurement of the edge
Definition base_edge.h:146
ErrorVector _error
Definition base_edge.h:149
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
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
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 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 &parameters)
Definition cache.h:125
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
Definition vertex_se3.h:50
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
Definition io_helper.h:36
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Definition io_helper.h:42
VectorN< 3 > Vector3
Definition eigen_types.h:51
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
std::vector< Parameter * > ParameterVector
Definition parameter.h:54
Definition jet.h:876
#define LANDMARK_EDGE_COLOR