g2o
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 <iostream>
30 #include <iomanip>
31 
32 #ifdef G2O_HAVE_OPENGL
35 #endif
36 
37 namespace g2o {
38  using namespace std;
39 
40 
41  // point to camera projection, monocular
45  information().setIdentity();
46  information()(2,2)=1000.;
47  J.fill(0);
48  J.block<3,3>(0,0) = -Matrix3D::Identity();
49  }
50 
51 
53  ParameterVector pv(1);
54  pv[0]=params;
55  resolveCache(cache, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_CAMERA",pv);
56  return cache != 0;
57  }
58 
59 
60  bool EdgeSE3PointXYZDisparity::read(std::istream& is) {
61  // measured keypoint
62  int pid;
63  is >> pid;
64  setParameterId(0,pid);
65 
66  Vector3D meas;
67  for (int i=0; i<3; i++) is >> meas[i];
68  setMeasurement(meas);
69  if (is.bad())
70  return false;
71  for ( int i=0; i<information().rows() && is.good(); i++)
72  for (int j=i; j<information().cols() && is.good(); j++){
73  is >> information()(i,j);
74  if (i!=j)
75  information()(j,i)=information()(i,j);
76  }
77  if (is.bad()) {
78  // we overwrite the information matrix
79  information().setIdentity();
80  information()(2,2)=1000.;
81  }
82  //_cacheIds[0] = _paramId;
83  return true;
84  }
85 
86  bool EdgeSE3PointXYZDisparity::write(std::ostream& os) const {
87  os << params->id() << " ";
88  for (int i=0; i<3; i++) os << measurement()[i] << " ";
89  for (int i=0; i<information().rows(); i++)
90  for (int j=i; j<information().cols(); j++) {
91  os << information()(i,j) << " ";
92  }
93  return os.good();
94  }
95 
96 
98  //VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
99  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
100  const Vector3D& pt = point->estimate();
101  //Vector4D ppt(pt(0),pt(1),pt(2),1.0);
102 
103  // VertexCameraCache* vcache = (VertexCameraCache*)cam->getCache(_cacheIds[0]);
104  // if (! vcache){
105  // cerr << "fatal error in retrieving cache" << endl;
106  // }
107 
108  // CacheCamera* vcache = cache;
109  // if (! vcache){
110  // cerr << "fatal error in retrieving cache" << endl;
111  // }
112 
113  Vector3D p = cache->w2i() * pt;
114 
115  Vector3D perr;
116  perr.head<2>() = p.head<2>()/p(2);
117  perr(2) = 1/p(2);
118 
119  // error, which is backwards from the normal observed - calculated
120  // _measurement is the measured projection
121  _error = perr - _measurement;
122  }
123 
124 #ifdef EDGE_PROJECT_DISPARITY_ANALYTIC_JACOBIAN
125 
127  //VertexSE3 *cam = static_cast<VertexSE3 *>(_vertices[0]);
128  VertexPointXYZ *vp = static_cast<VertexPointXYZ *>(_vertices[1]);
129 
130  // VertexCameraCache* vcache = (VertexCameraCache*)cam->getCache(_cacheIds[0]);
131  // if (! vcache){
132  // cerr << "fatal error in retrieving cache" << endl;
133  // }
134 
135  // CacheCamera* vcache = cache;
136  // if (! vcache){
137  // cerr << "fatal error in retrieving cache" << endl;
138  // }
139 
140 
141  const Vector3D& pt = vp->estimate();
142 
143  Vector3D Zcam = cache->w2l() * vp->estimate();
144 
145  // J(0,3) = -0.0;
146  J(0,4) = -2*Zcam(2);
147  J(0,5) = 2*Zcam(1);
148 
149  J(1,3) = 2*Zcam(2);
150  // J(1,4) = -0.0;
151  J(1,5) = -2*Zcam(0);
152 
153  J(2,3) = -2*Zcam(1);
154  J(2,4) = 2*Zcam(0);
155  // J(2,5) = -0.0;
156 
157  J.block<3,3>(0,6) = cache->w2l().rotation();
158 
159  //Eigen::Matrix<double,3,9,Eigen::ColMajor> Jprime = vcache->params->Kcam_inverseOffsetR * J;
160  Eigen::Matrix<double,3,9,Eigen::ColMajor> Jprime = params->Kcam_inverseOffsetR() * J;
161  Eigen::Matrix<double,3,9,Eigen::ColMajor> Jhom;
162  Vector3D Zprime = cache->w2i() * pt;
163 
164  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));
165  Jhom.block<1,9>(2,0) = - 1/(Zprime(2)*Zprime(2)) * Jprime.block<1,9>(2,0);
166 
167  _jacobianOplusXi = Jhom.block<3,6>(0,0);
168  _jacobianOplusXj = Jhom.block<3,3>(0,6);
169  }
170 
171 #endif
172 
174  //VertexSE3 *cam = static_cast< VertexSE3*>(_vertices[0]);
175  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
176  const Vector3D &pt = point->estimate();
177 
178  // VertexCameraCache* vcache = (VertexCameraCache*) cam->getCache(_cacheIds[0]);
179  // if (! vcache){
180  // cerr << "fatal error in retrieving cache" << endl;
181  // }
182 
183  Vector3D p = cache->w2i() * pt;
184 
185  Vector3D perr;
186  perr.head<2>() = p.head<2>()/p(2);
187  perr(2) = 1/p(2);
188 
189  // error, which is backwards from the normal observed - calculated
190  // _measurement is the measured projection
191  _measurement = perr;
192  return true;
193  }
194 
196  {
197  (void) from;
198  assert(from.size() == 1 && from.count(_vertices[0]) == 1 && "Can not initialize VertexDepthCam position by VertexTrackXYZ");
199  VertexSE3 *cam = dynamic_cast<VertexSE3*>(_vertices[0]);
200  VertexPointXYZ *point = dynamic_cast<VertexPointXYZ*>(_vertices[1]);
201 
202  // VertexCameraCache* vcache = (VertexCameraCache* ) cam->getCache(_cacheIds[0]);
203  // if (! vcache){
204  // cerr << "fatal error in retrieving cache" << endl;
205  // }
206  //ParameterCamera* params=vcache->params;
207  const Eigen::Matrix<double, 3, 3, Eigen::ColMajor>& invKcam = params->invKcam();
208  Vector3D p;
209  double w=1./_measurement(2);
210  p.head<2>() = _measurement.head<2>()*w;
211  p(2) = w;
212  p = invKcam * p;
213  p = cam->estimate() * (params->offset() * p);
214  point->setEstimate(p);
215  }
216 
217 
218 #ifdef G2O_HAVE_OPENGL
219  EdgeProjectDisparityDrawAction::EdgeProjectDisparityDrawAction(): DrawAction(typeid(EdgeSE3PointXYZDisparity).name()){}
220 
221  HyperGraphElementAction* EdgeProjectDisparityDrawAction::operator()(HyperGraph::HyperGraphElement* element,
223  if (typeid(*element).name()!=_typeName)
224  return 0;
225  refreshPropertyPtrs(params_);
226  if (! _previousParams)
227  return this;
228 
229  if (_show && !_show->value())
230  return this;
231  EdgeSE3PointXYZDisparity* e = static_cast<EdgeSE3PointXYZDisparity*>(element);
232  VertexSE3* fromEdge = static_cast<VertexSE3*>(e->vertices()[0]);
233  VertexPointXYZ* toEdge = static_cast<VertexPointXYZ*>(e->vertices()[1]);
234  if (! fromEdge || ! toEdge)
235  return this;
236  Isometry3D fromTransform=fromEdge->estimate() * e->cameraParameter()->offset();
237  glColor3f(LANDMARK_EDGE_COLOR);
238  glPushAttrib(GL_ENABLE_BIT);
239  glDisable(GL_LIGHTING);
240  glBegin(GL_LINES);
241  glVertex3f((float)fromTransform.translation().x(),(float)fromTransform.translation().y(),(float)fromTransform.translation().z());
242  glVertex3f((float)toEdge->estimate().x(),(float)toEdge->estimate().y(),(float)toEdge->estimate().z());
243  glEnd();
244  glPopAttrib();
245  return this;
246  }
247 #endif
248 
249 }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const Affine3D & w2i() const
return the world to image transform
const Isometry3D & w2l() const
const Matrix3D & invKcam() const
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
Abstract action that operates on a graph entity.
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
const ParameterCamera * cameraParameter() const
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
edge from a track to a depth camera node using a disparity measurement
bool setParameterId(int argNum, int paramId)
const VertexContainer & vertices() const
Definition: hyper_graph.h:178
#define LANDMARK_EDGE_COLOR
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
void resolveCache(CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector &parameters)
Definition: cache.h:122
std::vector< Parameter * > ParameterVector
Definition: parameter.h:52
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Definition: eigen_types.h:66
int id() const
Definition: parameter.h:45
Vertex for a tracked point in space.
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
virtual bool write(std::ostream &os) const
write the vertex to a stream
A general case Vertex for optimization.
void resizeParameters(size_t newSize)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
virtual void setMeasurement(const Vector3D &m)
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
const Matrix3D & Kcam_inverseOffsetR() const
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
VertexContainer _vertices
Definition: hyper_graph.h:202