Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #define NOMINMAX
00026 #include <octovis/SceneObject.h>
00027
00028 #ifndef RAD2DEG
00029 #define RAD2DEG(x) ((x) * 57.29577951308232087721)
00030 #endif
00031
00032 namespace octomap {
00033
00034 SceneObject::SceneObject() :
00035 m_zMin(0.0), m_zMax(1.0), m_colorMode(CM_FLAT) {
00036 }
00037
00038 void SceneObject::heightMapColor(double h, GLfloat* glArrayPos) const {
00039 if (m_zMin >= m_zMax)
00040 h = 0.5;
00041 else{
00042 h = (1.0 - std::min(std::max((h-m_zMin)/ (m_zMax - m_zMin), 0.0), 1.0)) *0.8;
00043 }
00044
00045
00046 double r, g, b;
00047 double s = 1.0;
00048 double v = 1.0;
00049
00050 h -= floor(h);
00051 h *= 6;
00052 int i;
00053 double m, n, f;
00054
00055 i = floor(h);
00056 f = h - i;
00057 if (!(i & 1))
00058 f = 1 - f;
00059 m = v * (1 - s);
00060 n = v * (1 - s * f);
00061
00062 switch (i) {
00063 case 6:
00064 case 0:
00065 r = v; g = n; b = m;
00066 break;
00067 case 1:
00068 r = n; g = v; b = m;
00069 break;
00070 case 2:
00071 r = m; g = v; b = n;
00072 break;
00073 case 3:
00074 r = m; g = n; b = v;
00075 break;
00076 case 4:
00077 r = n; g = m; b = v;
00078 break;
00079 case 5:
00080 r = v; g = m; b = n;
00081 break;
00082 default:
00083 r = 1; g = 0.5; b = 0.5;
00084 break;
00085 }
00086
00087 glArrayPos[0] = r;
00088 glArrayPos[1] = g;
00089 glArrayPos[2] = b;
00090 }
00091
00092 void SceneObject::heightMapGray(double h, GLfloat* glArrayPos) const {
00093 if (m_zMin >= m_zMax)
00094 h = 0.5;
00095 else{
00096 h = std::min(std::max((h-m_zMin)/ (m_zMax - m_zMin), 0.0), 1.0) * 0.4 + 0.3;
00097 }
00098
00099 glArrayPos[0] = h;
00100 glArrayPos[1] = h;
00101 glArrayPos[2] = h;
00102 }
00103
00104
00105 }