Main Page
Namespaces
Classes
Files
File List
File Members
src
SceneObject.cpp
Go to the documentation of this file.
1
/*
2
* This file is part of OctoMap - An Efficient Probabilistic 3D Mapping
3
* Framework Based on Octrees
4
* http://octomap.github.io
5
*
6
* Copyright (c) 2009-2014, K.M. Wurm and A. Hornung, University of Freiburg
7
* All rights reserved. License for the viewer octovis: GNU GPL v2
8
* http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt
9
*
10
*
11
* This program is free software; you can redistribute it and/or modify
12
* it under the terms of the GNU General Public License as published by
13
* the Free Software Foundation; either version 2 of the License, or
14
* (at your option) any later version.
15
*
16
* This program is distributed in the hope that it will be useful, but
17
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
18
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
19
* for more details.
20
*
21
* You should have received a copy of the GNU General Public License
22
* along with this program. If not, see http://www.gnu.org/licenses/.
23
*/
24
25
#define NOMINMAX
26
#include <
octovis/SceneObject.h
>
27
28
#ifndef RAD2DEG
29
#define RAD2DEG(x) ((x) * 57.29577951308232087721)
30
#endif
31
32
namespace
octomap
{
33
34
SceneObject::SceneObject
() :
35
m_zMin(0.0), m_zMax(1.0), m_colorMode(CM_FLAT) {
36
}
37
38
void
SceneObject::heightMapColor
(
double
h, GLfloat* glArrayPos)
const
{
39
if
(
m_zMin
>=
m_zMax
)
40
h = 0.5;
41
else
{
42
h = (1.0 - std::min(std::max((h-
m_zMin
)/ (
m_zMax
-
m_zMin
), 0.0), 1.0)) *0.8;
43
}
44
45
// blend over HSV-values (more colors)
46
double
r, g, b;
47
double
s = 1.0;
48
double
v = 1.0;
49
50
h -= floor(h);
51
h *= 6;
52
int
i;
53
double
m, n, f;
54
55
i = floor(h);
56
f = h - i;
57
if
(!(i & 1))
58
f = 1 - f;
// if i is even
59
m = v * (1 - s);
60
n = v * (1 - s * f);
61
62
switch
(i) {
63
case
6:
64
case
0:
65
r = v; g = n; b = m;
66
break
;
67
case
1:
68
r = n; g = v; b = m;
69
break
;
70
case
2:
71
r = m; g = v; b = n;
72
break
;
73
case
3:
74
r = m; g = n; b = v;
75
break
;
76
case
4:
77
r = n; g = m; b = v;
78
break
;
79
case
5:
80
r = v; g = m; b = n;
81
break
;
82
default
:
83
r = 1; g = 0.5; b = 0.5;
84
break
;
85
}
86
87
glArrayPos[0] = r;
88
glArrayPos[1] = g;
89
glArrayPos[2] = b;
90
}
91
92
void
SceneObject::heightMapGray
(
double
h, GLfloat* glArrayPos)
const
{
93
if
(
m_zMin
>=
m_zMax
)
94
h = 0.5;
95
else
{
96
h = std::min(std::max((h-
m_zMin
)/ (
m_zMax
-
m_zMin
), 0.0), 1.0) * 0.4 + 0.3;
// h \in [0.3, 0.7]
97
}
98
99
glArrayPos[0] = h;
100
glArrayPos[1] = h;
101
glArrayPos[2] = h;
102
}
103
104
105
}
octomap
octomap::SceneObject::m_zMax
double m_zMax
Definition:
SceneObject.h:86
SceneObject.h
octomap::SceneObject::SceneObject
SceneObject()
Definition:
SceneObject.cpp:34
octomap::SceneObject::m_zMin
double m_zMin
Definition:
SceneObject.h:85
octomap::SceneObject::heightMapGray
void heightMapGray(double h, GLfloat *glArrayPos) const
Definition:
SceneObject.cpp:92
octomap::SceneObject::heightMapColor
void heightMapColor(double h, GLfloat *glArrayPos) const
Definition:
SceneObject.cpp:38
octovis
Author(s): Kai M. Wurm
, Armin Hornung
autogenerated on Wed Jun 5 2019 19:26:39