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 #include "vertex_se3.h"
29 #include "isometry3d_gradients.h"
30 
31 #ifdef G2O_HAVE_OPENGL
34 #endif
35 
36 namespace g2o {
37 
39  setOffset();
40  }
41 
43  _offset = offset_;
44  _inverseOffset = _offset.inverse();
45  }
46 
47  bool ParameterSE3Offset::read(std::istream& is) {
48  Vector7d off;
49  for (int i=0; i<7; i++) {
50  is >> off[i];
51  }
52  // normalize the quaternion to recover numerical precision lost by storing as human readable text
53  Vector4D::MapType(off.data()+3).normalize();
55  return is.good();
56  }
57 
58  bool ParameterSE3Offset::write(std::ostream& os) const {
60  for (int i=0; i<7; i++)
61  os << off[i] << " ";
62  return os.good();
63  }
64 
66  Cache(),
67  _offsetParam(0)
68  {
69  }
70 
72  _offsetParam = dynamic_cast <ParameterSE3Offset*> (_parameters[0]);
73  return _offsetParam != 0;
74  }
75 
77  const VertexSE3* v = static_cast<const VertexSE3*>(vertex());
78  _n2w = v->estimate() * _offsetParam->offset();
79  _w2n = _n2w.inverse();
80  _w2l = v->estimate().inverse();
81  }
82 
84  {
86  }
87 
88 #ifdef G2O_HAVE_OPENGL
89  CacheSE3OffsetDrawAction::CacheSE3OffsetDrawAction(): DrawAction(typeid(CacheSE3Offset).name()){
90  _previousParams = (DrawAction::Parameters*)0x42;
91  refreshPropertyPtrs(0);
92  }
93 
94 
95  bool CacheSE3OffsetDrawAction::refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_){
96  if (! DrawAction::refreshPropertyPtrs(params_))
97  return false;
98  if (_previousParams){
99  _cubeSide = _previousParams->makeProperty<FloatProperty>(_typeName + "::CUBE_SIDE", .05f);
100  } else {
101  _cubeSide = 0;
102  }
103  return true;
104  }
105 
106  HyperGraphElementAction* CacheSE3OffsetDrawAction::operator()(HyperGraph::HyperGraphElement* element,
108  if (typeid(*element).name()!=_typeName)
109  return 0;
110  CacheSE3Offset* that = static_cast<CacheSE3Offset*>(element);
111  refreshPropertyPtrs(params_);
112  if (! _previousParams)
113  return this;
114 
115  if (_show && !_show->value())
116  return this;
117  float cs = _cubeSide ? _cubeSide->value() : 1.0f;
118  glPushAttrib(GL_COLOR);
119  glColor3f(POSE_PARAMETER_COLOR);
120  glPushMatrix();
121  glMultMatrixd(that->offsetParam()->offset().data());
122  opengl::drawBox(cs,cs,cs);
123  glPopMatrix();
124  glPopAttrib();
125  return this;
126  }
127 #endif
128 
129 } // end namespace
ParameterVector _parameters
Definition: cache.h:99
caching the offset related to a vertex
Isometry3D fromVectorQT(const Vector7d &v)
virtual void updateImpl()
redefine this to do the update
Abstract action that operates on a graph entity.
const ParameterSE3Offset * offsetParam() const
virtual bool resolveDependancies()
OptimizableGraph::Vertex * vertex()
Definition: cache.cpp:61
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
Eigen::Matrix< double, 7, 1 > Vector7d
Definition: sim3.h:35
void setOffsetParam(ParameterSE3Offset *offsetParam)
void setOffset(const Isometry3D &offset_=Isometry3D::Identity())
void drawBox(GLfloat l, GLfloat w, GLfloat h)
virtual bool read(std::istream &is)
read the data from a stream
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Definition: eigen_types.h:66
Eigen::Quaterniond & normalize(Eigen::Quaterniond &q)
#define POSE_PARAMETER_COLOR
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
3D pose Vertex, represented as an Isometry3D
Definition: vertex_se3.h:50
Vector7d toVectorQT(const Isometry3D &t)
virtual bool write(std::ostream &os) const
write the data to a stream