g2o
edge_se3_offset.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_offset.h"
29 #include "parameter_se3_offset.h"
30 
31 #include <iostream>
32 
33 namespace g2o {
34 namespace deprecated {
35 
36  using namespace std;
37 
39  information().setIdentity();
40  _offsetFrom = 0;
41  _offsetTo = 0;
42  _cacheFrom = 0;
43  _cacheTo = 0;
47  }
48 
50  assert(_offsetFrom && _offsetTo);
51 
52  ParameterVector pv(2);
53  pv[0]=_offsetFrom;
54  resolveCache(_cacheFrom, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE3_OFFSET",pv);
55  pv[1]=_offsetTo;
56  resolveCache(_cacheTo, (OptimizableGraph::Vertex*)_vertices[1],"CACHE_SE3_OFFSET",pv);
57  return (_cacheFrom && _cacheTo);
58  }
59 
60  bool EdgeSE3Offset::read(std::istream& is) {
61  int pidFrom, pidTo;
62  is >> pidFrom >> pidTo ;
63  if (! setParameterId(0,pidFrom))
64  return false;
65  if (! setParameterId(1,pidTo))
66  return false;
67 
68  Vector7d meas;
69  for (int i=0; i<7; i++)
70  is >> meas[i];
71  setMeasurement(SE3Quat(meas));
72 
73  if (is.bad()) {
74  return false;
75  }
76  for ( int i=0; i<information().rows() && is.good(); i++)
77  for (int j=i; j<information().cols() && is.good(); j++){
78  is >> information()(i,j);
79  if (i!=j)
80  information()(j,i)=information()(i,j);
81  }
82  if (is.bad()) {
83  // we overwrite the information matrix with the Identity
84  information().setIdentity();
85  }
86  return true;
87  }
88 
89  bool EdgeSE3Offset::write(std::ostream& os) const {
90  os << _offsetFrom->id() << " " << _offsetTo->id() << " ";
91  for (int i=0; i<7; i++) os << measurement()[i] << " ";
92  for (int i=0; i<information().rows(); i++)
93  for (int j=i; j<information().cols(); j++) {
94  os << information()(i,j) << " ";
95  }
96  return os.good();
97  }
98 
101  _error.head<3>() = delta.translation();
102  // The analytic Jacobians assume the error in this special form (w beeing positive)
103  if (delta.rotation().w() < 0.)
104  _error.tail<3>() = - delta.rotation().vec();
105  else
106  _error.tail<3>() = delta.rotation().vec();
107  }
108 
110  SE3Quat delta = _cacheFrom->w2n() * _cacheTo->n2w();
111  setMeasurement(delta);
112  return true;
113  }
114 
116  //BaseBinaryEdge<6, SE3Quat, VertexSE3, VertexSE3>::linearizeOplus();
117 
118  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
119  VertexSE3 *to = static_cast<VertexSE3*>(_vertices[1]);
120  Eigen::Isometry3d E;
121  Eigen::Isometry3d Z, Xi, Xj, Pi, Pj;
122  Xi=from->estimate().rotation().toRotationMatrix();
123  Xi.translation()=from->estimate().translation();
124  Xj=to->estimate().rotation().toRotationMatrix();
125  Xj.translation()=to->estimate().translation();
126  Pi=_cacheFrom->offsetParam()->offset().rotation().toRotationMatrix();
127  Pi.translation()=_cacheFrom->offsetParam()->offset().translation();
128  Pj=_cacheTo->offsetParam()->offset().rotation().toRotationMatrix();
129  Pj.translation()=_cacheTo->offsetParam()->offset().translation();
130  Z=_measurement.rotation().toRotationMatrix();
131  Z.translation()=_measurement.translation();
132  // Matrix6d Ji, Jj;
133  // computeSE3Gradient(E, Ji , Jj,
134  // Z, Pi, Xi, Pj, Xj);
135  // cerr << "Ji:" << endl;
136  // cerr << Ji-_jacobianOplusXi << endl;
137  // cerr << "Jj:" << endl;
138  // cerr << Jj-_jacobianOplusXj << endl;
139  internal::computeEdgeSE3Gradient<JacobianXiOplusType>(E, _jacobianOplusXi , _jacobianOplusXj,
140  Z, Xi, Xj, Pi, Pj);
141  }
142 
144  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
145  VertexSE3 *to = static_cast<VertexSE3*>(_vertices[1]);
146 
147  SE3Quat virtualMeasurement = _cacheFrom->offsetParam()->offset() * measurement() * _cacheTo->offsetParam()->offset().inverse();
148 
149  if (from_.count(from) > 0) {
150  to->setEstimate(from->estimate() * virtualMeasurement);
151  } else
152  from->setEstimate(to->estimate() * virtualMeasurement.inverse());
153  }
154 
155 }
156 }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
const SE3Quat & offset() const
return the offset as SE3Quat
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
virtual void setMeasurement(const SE3Quat &m)
virtual bool write(std::ostream &os) const
write the vertex to a stream
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
SE3Quat inverse() const
Definition: se3quat.h:120
bool setParameterId(int argNum, int paramId)
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::Quaterniond & rotation() const
Definition: se3quat.h:97
ParameterSE3Offset * _offsetTo
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)
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
ParameterSE3Offset * _offsetFrom
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
EIGEN_STRONG_INLINE const Measurement & measurement() const
accessor functions for the measurement represented by the edge
Definition: base_edge.h:75
const ParameterSE3Offset * offsetParam() const
const Vector3D & translation() const
Definition: se3quat.h:93
VertexContainer _vertices
Definition: hyper_graph.h:202