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"
28 #include "isometry3d_gradients.h"
29 #include "parameter_se3_offset.h"
30 
31 #include <iostream>
32 
33 namespace g2o {
34  using namespace std;
35  using namespace Eigen;
36 
38  information().setIdentity();
39  _offsetFrom = 0;
40  _offsetTo = 0;
41  _cacheFrom = 0;
42  _cacheTo = 0;
46  }
47 
49  assert(_offsetFrom && _offsetTo);
50 
51  ParameterVector pv(2);
52  pv[0]=_offsetFrom;
53  resolveCache(_cacheFrom, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE3_OFFSET",pv);
54  pv[1]=_offsetTo;
55  resolveCache(_cacheTo, (OptimizableGraph::Vertex*)_vertices[1],"CACHE_SE3_OFFSET",pv);
56  return (_cacheFrom && _cacheTo);
57  }
58 
59  bool EdgeSE3Offset::read(std::istream& is) {
60  int pidFrom, pidTo;
61  is >> pidFrom >> pidTo ;
62  if (! setParameterId(0,pidFrom))
63  return false;
64  if (! setParameterId(1,pidTo))
65  return false;
66 
67  Vector7d meas;
68  for (int i=0; i<7; i++)
69  is >> meas[i];
70  // normalize the quaternion to recover numerical precision lost by storing as human readable text
71  Vector4D::MapType(meas.data()+3).normalize();
73 
74  if (is.bad()) {
75  return false;
76  }
77  for ( int i=0; i<information().rows() && is.good(); i++)
78  for (int j=i; j<information().cols() && is.good(); j++){
79  is >> information()(i,j);
80  if (i!=j)
81  information()(j,i)=information()(i,j);
82  }
83  if (is.bad()) {
84  // we overwrite the information matrix with the Identity
85  information().setIdentity();
86  }
87  return true;
88  }
89 
90  bool EdgeSE3Offset::write(std::ostream& os) const {
91  os << parameter(0)->id() << " ";
92  os << parameter(1)->id() << " ";
94  for (int i=0; i<7; i++) os << meas[i] << " ";
95  for (int i=0; i<information().rows(); i++)
96  for (int j=i; j<information().cols(); j++) {
97  os << information()(i,j) << " ";
98  }
99  return os.good();
100  }
101 
105  }
106 
108  Isometry3D delta = _cacheFrom->w2n() * _cacheTo->n2w();
109  setMeasurement(delta);
110  return true;
111  }
112 
114  //BaseBinaryEdge<6, SE3Quat, VertexSE3, VertexSE3>::linearizeOplus();
115 
116  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
117  VertexSE3 *to = static_cast<VertexSE3*>(_vertices[1]);
118  Isometry3D E;
119  const Isometry3D& Xi=from->estimate();
120  const Isometry3D& Xj=to->estimate();
121  const Isometry3D& Pi=_cacheFrom->offsetParam()->offset();
122  const Isometry3D& Pj=_cacheTo->offsetParam()->offset();
123  const Isometry3D& Z=_measurement;
124  // Matrix6d Ji, Jj;
125  // computeSE3Gradient(E, Ji , Jj,
126  // Z, Pi, Xi, Pj, Xj);
127  // cerr << "Ji:" << endl;
128  // cerr << Ji-_jacobianOplusXi << endl;
129  // cerr << "Jj:" << endl;
130  // cerr << Jj-_jacobianOplusXj << endl;
132  }
133 
135  VertexSE3 *from = static_cast<VertexSE3*>(_vertices[0]);
136  VertexSE3 *to = static_cast<VertexSE3*>(_vertices[1]);
137 
138  Isometry3D virtualMeasurement = _cacheFrom->offsetParam()->offset() * measurement() * _cacheTo->offsetParam()->offset().inverse();
139 
140  if (from_.count(from) > 0) {
141  to->setEstimate(from->estimate() * virtualMeasurement);
142  } else
143  from->setEstimate(to->estimate() * virtualMeasurement.inverse());
144  }
145 
146 }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
ParameterSE3Offset * _offsetFrom
Isometry3D fromVectorQT(const Vector7d &v)
const ParameterSE3Offset * offsetParam() const
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
virtual void initialEstimate(const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
virtual bool resolveCaches()
const Isometry3D & w2n() const
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
CacheSE3Offset * _cacheTo
virtual bool setMeasurementFromState()
Edge between two 3D pose vertices.
Definition: edge_se3.h:18
bool setParameterId(int argNum, int paramId)
virtual void setMeasurement(const Isometry3D &m)
Definition: edge_se3.h:27
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
Eigen::Quaterniond & normalize(Eigen::Quaterniond &q)
Vector6d toVectorMQT(const Isometry3D &t)
CacheSE3Offset * _cacheFrom
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
const Parameter * parameter(int argNo) const
A general case Vertex for optimization.
ParameterSE3Offset * _offsetTo
void resizeParameters(size_t newSize)
Isometry3D _inverseMeasurement
Definition: edge_se3.h:58
EIGEN_STRONG_INLINE const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:67
const Isometry3D & n2w() const
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
void computeEdgeSE3Gradient(Isometry3D &E, Eigen::MatrixBase< Derived > const &JiConstRef, Eigen::MatrixBase< Derived > const &JjConstRef, const Isometry3D &Z, const Isometry3D &Xi, const Isometry3D &Xj, const Isometry3D &Pi, const Isometry3D &Pj)
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
virtual bool write(std::ostream &os) const
write the vertex to a stream
Vector7d toVectorQT(const Isometry3D &t)
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