g2o
Loading...
Searching...
No Matches
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
28
30#include "vertex_se3.h"
31
32#ifdef G2O_HAVE_OPENGL
35#endif
36
37namespace g2o {
38
40
42 _offset = offset_;
43 _inverseOffset = _offset.inverse();
44}
45
46bool ParameterSE3Offset::read(std::istream& is) {
47 Vector7 off;
48 bool state = internal::readVector(is, off);
49 // normalize the quaternion to recover numerical precision lost by storing as
50 // human readable text
51 Vector4::MapType(off.data() + 3).normalize();
53 return state;
54}
55
56bool ParameterSE3Offset::write(std::ostream& os) const {
58}
59
60CacheSE3Offset::CacheSE3Offset() : Cache(), _offsetParam(0) {}
61
66
68 const VertexSE3* v = static_cast<const VertexSE3*>(vertex());
69 _n2w = v->estimate() * _offsetParam->offset();
70 _w2n = _n2w.inverse();
71 _w2l = v->estimate().inverse();
72}
73
77
78#ifdef G2O_HAVE_OPENGL
79CacheSE3OffsetDrawAction::CacheSE3OffsetDrawAction()
80 : DrawAction(typeid(CacheSE3Offset).name()) {
81 _previousParams = (DrawAction::Parameters*)0x42;
82 refreshPropertyPtrs(0);
83}
84
85bool CacheSE3OffsetDrawAction::refreshPropertyPtrs(
86 HyperGraphElementAction::Parameters* params_) {
87 if (!DrawAction::refreshPropertyPtrs(params_)) return false;
88 if (_previousParams) {
89 _cubeSide = _previousParams->makeProperty<FloatProperty>(
90 _typeName + "::CUBE_SIDE", .05f);
91 } else {
92 _cubeSide = 0;
93 }
94 return true;
95}
96
97HyperGraphElementAction* CacheSE3OffsetDrawAction::operator()(
98 HyperGraph::HyperGraphElement* element,
99 HyperGraphElementAction::Parameters* params_) {
100 if (typeid(*element).name() != _typeName) return nullptr;
101 CacheSE3Offset* that = static_cast<CacheSE3Offset*>(element);
102 refreshPropertyPtrs(params_);
103 if (!_previousParams) return this;
104
105 if (_show && !_show->value()) return this;
106 float cs = _cubeSide ? _cubeSide->value() : 1.0f;
107 glPushAttrib(GL_COLOR);
108 glColor3f(POSE_PARAMETER_COLOR);
109 glPushMatrix();
110 glMultMatrixd(that->offsetParam()->offset().cast<double>().data());
111 opengl::drawBox(cs, cs, cs);
112 glPopMatrix();
113 glPopAttrib();
114 return this;
115}
116#endif
117
118} // namespace g2o
const EstimateType & estimate() const
return the current estimate of the vertex
caching the offset related to a vertex
ParameterSE3Offset * _offsetParam
the parameter connected to the cache
virtual void updateImpl()
redefine this to do the update
void setOffsetParam(ParameterSE3Offset *offsetParam)
const ParameterSE3Offset * offsetParam() const
virtual bool resolveDependencies()
OptimizableGraph::Vertex * vertex()
Definition cache.cpp:57
ParameterVector _parameters
Definition cache.h:103
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
virtual bool write(std::ostream &os) const
write the data to a stream
void setOffset(const Isometry3 &offset_=Isometry3::Identity())
const Isometry3 & offset() const
rotation of the offset as 3x3 rotation matrix
virtual bool read(std::istream &is)
read the data from a stream
3D pose Vertex, represented as an Isometry3
Definition vertex_se3.h:50
Isometry3 fromVectorQT(const Vector7 &v)
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
Definition io_helper.h:36
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Definition io_helper.h:42
Vector7 toVectorQT(const Isometry3 &t)
void drawBox(GLfloat l, GLfloat w, GLfloat h)
VectorN< 7 > Vector7
Definition eigen_types.h:54
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Definition eigen_types.h:77
Property< float > FloatProperty
Definition property.h:150
#define POSE_PARAMETER_COLOR