g2o
Loading...
Searching...
No Matches
vertex_se2.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 "vertex_se2.h"
28
29#include <typeinfo>
30
31#ifdef G2O_HAVE_OPENGL
34#endif
35
36namespace g2o {
37
39
40bool VertexSE2::read(std::istream& is) {
41 Vector3 p;
42 bool state = internal::readVector(is, p);
43 setEstimate(p);
44 return state;
45}
46
47bool VertexSE2::write(std::ostream& os) const {
48 return internal::writeVector(os, estimate().toVector());
49}
50
53
57 if (typeid(*element).name() != _typeName) return nullptr;
59 static_cast<WriteGnuplotAction::Parameters*>(params_);
60 if (!params || !params->os) {
61 return nullptr;
62 }
63
64 VertexSE2* v = static_cast<VertexSE2*>(element);
65 *(params->os) << v->estimate().translation().x() << " "
66 << v->estimate().translation().y() << " "
67 << v->estimate().rotation().angle() << std::endl;
68 return this;
69}
70
71#ifdef G2O_HAVE_OPENGL
72VertexSE2DrawAction::VertexSE2DrawAction()
73 : DrawAction(typeid(VertexSE2).name()),
74 _drawActions(nullptr),
75 _triangleX(nullptr),
76 _triangleY(nullptr) {}
77
78bool VertexSE2DrawAction::refreshPropertyPtrs(
79 HyperGraphElementAction::Parameters* params_) {
80 if (!DrawAction::refreshPropertyPtrs(params_)) return false;
81 if (_previousParams) {
82 _triangleX = _previousParams->makeProperty<FloatProperty>(
83 _typeName + "::TRIANGLE_X", .2f);
84 _triangleY = _previousParams->makeProperty<FloatProperty>(
85 _typeName + "::TRIANGLE_Y", .05f);
86 } else {
87 _triangleX = 0;
88 _triangleY = 0;
89 }
90 return true;
91}
92
93HyperGraphElementAction* VertexSE2DrawAction::operator()(
94 HyperGraph::HyperGraphElement* element,
95 HyperGraphElementAction::Parameters* params_) {
96 if (typeid(*element).name() != _typeName) return nullptr;
97 initializeDrawActionsCache();
98 refreshPropertyPtrs(params_);
99
100 if (!_previousParams) return this;
101
102 if (_show && !_show->value()) return this;
103
104 VertexSE2* that = static_cast<VertexSE2*>(element);
105
106 glColor3f(POSE_VERTEX_COLOR);
107 glPushMatrix();
108 glTranslatef((float)that->estimate().translation().x(),
109 (float)that->estimate().translation().y(), 0.f);
110 glRotatef((float)RAD2DEG(that->estimate().rotation().angle()), 0.f, 0.f, 1.f);
111 opengl::drawArrow2D((float)_triangleX->value(), (float)_triangleY->value(),
112 (float)_triangleX->value() * .3f);
113 drawCache(that->cacheContainer(), params_);
114 drawUserData(that->userData(), params_);
115 glPopMatrix();
116 return this;
117}
118#endif
119
120} // namespace g2o
Templatized BaseVertex.
Definition base_vertex.h:51
const EstimateType & estimate() const
return the current estimate of the vertex
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
Abstract action that operates on a graph entity.
represent SE2
Definition se2.h:43
const Vector2 & translation() const
translational component
Definition se2.h:57
const Rotation2D & rotation() const
rotational component
Definition se2.h:61
virtual HyperGraphElementAction * operator()(HyperGraph::HyperGraphElement *element, HyperGraphElementAction::Parameters *params_)
2D pose Vertex, (x,y,theta)
Definition vertex_se2.h:41
virtual bool read(std::istream &is)
read the vertex from a stream, i.e., the internal state of the vertex
virtual bool write(std::ostream &os) const
write the vertex to a stream
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VertexSE2()
#define RAD2DEG(x)
Definition macros.h:35
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
void drawArrow2D(float len, float head_width, float head_len)
VectorN< 3 > Vector3
Definition eigen_types.h:51
Property< float > FloatProperty
Definition property.h:150
#define POSE_VERTEX_COLOR