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