g2o
parameter_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 "parameter_se2_offset.h"
28 #include "vertex_se2.h"
29 
30 #ifdef G2O_HAVE_OPENGL
32 #endif
33 
34 namespace g2o {
35 
37  setOffset();
38  }
39 
40  void ParameterSE2Offset::setOffset(const SE2& offset_){
41  _offset = offset_;
42  _offsetMatrix= _offset.rotation().toRotationMatrix();
43  _offsetMatrix.translation() = _offset.translation();
45  }
46 
47  bool ParameterSE2Offset::read(std::istream& is) {
48  Vector3D off;
49  for (int i=0; i<3; i++) {
50  is >> off[i];
51  std::cerr << off[i] << " " ;
52  }
53  std::cerr << std::endl;
54  setOffset(SE2(off));
55  return is.good() || is.eof();
56  }
57 
58  bool ParameterSE2Offset::write(std::ostream& os) const {
59  Vector3D off = _offset.toVector();
60  for (int i=0; i<3; i++)
61  os << off[i] << " ";
62  return os.good();
63  }
64 
66  Cache(),
67  _offsetParam(0)
68  {
69  }
70 
72  _offsetParam = dynamic_cast <ParameterSE2Offset*> (_parameters[0]);
73  return _offsetParam != 0;
74  }
75 
77  const VertexSE2* v = static_cast<const VertexSE2*>(vertex());
79 
80  _n2w = _se2_n2w.rotation().toRotationMatrix();
81  _n2w.translation() = _se2_n2w.translation();
82 
84  _w2n = _se2_w2n.rotation().toRotationMatrix();
85  _w2n.translation() = _se2_w2n.translation();
86 
87  SE2 w2l = v->estimate().inverse();
88  _w2l = w2l.rotation().toRotationMatrix();
89  _w2l.translation() = w2l.translation();
90 
91  double alpha=v->estimate().rotation().angle();
92  double c=cos(alpha), s=sin(alpha);
93  Matrix2D RInversePrime;
94  RInversePrime << -s, c, -c, -s;
95  _RpInverse_RInversePrime = _offsetParam->offset().rotation().toRotationMatrix().transpose()*RInversePrime;
97  }
98 
100  {
102  }
103 
104 
105 } // end namespace
ParameterVector _parameters
Definition: cache.h:99
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Definition: se2.h:108
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
OptimizableGraph::Vertex * vertex()
Definition: cache.cpp:61
represent SE2
Definition: se2.h:40
const ParameterSE2Offset * offsetParam() const
Eigen::Matrix< double, 2, 2, Eigen::ColMajor > Matrix2D
Definition: eigen_types.h:60
2D pose Vertex, (x,y,theta)
Definition: vertex_se2.h:41
virtual bool resolveDependancies()
ParameterSE2Offset * _offsetParam
the parameter connected to the cache
Isometry2D _w2n
world to sensor transform
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
Isometry2D _n2w
sensor to world
const SE2 & offset() const
Isometry2D _w2l
world to local
virtual bool read(std::istream &is)
read the data from a stream
void setOffset(const SE2 &offset_=SE2())
virtual bool write(std::ostream &os) const
write the data to a stream
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
void setOffsetParam(ParameterSE2Offset *offsetParam)
SE2 inverse() const
invert :-)
Definition: se2.h:82
virtual void updateImpl()
redefine this to do the update
const Vector2D & translation() const
translational component
Definition: se2.h:54