g2o
Loading...
Searching...
No Matches
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
30#include "g2o/core/cache.h"
33
34namespace g2o {
35
40 public:
43
44 virtual bool read(std::istream& is);
45 virtual bool write(std::ostream& os) const;
46
51 void setOffset(const Isometry3& offset_ = Isometry3::Identity());
52
54 const Isometry3& offset() const { return _offset; }
55
57 const Isometry3& inverseOffset() const { return _inverseOffset; }
58
59 protected:
62};
63
68 public:
71 virtual void updateImpl();
72
73 const ParameterSE3Offset* offsetParam() const { return _offsetParam; }
74 void setOffsetParam(ParameterSE3Offset* offsetParam);
75
76 const Isometry3& w2n() const { return _w2n; }
77 const Isometry3& n2w() const { return _n2w; }
78 const Isometry3& w2l() const { return _w2l; }
79
80 protected:
85
86 protected:
87 virtual bool resolveDependencies();
88};
89
90#ifdef G2O_HAVE_OPENGL
91class G2O_TYPES_SLAM3D_API CacheSE3OffsetDrawAction : public DrawAction {
92 public:
93 CacheSE3OffsetDrawAction();
94 virtual HyperGraphElementAction* operator()(
97
98 protected:
99 virtual bool refreshPropertyPtrs(
101 FloatProperty* _cubeSide;
102};
103#endif
104
105} // namespace g2o
106
107#endif
caching the offset related to a vertex
const Isometry3 & w2n() const
const Isometry3 & n2w() const
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
const Isometry3 & w2l() const
const ParameterSE3Offset * offsetParam() const
Abstract action that operates on a graph entity.
const Isometry3 & inverseOffset() const
rotation of the inverse offset as 3x3 rotation matrix
const Isometry3 & offset() const
rotation of the offset as 3x3 rotation matrix
#define G2O_TYPES_SLAM3D_API
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
Property< float > FloatProperty
Definition property.h:150