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 #include <iostream>
30 
31 namespace g2o {
32 namespace deprecated {
33 
34  using namespace std;
35 
36 
37  // point to camera projection, monocular
39  information().setIdentity();
40  J.fill(0);
41  J.block<3,3>(0,0) = -Eigen::Matrix3d::Identity();
42  cache = 0;
43  offsetParam = 0;
46  }
47 
49  ParameterVector pv(1);
50  pv[0]=offsetParam;
51  resolveCache(cache, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE3_OFFSET",pv);
52  return cache != 0;
53  }
54 
55 
56  bool EdgeSE3PointXYZ::read(std::istream& is) {
57  int pId;
58  is >> pId;
59  setParameterId(0, pId);
60  // measured keypoint
61  Eigen::Vector3d meas;
62  for (int i=0; i<3; i++) is >> meas[i];
63  setMeasurement(meas);
64  // information matrix is the identity for features, could be changed to allow arbitrary covariances
65  if (is.bad()) {
66  return false;
67  }
68  for ( int i=0; i<information().rows() && is.good(); i++)
69  for (int j=i; j<information().cols() && is.good(); j++){
70  is >> information()(i,j);
71  if (i!=j)
72  information()(j,i)=information()(i,j);
73  }
74  if (is.bad()) {
75  // we overwrite the information matrix
76  information().setIdentity();
77  }
78  return true;
79  }
80 
81  bool EdgeSE3PointXYZ::write(std::ostream& os) const {
82  os << offsetParam->id() << " ";
83  for (int i=0; i<3; i++) os << measurement()[i] << " ";
84  for (int i=0; i<information().rows(); i++)
85  for (int j=i; j<information().cols(); j++) {
86  os << information()(i,j) << " ";
87  }
88  return os.good();
89  }
90 
91 
93  // from cam to point (track)
94  //VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
95  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
96 
97  Eigen::Vector3d perr = cache->w2nMatrix() * point->estimate();
98 
99  // error, which is backwards from the normal observed - calculated
100  // _measurement is the measured projection
101  _error = perr - _measurement;
102  // std::cout << _error << std::endl << std::endl;
103  }
104 
106  //VertexSE3 *cam = static_cast<VertexSE3 *>(_vertices[0]);
107  VertexPointXYZ *vp = static_cast<VertexPointXYZ *>(_vertices[1]);
108 
109  Eigen::Vector3d Zcam = cache->w2lMatrix() * vp->estimate();
110 
111  // J(0,3) = -0.0;
112  J(0,4) = -2*Zcam(2);
113  J(0,5) = 2*Zcam(1);
114 
115  J(1,3) = 2*Zcam(2);
116  // J(1,4) = -0.0;
117  J(1,5) = -2*Zcam(0);
118 
119  J(2,3) = -2*Zcam(1);
120  J(2,4) = 2*Zcam(0);
121  // J(2,5) = -0.0;
122 
123  J.block<3,3>(0,6) = cache->w2lMatrix().rotation();
124 
125  Eigen::Matrix<double,3,9> Jhom = offsetParam->inverseOffsetMatrix().rotation() * J;
126 
127  _jacobianOplusXi = Jhom.block<3,6>(0,0);
128  _jacobianOplusXj = Jhom.block<3,3>(0,6);
129  }
130 
131 
133  //VertexSE3 *cam = static_cast<VertexSE3*>(_vertices[0]);
134  VertexPointXYZ *point = static_cast<VertexPointXYZ*>(_vertices[1]);
135 
136  // calculate the projection
137  const Eigen::Vector3d &pt = point->estimate();
138  // SE3OffsetCache* vcache = (SE3OffsetCache*) cam->getCache(_cacheIds[0]);
139  // if (! vcache){
140  // cerr << "fatal error in retrieving cache" << endl;
141  // }
142 
143  Eigen::Vector3d perr = cache->w2nMatrix() * pt;
144  _measurement = perr;
145  return true;
146  }
147 
148 
150  {
151  (void) from;
152  assert(from.size() == 1 && from.count(_vertices[0]) == 1 && "Can not initialize VertexDepthCam position by VertexTrackXYZ");
153 
154  VertexSE3 *cam = dynamic_cast<VertexSE3*>(_vertices[0]);
155  VertexPointXYZ *point = dynamic_cast<VertexPointXYZ*>(_vertices[1]);
156  // SE3OffsetCache* vcache = (SE3OffsetCache* ) cam->getCache(_cacheIds[0]);
157  // if (! vcache){
158  // cerr << "fatal error in retrieving cache" << endl;
159  // }
160  // SE3OffsetParameters* params=vcache->params;
161  const Eigen::Vector3d& p=_measurement;
162  point->setEstimate(cam->estimate() * (offsetParam->offsetMatrix() * p));
163  }
164 
165 }
166 }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const Eigen::Isometry3d & inverseOffsetMatrix() const
rotation of the inverse offset as 3x3 rotation matrix
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
const Eigen::Isometry3d & w2nMatrix() const
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
bool setParameterId(int argNum, int paramId)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW EdgeSE3PointXYZ()
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
3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vecto...
virtual void setMeasurement(const Eigen::Vector3d &m)
virtual bool write(std::ostream &os) const
write the vertex to a stream
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
Eigen::Matrix< double, 3, 9 > J
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
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