g2o
Loading...
Searching...
No Matches
vertex_line3d.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_line3d.h"
28
29#include "g2o/stuff/misc.h"
31
32namespace g2o {
33
34VertexLine3D::VertexLine3D() : BaseVertex<4, Line3D>(), color(1., 0.5, 0.) {}
35
36bool VertexLine3D::read(std::istream& is) {
37 Vector6 lv;
38 bool state = internal::readVector(is, lv);
40 return state;
41}
42
43bool VertexLine3D::write(std::ostream& os) const {
45}
46
47#ifdef G2O_HAVE_OPENGL
48VertexLine3DDrawAction::VertexLine3DDrawAction()
49 : DrawAction(typeid(VertexLine3D).name()),
50 _lineLength(nullptr),
51 _lineWidth(nullptr) {}
52
53bool VertexLine3DDrawAction::refreshPropertyPtrs(
54 HyperGraphElementAction::Parameters* params_) {
55 if (!DrawAction::refreshPropertyPtrs(params_)) {
56 return false;
57 }
58 if (_previousParams) {
59 _lineLength = _previousParams->makeProperty<FloatProperty>(
60 _typeName + "::LINE_LENGTH", 15);
61 _lineWidth = _previousParams->makeProperty<FloatProperty>(
62 _typeName + "::LINE_WIDTH", 5);
63 } else {
64 _lineLength = 0;
65 _lineWidth = 0;
66 }
67 return true;
68}
69
70HyperGraphElementAction* VertexLine3DDrawAction::operator()(
71 HyperGraph::HyperGraphElement* element,
72 HyperGraphElementAction::Parameters* params_) {
73 if (typeid(*element).name() != _typeName) {
74 return nullptr;
75 }
76
77 refreshPropertyPtrs(params_);
78 if (!_previousParams) {
79 return this;
80 }
81
82 if (_show && !_show->value()) {
83 return this;
84 }
85
86 VertexLine3D* that = static_cast<VertexLine3D*>(element);
87 Line3D line = that->estimate();
88 line.normalize();
89 Vector3 direction = line.d();
90 Vector3 npoint = line.d().cross(line.w());
91 glPushMatrix();
92 glColor3f(float(that->color(0)), float(that->color(1)),
93 float(that->color(2)));
94 if (_lineLength && _lineWidth) {
95 glLineWidth(float(_lineWidth->value()));
96 glBegin(GL_LINES);
97 glNormal3f(float(npoint.x()), float(npoint.y()), float(npoint.z()));
98 glVertex3f(float(npoint.x() - direction.x() * _lineLength->value() / 2),
99 float(npoint.y() - direction.y() * _lineLength->value() / 2),
100 float(npoint.z() - direction.z() * _lineLength->value() / 2));
101 glVertex3f(float(npoint.x() + direction.x() * _lineLength->value() / 2),
102 float(npoint.y() + direction.y() * _lineLength->value() / 2),
103 float(npoint.z() + direction.z() * _lineLength->value() / 2));
104 glEnd();
105 }
106 glPopMatrix();
107
108 return this;
109}
110#endif
111
112} // namespace g2o
Templatized BaseVertex.
Definition base_vertex.h:51
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters *params_)
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
some general case utility functions
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
VectorN< 3 > Vector3
Definition eigen_types.h:51
VectorN< 6 > Vector6
Definition eigen_types.h:53
Property< float > FloatProperty
Definition property.h:150