g2o
edge_se3_pointxyz.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 
27 #include "edge_se3_pointxyz.h"
28 #include "parameter_se3_offset.h"
29 
30 #ifdef G2O_HAVE_OPENGL
32 #endif
33 
34 #include <iostream>
35 
36 #ifdef G2O_HAVE_OPENGL
39 #endif
40 
41 namespace g2o {
42  using namespace std;
43 
44  // point to camera projection, monocular
46  information().setIdentity();
47  J.fill(0);
48  J.block<3,3>(0,0) = -Matrix3D::Identity();
49  cache = 0;
50  offsetParam = 0;
53  }
54 
56  ParameterVector pv(1);
57  pv[0]=offsetParam;
58  resolveCache(cache, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE3_OFFSET",pv);
59  return cache != 0;
60  }
61 
62 
63  bool EdgeSE3PointXYZ::read(std::istream& is) {
64  int pId;
65  is >> pId;
66  setParameterId(0, pId);
67  // measured keypoint
68  Vector3D meas;
69  for (int i=0; i<3; i++) is >> meas[i];
70  setMeasurement(meas);
71  // information matrix is the identity for features, could be changed to allow arbitrary covariances
72  if (is.bad()) {
73  return false;
74  }
75  for ( int i=0; i<information().rows() && is.good(); i++)
76  for (int j=i; j<information().cols() && is.good(); j++){
77  is >> information()(i,j);
78  if (i!=j)
79  information()(j,i)=information()(i,j);
80  }
81  if (is.bad()) {
82  // we overwrite the information matrix
83  information().setIdentity();
84  }
85  return true;
86  }
87 
88  bool EdgeSE3PointXYZ::write(std::ostream& os) const {
89  os << offsetParam->id() << " ";
90  for (int i=0; i<3; i++) os << measurement()[i] << " ";
91  for (int i=0; i<information().rows(); i++)
92  for (int j=i; j<information().cols(); j++) {
93  os << information()(i,j) << " ";
94  }
95  return os.good();
96  }
97 
98 
100  // from cam to point (track)
101  //VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
102  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
103 
104  Vector3D perr = cache->w2n() * point->estimate();
105 
106  // error, which is backwards from the normal observed - calculated
107  // _measurement is the measured projection
108  _error = perr - _measurement;
109  // std::cout << _error << std::endl << std::endl;
110  }
111 
113  //VertexSE3 *cam = static_cast<VertexSE3 *>(_vertices[0]);
114  VertexPointXYZ *vp = static_cast<VertexPointXYZ *>(_vertices[1]);
115 
116  Vector3D Zcam = cache->w2l() * vp->estimate();
117 
118  // J(0,3) = -0.0;
119  J(0,4) = -2*Zcam(2);
120  J(0,5) = 2*Zcam(1);
121 
122  J(1,3) = 2*Zcam(2);
123  // J(1,4) = -0.0;
124  J(1,5) = -2*Zcam(0);
125 
126  J(2,3) = -2*Zcam(1);
127  J(2,4) = 2*Zcam(0);
128  // J(2,5) = -0.0;
129 
130  J.block<3,3>(0,6) = cache->w2l().rotation();
131 
132  Eigen::Matrix<double,3,9,Eigen::ColMajor> Jhom = offsetParam->inverseOffset().rotation() * J;
133 
134  _jacobianOplusXi = Jhom.block<3,6>(0,0);
135  _jacobianOplusXj = Jhom.block<3,3>(0,6);
136 
137  // std::cerr << "just linearized." << std::endl;
138  // std::cerr << "_jacobianOplusXi:" << std::endl << _jacobianOplusXi << std::endl;
139  // std::cerr << "_jacobianOplusXj:" << std::endl << _jacobianOplusXj << std::endl;
140  }
141 
142 
144  //VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
145  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
146 
147  // calculate the projection
148  const Vector3D &pt = point->estimate();
149  // SE3OffsetCache* vcache = (SE3OffsetCache*) cam->getCache(_cacheIds[0]);
150  // if (! vcache){
151  // cerr << "fatal error in retrieving cache" << endl;
152  // }
153 
154  Vector3D perr = cache->w2n() * pt;
155  _measurement = perr;
156  return true;
157  }
158 
159 
161  {
162  (void) from;
163  assert(from.size() == 1 && from.count(_vertices[0]) == 1 && "Can not initialize VertexDepthCam position by VertexTrackXYZ");
164 
165  VertexSE3 *cam = dynamic_cast<VertexSE3*>(_vertices[0]);
166  VertexPointXYZ *point = dynamic_cast<VertexPointXYZ*>(_vertices[1]);
167  // SE3OffsetCache* vcache = (SE3OffsetCache* ) cam->getCache(_cacheIds[0]);
168  // if (! vcache){
169  // cerr << "fatal error in retrieving cache" << endl;
170  // }
171  // SE3OffsetParameters* params=vcache->params;
173  point->setEstimate(cam->estimate() * (offsetParam->offset() * p));
174  }
175 
176 #ifdef G2O_HAVE_OPENGL
177  EdgeSE3PointXYZDrawAction::EdgeSE3PointXYZDrawAction(): DrawAction(typeid(EdgeSE3PointXYZ).name()){}
178 
179  HyperGraphElementAction* EdgeSE3PointXYZDrawAction::operator()(HyperGraph::HyperGraphElement* element,
181  if (typeid(*element).name()!=_typeName)
182  return 0;
183  refreshPropertyPtrs(params_);
184  if (! _previousParams)
185  return this;
186 
187  if (_show && !_show->value())
188  return this;
189 
190  EdgeSE3PointXYZ* e = static_cast<EdgeSE3PointXYZ*>(element);
191  VertexSE3* fromEdge = static_cast<VertexSE3*>(e->vertex(0));
192  VertexPointXYZ* toEdge = static_cast<VertexPointXYZ*>(e->vertex(1));
193  if (! fromEdge || ! toEdge)
194  return this;
195  Isometry3D fromTransform=fromEdge->estimate() * e->offsetParameter()->offset();
196  glColor3f(LANDMARK_EDGE_COLOR);
197  glPushAttrib(GL_ENABLE_BIT);
198  glDisable(GL_LIGHTING);
199  glBegin(GL_LINES);
200  glVertex3f((float)fromTransform.translation().x(),(float)fromTransform.translation().y(),(float)fromTransform.translation().z());
201  glVertex3f((float)toEdge->estimate().x(),(float)toEdge->estimate().y(),(float)toEdge->estimate().z());
202  glEnd();
203  glPopAttrib();
204  return this;
205  }
206 #endif
207 
208 } // end namespace
Eigen::Matrix< double, 3, 9, Eigen::ColMajor > J
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const Vertex * vertex(size_t i) const
Definition: hyper_graph.h:186
const Isometry3D & w2l() const
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
const ParameterSE3Offset * offsetParameter()
Abstract action that operates on a graph entity.
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
g2o edge from a track to a point node
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
const Isometry3D & w2n() const
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZ()
const Isometry3D & inverseOffset() const
rotation of the inverse offset as 3x3 rotation matrix
CacheSE3Offset * cache
virtual bool setMeasurementFromState()
bool setParameterId(int argNum, int paramId)
virtual bool resolveCaches()
#define LANDMARK_EDGE_COLOR
virtual void setMeasurement(const Vector3D &m)
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
ParameterSE3Offset * offsetParam
Vertex for a tracked point in space.
virtual void linearizeOplus()
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)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
virtual bool write(std::ostream &os) const
write the vertex to a stream
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
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
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