g2o
parameter_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 "parameter_se3_offset.h"
28 
29 #include "vertex_se3_quat.h"
31 
32 using namespace Eigen;
33 
34 namespace g2o {
35 namespace deprecated {
36 
37  ParameterSE3Offset::ParameterSE3Offset(){
38  setOffset();
39  }
40 
41  void ParameterSE3Offset::setOffset(const SE3Quat& offset_){
42  _offset = offset_;
43  _offsetMatrix= _offset.rotation().toRotationMatrix();
44  _offsetMatrix.translation() = _offset.translation();
45  _inverseOffsetMatrix = _offsetMatrix.inverse();
46  }
47 
48  bool ParameterSE3Offset::read(std::istream& is) {
49  Vector7d off;
50  for (int i=0; i<7; i++) {
51  is >> off[i];
52  std::cerr << off[i] << " " ;
53  }
54  std::cerr << std::endl;
55  setOffset(SE3Quat(off));
56  return is.good();
57  }
58 
59  bool ParameterSE3Offset::write(std::ostream& os) const {
60  Vector7d off = _offset.toVector();
61  for (int i=0; i<7; i++)
62  os << off[i] << " ";
63  return os.good();
64  }
65 
66  CacheSE3Offset::CacheSE3Offset() :
67  Cache(),
68  _offsetParam(0)
69  {
70  }
71 
73  _offsetParam = dynamic_cast <ParameterSE3Offset*> (_parameters[0]);
74  return _offsetParam != 0;
75  }
76 
78  const VertexSE3* v = static_cast<const VertexSE3*>(vertex());
80 
81  _n2w = _se3_n2w.rotation().toRotationMatrix();
82  _n2w.translation() = _se3_n2w.translation();
83 
85  _w2n = _se3_w2n.rotation().toRotationMatrix();
86  _w2n.translation() = _se3_w2n.translation();
87 
88  SE3Quat w2l = v->estimate().inverse();
89  _w2l = w2l.rotation().toRotationMatrix();
90  _w2l.translation() = w2l.translation();
91  }
92 
94  {
96  }
97 
98 #ifdef G2O_HAVE_OPENGL
99  CacheSE3OffsetDrawAction::CacheSE3OffsetDrawAction(): DrawAction(typeid(CacheSE3Offset).name()){
100  _previousParams = (DrawAction::Parameters*)0x42;
101  refreshPropertyPtrs(0);
102  }
103 
104 
105  bool CacheSE3OffsetDrawAction::refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_){
106  if (! DrawAction::refreshPropertyPtrs(params_))
107  return false;
108  if (_previousParams){
109  _cubeSide = _previousParams->makeProperty<FloatProperty>(_typeName + "::CUBE_SIDE", .05f);
110  } else {
111  _cubeSide = 0;
112  }
113  return true;
114  }
115 
116  HyperGraphElementAction* CacheSE3OffsetDrawAction::operator()(HyperGraph::HyperGraphElement* element,
118  if (typeid(*element).name()!=_typeName)
119  return 0;
120  CacheSE3Offset* that = static_cast<CacheSE3Offset*>(element);
121  refreshPropertyPtrs(params);
122  if (! _previousParams)
123  return this;
124 
125  if (_show && !_show->value())
126  return this;
127 
128  glPushMatrix();
129  const Vector3d& offsetT=that->offsetParam()->offset().translation();
130  AngleAxisd aa(that->offsetParam()->offset().rotation());
131  glTranslatef((float)offsetT.x(), (float)offsetT.y(), (float)offsetT.z());
132  glRotatef((float)RAD2DEG(aa.angle()),(float)aa.axis().x(),(float)aa.axis().y(),(float)aa.axis().z());
133  // if (_cubeSide)
134  // drawMyPyramid(_cubeSide->value(), _cubeSide->value());
135  glPopMatrix();
136 
137  return this;
138  }
139 #endif
140 
141 } // end namespace
142 } // end namespace
caching the offset related to a vertex
ParameterVector _parameters
Definition: cache.h:99
const SE3Quat & offset() const
return the offset as SE3Quat
Abstract action that operates on a graph entity.
void setOffsetParam(ParameterSE3Offset *offsetParam)
OptimizableGraph::Vertex * vertex()
Definition: cache.cpp:61
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
SE3Quat inverse() const
Definition: se3quat.h:120
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
Eigen::Isometry3d _w2l
world to local
const Eigen::Quaterniond & rotation() const
Definition: se3quat.h:97
3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vecto...
Eigen::Isometry3d _n2w
sensor to world
virtual void updateImpl()
redefine this to do the update
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
#define RAD2DEG(x)
Definition: macros.h:35
Eigen::Isometry3d _w2n
world to sensor transform
const ParameterSE3Offset * offsetParam() const
const Vector3D & translation() const
Definition: se3quat.h:93