g2o
edge_se2_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_se2_offset.h"
28 
29 #include "parameter_se2_offset.h"
30 
31 #include <iostream>
32 
33 namespace g2o {
34  using namespace std;
35 
37  information().setIdentity();
38  _offsetFrom = 0;
39  _offsetTo = 0;
40  _cacheFrom = 0;
41  _cacheTo = 0;
45  }
46 
48  assert(_offsetFrom && _offsetTo);
49 
50  ParameterVector pv(1);
51  pv[0]=_offsetFrom;
52  resolveCache(_cacheFrom, (OptimizableGraph::Vertex*)_vertices[0],"CACHE_SE2_OFFSET",pv);
53  pv[0]=_offsetTo;
54  resolveCache(_cacheTo, (OptimizableGraph::Vertex*)_vertices[1],"CACHE_SE2_OFFSET",pv);
55  return (_cacheFrom && _cacheTo);
56  }
57 
58  bool EdgeSE2Offset::read(std::istream& is) {
59  int pidFrom, pidTo;
60  is >> pidFrom >> pidTo;
61  if (! setParameterId(0,pidFrom))
62  return false;
63  if (! setParameterId(1,pidTo))
64  return false;
65 
66  Vector3D meas;
67  for (int i=0; i<3; i++)
68  is >> meas[i];
69  setMeasurement(SE2(meas));
70  if (is.bad()) {
71  return false;
72  }
73  for ( int i=0; i<information().rows() && is.good(); i++)
74  for (int j=i; j<information().cols() && is.good(); j++){
75  is >> information()(i,j);
76  if (i!=j)
77  information()(j,i)=information()(i,j);
78  }
79  if (is.bad()) {
80  // we overwrite the information matrix with the Identity
81  information().setIdentity();
82  }
83  return true;
84  }
85 
86  bool EdgeSE2Offset::write(std::ostream& os) const {
87  os << _offsetFrom->id() << " " << _offsetTo->id() << " ";
88  for (int i=0; i<3; i++) os << measurement()[i] << " ";
89  for (int i=0; i<information().rows(); i++)
90  for (int j=i; j<information().cols(); j++) {
91  os << information()(i,j) << " ";
92  }
93  return os.good();
94  }
95 
98  _error.head<2>() = delta.translation();
99  _error(2)=delta.rotation().angle();
100  }
101 
103  SE2 delta = _cacheFrom->w2n() * _cacheTo->n2w();
104  setMeasurement(delta);
105  return true;
106  }
107 
109  VertexSE2 *from = static_cast<VertexSE2*>(_vertices[0]);
110  VertexSE2 *to = static_cast<VertexSE2*>(_vertices[1]);
111 
112  SE2 virtualMeasurement = _cacheFrom->offsetParam()->offset() * measurement() * _cacheTo->offsetParam()->offset().inverse();
113 
114  if (from_.count(from) > 0) {
115  to->setEstimate(from->estimate() * virtualMeasurement);
116  } else
117  from->setEstimate(to->estimate() * virtualMeasurement.inverse());
118  }
119 
120 }
bool installParameter(ParameterType *&p, size_t argNo, int paramId=-1)
ErrorVector _error
Definition: base_edge.h:89
virtual void setMeasurement(const SE2 &m)
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
CacheSE2Offset * _cacheFrom
const SE2 & w2n() const
std::set< Vertex * > VertexSet
Definition: hyper_graph.h:136
represent SE2
Definition: se2.h:40
const ParameterSE2Offset * offsetParam() const
2D pose Vertex, (x,y,theta)
Definition: vertex_se2.h:41
ParameterSE2Offset * _offsetTo
virtual bool write(std::ostream &os) const
write the vertex to a stream
bool setParameterId(int argNum, int paramId)
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
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
const SE2 & offset() const
int id() const
Definition: parameter.h:45
CacheSE2Offset * _cacheTo
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.
virtual bool resolveCaches()
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
ParameterSE2Offset * _offsetFrom
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual bool setMeasurementFromState()
SE2 inverse() const
invert :-)
Definition: se2.h:82
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
const Vector2D & translation() const
translational component
Definition: se2.h:54
const SE2 & n2w() const
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