g2o
parameter_se3_offset.h
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 #ifndef G2O_VERTEX_SE3_OFFSET_PARAMETERS_H_
28 #define G2O_VERTEX_SE3_OFFSET_PARAMETERS_H_
29 
31 
33 #include "g2o/core/cache.h"
34 #include "g2o_types_slam3d_api.h"
35 
36 #include <Eigen/Geometry>
37 
38 namespace g2o {
39 
40  class VertexSE3;
41 
46  {
47  public:
50 
51  virtual bool read(std::istream& is);
52  virtual bool write(std::ostream& os) const;
53 
58  void setOffset(const Isometry3D& offset_=Isometry3D::Identity());
59 
61  const Isometry3D& offset() const { return _offset;}
62 
64  const Isometry3D& inverseOffset() const { return _inverseOffset;}
65 
66  protected:
69  };
70 
75  public:
78  virtual void updateImpl();
79 
80  const ParameterSE3Offset* offsetParam() const { return _offsetParam;}
81  void setOffsetParam(ParameterSE3Offset* offsetParam);
82 
83  const Isometry3D& w2n() const { return _w2n;}
84  const Isometry3D& n2w() const { return _n2w;}
85  const Isometry3D& w2l() const { return _w2l;}
86 
87  protected:
92 
93  protected:
94  virtual bool resolveDependancies();
95  };
96 
97 
98 #ifdef G2O_HAVE_OPENGL
99  class G2O_TYPES_SLAM3D_API CacheSE3OffsetDrawAction: public DrawAction{
100  public:
101  CacheSE3OffsetDrawAction();
102  virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element,
104  protected:
105  virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_);
106  FloatProperty* _cubeSide;
107  };
108 #endif
109 
110 }
111 
112 #endif
caching the offset related to a vertex
const Isometry3D & w2l() const
Abstract action that operates on a graph entity.
const ParameterSE3Offset * offsetParam() const
const Isometry3D & offset() const
rotation of the offset as 3x3 rotation matrix
const Isometry3D & w2n() const
const Isometry3D & inverseOffset() const
rotation of the inverse offset as 3x3 rotation matrix
#define G2O_TYPES_SLAM3D_API
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Definition: eigen_types.h:66
const Isometry3D & n2w() const
ParameterSE3Offset * _offsetParam
the parameter connected to the cache