OcTreeDrawer.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 #include <octovis/OcTreeDrawer.h>
26 
27 #define OTD_RAD2DEG 57.2957795
28 
29 namespace octomap {
30 
32  m_occupiedThresSize(0), m_freeThresSize(0),
33  m_occupiedSize(0), m_freeSize(0), m_selectionSize(0),
34  octree_grid_vertex_size(0), m_alphaOccupied(0.8), map_id(0)
35  {
37  m_drawOccupied = true;
38  m_drawOcTreeGrid = false;
39  m_drawFree = false;
40  m_drawSelection = true;
41  m_displayAxes = false;
42 
43  m_occupiedArray = NULL;
44  m_freeArray = NULL;
45  m_occupiedThresArray = NULL;
46  m_freeThresArray = NULL;
47  m_occupiedColorArray = NULL;
49  m_selectionArray = NULL;
50 
51  // origin and movement
52  initial_origin = octomap::pose6d(0,0,0,0,0,0);
54  }
55 
57  clear();
58  }
59 
60  void OcTreeDrawer::draw() const {
61 
62  // push current status
63  glPushMatrix();
64  // octomap::pose6d relative_transform = origin * initial_origin.inv();
65 
66  octomap::pose6d relative_transform = origin;// * initial_origin;
67 
68  // apply relative transform
69  const octomath::Quaternion& q = relative_transform.rot();
70  glTranslatef(relative_transform.x(), relative_transform.y(), relative_transform.z());
71 
72  // convert quaternion to angle/axis notation
73  float scale = sqrt(q.x() * q.x() + q.y() * q.y() + q.z() * q.z());
74  if (scale) {
75  float axis_x = q.x() / scale;
76  float axis_y = q.y() / scale;
77  float axis_z = q.z() / scale;
78  float angle = acos(q.u()) * 2.0f * OTD_RAD2DEG; // opengl expects DEG
79  glRotatef(angle, axis_x, axis_y, axis_z);
80  }
81 
82  glEnableClientState(GL_VERTEX_ARRAY);
83 
84  if (m_drawOccupied)
86  if (m_drawFree)
88  if (m_drawOcTreeGrid)
90  if (m_drawSelection)
91  drawSelection();
92 
93  if (m_displayAxes) {
94  drawAxes();
95  }
96 
97  glDisableClientState(GL_VERTEX_ARRAY);
98 
99  // reset previous status
100  glPopMatrix();
101 
102  }
103 
104  void OcTreeDrawer::setAlphaOccupied(double alpha){
105  m_alphaOccupied = alpha;
106  }
107 
108 
109  void OcTreeDrawer::setOcTree(const AbstractOcTree& tree, const pose6d& origin, int map_id_) {
110 
111  const OcTree& octree = (const OcTree&) tree;
112  this->map_id = map_id_;
113 
114  // save origin used during cube generation
115  this->initial_origin = octomap::pose6d(octomap::point3d(0,0,0), origin.rot());
116 
117  // origin is in global coords
118  this->origin = origin;
119 
120  // maximum size to prevent crashes on large maps: (should be checked in a better way than a constant)
121  bool showAll = (octree.size() < 5 * 1e6);
122  bool uses_origin = ( (origin.rot().x() != 0.) && (origin.rot().y() != 0.)
123  && (origin.rot().z() != 0.) && (origin.rot().u() != 1.) );
124 
125  // walk the tree one to find the number of nodes in each category
126  // (this is used to set up the OpenGL arrays)
127  // TODO: this step may be left out, if we maintained the GLArrays in std::vectors instead...
128  unsigned int cnt_occupied(0), cnt_occupied_thres(0), cnt_free(0), cnt_free_thres(0);
129  for(OcTree::tree_iterator it = octree.begin_tree(this->m_max_tree_depth),
130  end=octree.end_tree(); it!= end; ++it) {
131  if (it.isLeaf()) {
132  if (octree.isNodeOccupied(*it)){ // occupied voxels
133  if (octree.isNodeAtThreshold(*it)) ++cnt_occupied_thres;
134  else ++cnt_occupied;
135  }
136  else if (showAll) { // freespace voxels
137  if (octree.isNodeAtThreshold(*it)) ++cnt_free_thres;
138  else ++cnt_free;
139  }
140  }
141  }
142  // setup GL arrays for cube quads and cube colors
145  initGLArrays(cnt_free , m_freeSize , &m_freeArray, NULL);
146  initGLArrays(cnt_free_thres , m_freeThresSize , &m_freeThresArray, NULL);
147 
148  double minX, minY, minZ, maxX, maxY, maxZ;
149  octree.getMetricMin(minX, minY, minZ);
150  octree.getMetricMax(maxX, maxY, maxZ);
151 
152  // set min/max Z for color height map
153  m_zMin = minZ;
154  m_zMax = maxZ;
155 
156  std::vector<octomath::Vector3> cube_template;
157  initCubeTemplate(origin, cube_template);
158 
159  unsigned int idx_occupied(0), idx_occupied_thres(0), idx_free(0), idx_free_thres(0);
160  unsigned int color_idx_occupied(0), color_idx_occupied_thres(0);
161 
162  m_grid_voxels.clear();
163  OcTreeVolume voxel; // current voxel, possibly transformed
164  for(OcTree::tree_iterator it = octree.begin_tree(this->m_max_tree_depth),
165  end=octree.end_tree(); it!= end; ++it) {
166 
167  if (it.isLeaf()) { // voxels for leaf nodes
168  if (uses_origin)
169  voxel = OcTreeVolume(origin.rot().rotate(it.getCoordinate()), it.getSize());
170  else
171  voxel = OcTreeVolume(it.getCoordinate(), it.getSize());
172 
173  if (octree.isNodeOccupied(*it)){ // occupied voxels
174  if (octree.isNodeAtThreshold(*it)) {
175  idx_occupied_thres = generateCube(voxel, cube_template, idx_occupied_thres, &m_occupiedThresArray);
176  color_idx_occupied_thres = setCubeColorHeightmap(voxel, color_idx_occupied_thres, &m_occupiedThresColorArray);
177  }
178  else {
179  idx_occupied = generateCube(voxel, cube_template, idx_occupied, &m_occupiedArray);
180  color_idx_occupied = setCubeColorHeightmap(voxel, color_idx_occupied, &m_occupiedColorArray);
181  }
182  }
183  else if (showAll) { // freespace voxels
184  if (octree.isNodeAtThreshold(*it)) {
185  idx_free_thres = generateCube(voxel, cube_template, idx_free_thres, &m_freeThresArray);
186  }
187  else {
188  idx_free = generateCube(voxel, cube_template, idx_free, &m_freeArray);
189  }
190  }
191  }
192 
193  else { // inner node voxels (for grid structure only)
194  if (showAll) {
195  if (uses_origin)
196  voxel = OcTreeVolume(origin.rot().rotate(it.getCoordinate()), it.getSize());
197  else
198  voxel = OcTreeVolume(it.getCoordinate(), it.getSize());
199  m_grid_voxels.push_back(voxel);
200  }
201  }
202  } // end for all voxels
203 
205 
206  if(m_drawOcTreeGrid)
208  }
209 
210  void OcTreeDrawer::setOcTreeSelection(const std::list<octomap::OcTreeVolume>& selectedVoxels){
211  generateCubes(selectedVoxels, &m_selectionArray, m_selectionSize, this->origin);
212  }
213 
216  }
217 
218  void OcTreeDrawer::initGLArrays(const unsigned int& num_cubes,
219  unsigned int& glArraySize,
220  GLfloat*** glArray, GLfloat** glColorArray) {
221 
222  clearCubes(glArray, glArraySize, glColorArray);
223 
224  // store size of GL arrays for drawing
225  glArraySize = num_cubes * 4 * 3;
226 
227  // allocate cube arrays, 6 quads per cube
228  *glArray = new GLfloat* [6];
229  for (unsigned i = 0; i<6; ++i){
230  (*glArray)[i] = new GLfloat[glArraySize];
231  }
232  // setup quad color array, if given
233  if (glColorArray != NULL)
234  *glColorArray = new GLfloat[glArraySize * 4 *4];
235  }
236 
238  std::vector<octomath::Vector3>& cube_template) {
239  cube_template.clear();
240  cube_template.reserve(24);
241 
242  cube_template.push_back(octomath::Vector3( 1, 1,-1));
243  cube_template.push_back(octomath::Vector3( 1,-1,-1));
244  cube_template.push_back(octomath::Vector3( 1, 1,-1));
245  cube_template.push_back(octomath::Vector3(-1, 1,-1));
246  cube_template.push_back(octomath::Vector3( 1, 1,-1));
247  cube_template.push_back(octomath::Vector3( 1, 1, 1));
248 
249  cube_template.push_back(octomath::Vector3(-1, 1,-1));
250  cube_template.push_back(octomath::Vector3(-1,-1,-1));
251  cube_template.push_back(octomath::Vector3( 1, 1, 1));
252  cube_template.push_back(octomath::Vector3(-1, 1, 1));
253  cube_template.push_back(octomath::Vector3( 1,-1,-1));
254  cube_template.push_back(octomath::Vector3( 1,-1, 1));
255 
256  cube_template.push_back(octomath::Vector3(-1, 1, 1));
257  cube_template.push_back(octomath::Vector3(-1,-1, 1));
258  cube_template.push_back(octomath::Vector3( 1,-1, 1));
259  cube_template.push_back(octomath::Vector3(-1,-1, 1));
260  cube_template.push_back(octomath::Vector3(-1,-1,-1));
261  cube_template.push_back(octomath::Vector3(-1,-1, 1));
262 
263  cube_template.push_back(octomath::Vector3( 1, 1, 1));
264  cube_template.push_back(octomath::Vector3( 1,-1, 1));
265  cube_template.push_back(octomath::Vector3( 1,-1,-1));
266  cube_template.push_back(octomath::Vector3(-1,-1,-1));
267  cube_template.push_back(octomath::Vector3(-1, 1,-1));
268  cube_template.push_back(octomath::Vector3(-1, 1, 1));
269  }
270 
272  const std::vector<octomath::Vector3>& cube_template,
273  const unsigned int& current_array_idx,
274  GLfloat*** glArray) {
275 
276  // epsilon to be substracted from cube size so that neighboring planes don't overlap
277  // seems to introduce strange artifacts nevertheless...
278  double eps = 1e-5;
279 
281 
282  double half_cube_size = GLfloat(v.second /2.0 -eps);
283  unsigned int i = current_array_idx;
284  // Cube surfaces are in gl_array in order: back, front, top, down, left, right.
285  // Arrays are filled in parallel (increasing i for all at once)
286  // One color array for all surfaces is filled when requested
287 
288  p = v.first + cube_template[0] * half_cube_size;
289  (*glArray)[0][i] = p.x();
290  (*glArray)[0][i+1] = p.y();
291  (*glArray)[0][i+2] = p.z();
292 
293  p = v.first + cube_template[1] * half_cube_size;
294  (*glArray)[1][i] = p.x();
295  (*glArray)[1][i+1] = p.y();
296  (*glArray)[1][i+2] = p.z();
297 
298  p = v.first + cube_template[2] * half_cube_size;
299  (*glArray)[2][i] = p.x();
300  (*glArray)[2][i+1] = p.y();
301  (*glArray)[2][i+2] = p.z();
302 
303  p = v.first + cube_template[3] * half_cube_size;
304  (*glArray)[3][i] = p.x();
305  (*glArray)[3][i+1] = p.y();
306  (*glArray)[3][i+2] = p.z();
307 
308  p = v.first + cube_template[4] * half_cube_size;
309  (*glArray)[4][i] = p.x();
310  (*glArray)[4][i+1] = p.y();
311  (*glArray)[4][i+2] = p.z();
312 
313  p = v.first + cube_template[5] * half_cube_size;
314  (*glArray)[5][i] = p.x();
315  (*glArray)[5][i+1] = p.y();
316  (*glArray)[5][i+2] = p.z();
317  i+= 3; //-------------------
318 
319  p = v.first + cube_template[6] * half_cube_size;
320  (*glArray)[0][i] = p.x();
321  (*glArray)[0][i+1] = p.y();
322  (*glArray)[0][i+2] = p.z();
323 
324  p = v.first + cube_template[7] * half_cube_size;
325  (*glArray)[1][i] = p.x();
326  (*glArray)[1][i+1] = p.y();
327  (*glArray)[1][i+2] = p.z();
328 
329  p = v.first + cube_template[8] * half_cube_size;
330  (*glArray)[2][i] = p.x();
331  (*glArray)[2][i+1] = p.y();
332  (*glArray)[2][i+2] = p.z();
333 
334  p = v.first + cube_template[9] * half_cube_size;
335  (*glArray)[3][i] = p.x();
336  (*glArray)[3][i+1] = p.y();
337  (*glArray)[3][i+2] = p.z();
338 
339  p = v.first + cube_template[10] * half_cube_size;
340  (*glArray)[4][i] = p.x();
341  (*glArray)[4][i+1] = p.y();
342  (*glArray)[4][i+2] = p.z();
343 
344  p = v.first + cube_template[11] * half_cube_size;
345  (*glArray)[5][i] = p.x();
346  (*glArray)[5][i+1] = p.y();
347  (*glArray)[5][i+2] = p.z();
348  i+= 3; //-------------------
349 
350  p = v.first + cube_template[12] * half_cube_size;
351  (*glArray)[0][i] = p.x();
352  (*glArray)[0][i+1] = p.y();
353  (*glArray)[0][i+2] = p.z();
354 
355  p = v.first + cube_template[13] * half_cube_size;
356  (*glArray)[1][i] = p.x();
357  (*glArray)[1][i+1] = p.y();
358  (*glArray)[1][i+2] = p.z();
359 
360  p = v.first + cube_template[14] * half_cube_size;
361  (*glArray)[2][i] = p.x();
362  (*glArray)[2][i+1] = p.y();
363  (*glArray)[2][i+2] = p.z();
364 
365  p = v.first + cube_template[15] * half_cube_size;
366  (*glArray)[3][i] = p.x();
367  (*glArray)[3][i+1] = p.y();
368  (*glArray)[3][i+2] = p.z();
369 
370  p = v.first + cube_template[16] * half_cube_size;
371  (*glArray)[4][i] = p.x();
372  (*glArray)[4][i+1] = p.y();
373  (*glArray)[4][i+2] = p.z();
374 
375  p = v.first + cube_template[17] * half_cube_size;
376  (*glArray)[5][i] = p.x();
377  (*glArray)[5][i+1] = p.y();
378  (*glArray)[5][i+2] = p.z();
379  i+= 3; //-------------------
380 
381  p = v.first + cube_template[18] * half_cube_size;
382  (*glArray)[0][i] = p.x();
383  (*glArray)[0][i+1] = p.y();
384  (*glArray)[0][i+2] = p.z();
385 
386  p = v.first + cube_template[19] * half_cube_size;
387  (*glArray)[1][i] = p.x();
388  (*glArray)[1][i+1] = p.y();
389  (*glArray)[1][i+2] = p.z();
390 
391  p = v.first + cube_template[20] * half_cube_size;
392  (*glArray)[2][i] = p.x();
393  (*glArray)[2][i+1] = p.y();
394  (*glArray)[2][i+2] = p.z();
395 
396  p = v.first + cube_template[21] * half_cube_size;
397  (*glArray)[3][i] = p.x();
398  (*glArray)[3][i+1] = p.y();
399  (*glArray)[3][i+2] = p.z();
400 
401  p = v.first + cube_template[22] * half_cube_size;
402  (*glArray)[4][i] = p.x();
403  (*glArray)[4][i+1] = p.y();
404  (*glArray)[4][i+2] = p.z();
405 
406  p = v.first + cube_template[23] * half_cube_size;
407  (*glArray)[5][i] = p.x();
408  (*glArray)[5][i+1] = p.y();
409  (*glArray)[5][i+2] = p.z();
410  i += 3; //-------------------
411 
412  return i; // updated array idx
413  }
414 
415 
417  const unsigned int& current_array_idx,
418  GLfloat** glColorArray) {
419 
420  if (glColorArray == NULL) return current_array_idx;
421 
422  unsigned int colorIdx = current_array_idx;
423  // color for all 4 vertices (same height)
424  for (int k = 0; k < 4; ++k) {
426  SceneObject::heightMapGray(v.first.z(), *glColorArray + colorIdx); // sets r,g,b
427  else
428  SceneObject::heightMapColor(v.first.z(), *glColorArray + colorIdx); // sets r,g,b
429  // set Alpha value:
430  (*glColorArray)[colorIdx + 3] = m_alphaOccupied;
431  colorIdx += 4;
432  }
433  return colorIdx;
434  }
435 
436  unsigned int OcTreeDrawer::setCubeColorRGBA(const unsigned char& r,
437  const unsigned char& g,
438  const unsigned char& b,
439  const unsigned char& a,
440  const unsigned int& current_array_idx,
441  GLfloat** glColorArray) {
442 
443  if (glColorArray == NULL) return current_array_idx;
444  unsigned int colorIdx = current_array_idx;
445  // set color for next 4 vertices (=one quad)
446  for (int k = 0; k < 4; ++k) {
447  (*glColorArray)[colorIdx ] = (double) r/255.;
448  (*glColorArray)[colorIdx + 1] = (double) g/255.;
449  (*glColorArray)[colorIdx + 2] = (double) b/255.;
450  (*glColorArray)[colorIdx + 3] = (double) a/255.;
451  colorIdx += 4;
452  }
453  return colorIdx;
454  }
455 
456 
457  void OcTreeDrawer::clearCubes(GLfloat*** glArray,
458  unsigned int& glArraySize,
459  GLfloat** glColorArray) {
460  if (glArraySize != 0) {
461  for (unsigned i = 0; i < 6; ++i) {
462  delete[] (*glArray)[i];
463  }
464  delete[] *glArray;
465  *glArray = NULL;
466  glArraySize = 0;
467  }
468  if (glColorArray != NULL && *glColorArray != NULL) {
469  delete[] *glColorArray;
470  *glColorArray = NULL;
471  }
472  }
473 
474 
475  // still used for "selection" nodes
476  void OcTreeDrawer::generateCubes(const std::list<octomap::OcTreeVolume>& voxels,
477  GLfloat*** glArray, unsigned int& glArraySize,
479  GLfloat** glColorArray) {
480  unsigned int i = 0;
481  unsigned int colorIdx = 0;
482 
483  std::vector<octomath::Vector3> cube_template;
484  initCubeTemplate(origin, cube_template);
485 
486  for (std::list<octomap::OcTreeVolume>::const_iterator it=voxels.begin();
487  it != voxels.end(); it++) {
488  i = generateCube(*it, cube_template, i, glArray);
489  }
490 
491  if (glColorArray != NULL) {
492  for (std::list<octomap::OcTreeVolume>::const_iterator it=voxels.begin();
493  it != voxels.end(); it++) {
494  colorIdx = setCubeColorHeightmap(*it, colorIdx, glColorArray);
495  }
496  }
497  }
498 
500 
501  if (m_octree_grid_vis_initialized) return;
502 
504  // allocate arrays for octree grid visualization
505  octree_grid_vertex_size = m_grid_voxels.size() * 12 * 2 * 3;
507 
508  // generate the cubes, 12 lines each
509  std::list<octomap::OcTreeVolume>::iterator it_rec;
510  unsigned int i = 0;
511  double x,y,z;
512  for (it_rec=m_grid_voxels.begin(); it_rec != m_grid_voxels.end(); it_rec++) {
513 
514  x = it_rec->first.x();
515  y = it_rec->first.y();
516  z = it_rec->first.z();
517 
518  double half_voxel_size = it_rec->second / 2.0;
519 
520  // ----
521  octree_grid_vertex_array[i] = x + half_voxel_size;
522  octree_grid_vertex_array[i+1] = y + half_voxel_size;
523  octree_grid_vertex_array[i+2] = z - half_voxel_size;
524  i+= 3;
525  octree_grid_vertex_array[i] = x - half_voxel_size;
526  octree_grid_vertex_array[i+1] = y + half_voxel_size;
527  octree_grid_vertex_array[i+2] = z - half_voxel_size;
528  i+= 3;
529  octree_grid_vertex_array[i] = x - half_voxel_size;
530  octree_grid_vertex_array[i+1] = y + half_voxel_size;
531  octree_grid_vertex_array[i+2] = z - half_voxel_size;
532  i += 3;
533  octree_grid_vertex_array[i] = x - half_voxel_size;
534  octree_grid_vertex_array[i+1] = y + half_voxel_size;
535  octree_grid_vertex_array[i+2] = z + half_voxel_size;
536  i+= 3;
537  octree_grid_vertex_array[i] = x - half_voxel_size;
538  octree_grid_vertex_array[i+1] = y + half_voxel_size;
539  octree_grid_vertex_array[i+2] = z + half_voxel_size;
540  i+= 3;
541  octree_grid_vertex_array[i] = x + half_voxel_size;
542  octree_grid_vertex_array[i+1] = y + half_voxel_size;
543  octree_grid_vertex_array[i+2] = z + half_voxel_size;
544  i+= 3;
545  octree_grid_vertex_array[i] = x + half_voxel_size;
546  octree_grid_vertex_array[i+1] = y + half_voxel_size;
547  octree_grid_vertex_array[i+2] = z + half_voxel_size;
548  i+= 3;
549  octree_grid_vertex_array[i] = x + half_voxel_size;
550  octree_grid_vertex_array[i+1] = y + half_voxel_size;
551  octree_grid_vertex_array[i+2] = z - half_voxel_size;
552  i+= 3;
553  // ----
554  octree_grid_vertex_array[i] = x + half_voxel_size;
555  octree_grid_vertex_array[i+1] = y - half_voxel_size;
556  octree_grid_vertex_array[i+2] = z + half_voxel_size;
557  i+= 3;
558  octree_grid_vertex_array[i] = x - half_voxel_size;
559  octree_grid_vertex_array[i+1] = y - half_voxel_size;
560  octree_grid_vertex_array[i+2] = z + half_voxel_size;
561  i+= 3;
562  octree_grid_vertex_array[i] = x - half_voxel_size;
563  octree_grid_vertex_array[i+1] = y - half_voxel_size;
564  octree_grid_vertex_array[i+2] = z + half_voxel_size;
565  i+= 3;
566  octree_grid_vertex_array[i] = x - half_voxel_size;
567  octree_grid_vertex_array[i+1] = y - half_voxel_size;
568  octree_grid_vertex_array[i+2] = z - half_voxel_size;
569  i+= 3;
570  octree_grid_vertex_array[i] = x - half_voxel_size;
571  octree_grid_vertex_array[i+1] = y - half_voxel_size;
572  octree_grid_vertex_array[i+2] = z - half_voxel_size;
573  i+= 3;
574  octree_grid_vertex_array[i] = x + half_voxel_size;
575  octree_grid_vertex_array[i+1] = y - half_voxel_size;
576  octree_grid_vertex_array[i+2] = z - half_voxel_size;
577  i+= 3;
578  octree_grid_vertex_array[i] = x + half_voxel_size;
579  octree_grid_vertex_array[i+1] = y - half_voxel_size;
580  octree_grid_vertex_array[i+2] = z - half_voxel_size;
581  i+= 3;
582  octree_grid_vertex_array[i] = x + half_voxel_size;
583  octree_grid_vertex_array[i+1] = y - half_voxel_size;
584  octree_grid_vertex_array[i+2] = z + half_voxel_size;
585  i+= 3;
586  // ----
587  octree_grid_vertex_array[i] = x + half_voxel_size;
588  octree_grid_vertex_array[i+1] = y + half_voxel_size;
589  octree_grid_vertex_array[i+2] = z - half_voxel_size;
590  i+= 3;
591  octree_grid_vertex_array[i] = x + half_voxel_size;
592  octree_grid_vertex_array[i+1] = y - half_voxel_size;
593  octree_grid_vertex_array[i+2] = z - half_voxel_size;
594  i+= 3;
595  octree_grid_vertex_array[i] = x - half_voxel_size;
596  octree_grid_vertex_array[i+1] = y + half_voxel_size;
597  octree_grid_vertex_array[i+2] = z - half_voxel_size;
598  i+= 3;
599  octree_grid_vertex_array[i] = x - half_voxel_size;
600  octree_grid_vertex_array[i+1] = y - half_voxel_size;
601  octree_grid_vertex_array[i+2] = z - half_voxel_size;
602  i+= 3;
603  octree_grid_vertex_array[i] = x - half_voxel_size;
604  octree_grid_vertex_array[i+1] = y + half_voxel_size;
605  octree_grid_vertex_array[i+2] = z + half_voxel_size;
606  i+= 3;
607  octree_grid_vertex_array[i] = x - half_voxel_size;
608  octree_grid_vertex_array[i+1] = y - half_voxel_size;
609  octree_grid_vertex_array[i+2] = z + half_voxel_size;
610  i+= 3;
611  octree_grid_vertex_array[i] = x + half_voxel_size;
612  octree_grid_vertex_array[i+1] = y + half_voxel_size;
613  octree_grid_vertex_array[i+2] = z + half_voxel_size;
614  i+= 3;
615  octree_grid_vertex_array[i] = x + half_voxel_size;
616  octree_grid_vertex_array[i+1] = y - half_voxel_size;
617  octree_grid_vertex_array[i+2] = z + half_voxel_size;
618  i+= 3;
619  // ----
620  }
622  }
623 
625  if (octree_grid_vertex_size != 0) {
626  delete[] octree_grid_vertex_array;
628  }
630  }
631 
633  //clearOcTree();
640  }
641 
642 
644 
645  if (m_colorMode == CM_SEMANTIC) {
646  // hardcoded mapping id -> colors
647  if (this->map_id == 0) { // background
648  glColor3f(0.784f, 0.66f, 0); // gold
649  }
650  else if (this->map_id == 1) { // table
651  glColor3f(0.68f, 0., 0.62f); // purple
652  }
653  else { // object
654  glColor3f(0., 0.784f, 0.725f); // cyan
655  }
657  }
658  else {
659  // colors for printout mode:
660  if (m_colorMode == CM_PRINTOUT) {
661  if (!m_drawFree) { // gray on white background
662  glColor3f(0.6f, 0.6f, 0.6f);
663  }
664  else {
665  glColor3f(0.1f, 0.1f, 0.1f);
666  }
667  }
668 
669  // draw binary occupied cells
670  if (m_occupiedThresSize != 0) {
671  if (m_colorMode != CM_PRINTOUT) glColor4f(0.0f, 0.0f, 1.0f, m_alphaOccupied);
673  }
674 
675  // draw delta occupied cells
676  if (m_occupiedSize != 0) {
677  if (m_colorMode != CM_PRINTOUT) glColor4f(0.2f, 0.7f, 1.0f, m_alphaOccupied);
679  }
680  }
681  }
682 
683 
685 
686  if (m_colorMode == CM_PRINTOUT) {
687  if (!m_drawOccupied) { // gray on white background
688  glColor3f(0.5f, 0.5f, 0.5f);
689  }
690  else {
691  glColor3f(0.9f, 0.9f, 0.9f);
692  }
693  }
694 
695  // draw binary freespace cells
696  if (m_freeThresSize != 0) {
697  if (m_colorMode != CM_PRINTOUT) glColor4f(0.0f, 1.0f, 0.0f, 0.3f);
699  }
700 
701  // draw delta freespace cells
702  if (m_freeSize != 0) {
703  if (m_colorMode != CM_PRINTOUT) glColor4f(0.5f, 1.0f, 0.1f, 0.3f);
705  }
706  }
707 
709  if (m_selectionSize != 0) {
710  glColor4f(1.0, 0.0, 0.0, 0.5);
712  }
713  }
714 
715  void OcTreeDrawer::drawCubes(GLfloat** cubeArray, unsigned int cubeArraySize,
716  GLfloat* cubeColorArray) const {
717  if (cubeArraySize == 0 || cubeArray == NULL){
718  std::cerr << "Warning: GLfloat array to draw cubes appears to be empty, nothing drawn.\n";
719  return;
720  }
721 
722  // save current color
723  GLfloat* curcol = new GLfloat[4];
724  glGetFloatv(GL_CURRENT_COLOR, curcol);
725 
726  // enable color pointer when heightColorMode is enabled:
727 
728  if ((m_colorMode == CM_COLOR_HEIGHT || m_colorMode == CM_GRAY_HEIGHT) && (cubeColorArray != NULL)){
729  glEnableClientState(GL_COLOR_ARRAY);
730  glColorPointer(4, GL_FLOAT, 0, cubeColorArray);
731  }
732 
733  // top surfaces:
734  glNormal3f(0.0f, 1.0f, 0.0f);
735  glVertexPointer(3, GL_FLOAT, 0, cubeArray[0]);
736  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
737  // bottom surfaces:
738  glNormal3f(0.0f, -1.0f, 0.0f);
739  glVertexPointer(3, GL_FLOAT, 0, cubeArray[1]);
740  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
741  // right surfaces:
742  glNormal3f(1.0f, 0.0f, 0.0f);
743  glVertexPointer(3, GL_FLOAT, 0, cubeArray[2]);
744  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
745  // left surfaces:
746  glNormal3f(-1.0f, 0.0f, 0.0f);
747  glVertexPointer(3, GL_FLOAT, 0, cubeArray[3]);
748  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
749  // back surfaces:
750  glNormal3f(0.0f, 0.0f, -1.0f);
751  glVertexPointer(3, GL_FLOAT, 0, cubeArray[4]);
752  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
753  // front surfaces:
754  glNormal3f(0.0f, 0.0f, 1.0f);
755  glVertexPointer(3, GL_FLOAT, 0, cubeArray[5]);
756  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
757 
759  && (cubeColorArray != NULL)){
760  glDisableClientState(GL_COLOR_ARRAY);
761  }
762 
763  // draw bounding linies of cubes in printout:
764  if (m_colorMode == CM_PRINTOUT){
765  glDisable(GL_LIGHTING);
766  glHint (GL_LINE_SMOOTH_HINT, GL_NICEST);
767  glEnable (GL_LINE_SMOOTH);
768  glPolygonMode (GL_FRONT_AND_BACK, GL_LINE); // Draw Polygons only as Wireframes
769  glLineWidth(2.0f);
770  glColor3f(0.0f, 0.0f, 0.0f);
771  glCullFace(GL_FRONT_AND_BACK); // Don't draw any Polygons faces
772  //glDepthFunc (GL_LEQUAL);
773 
774  // top meshes:
775  glNormal3f(0.0f, 1.0f, 0.0f);
776  glVertexPointer(3, GL_FLOAT, 0, cubeArray[0]);
777  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
778  // bottom meshes:
779  glNormal3f(0.0f, -1.0f, 0.0f);
780  glVertexPointer(3, GL_FLOAT, 0, cubeArray[1]);
781  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
782  // right meshes:
783  glNormal3f(1.0f, 0.0f, 0.0f);
784  glVertexPointer(3, GL_FLOAT, 0, cubeArray[2]);
785  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
786  // left meshes:
787  glNormal3f(-1.0f, 0.0f, 0.0f);
788  glVertexPointer(3, GL_FLOAT, 0, cubeArray[3]);
789  glDrawArrays(GL_QUADS, 0, cubeArraySize / 3);
790 
791  // restore defaults:
792  glCullFace(GL_BACK);
793  //glDepthFunc(GL_LESS);
794  glDisable(GL_LINE_SMOOTH);
795  glPolygonMode(GL_FRONT_AND_BACK, GL_FILL);
796  glEnable(GL_LIGHTING);
797  }
798  // reset color
799  glColor4fv(curcol);
800  delete[] curcol;
801  }
802 
804  if (!m_octree_grid_vis_initialized) return;
805  if (octree_grid_vertex_size == 0) return;
806 
807  glDisable(GL_LIGHTING);
808  glEnable(GL_LINE_SMOOTH);
809 
810  glLineWidth(1.);
811  glVertexPointer(3, GL_FLOAT, 0, octree_grid_vertex_array);
812  glColor3f(0.0, 0.0, 0.0);
813  glDrawArrays(GL_LINES, 0, octree_grid_vertex_size / 3);
814 
815  glDisable(GL_LINE_SMOOTH);
816  glEnable(GL_LIGHTING);
817  }
818 
819  void OcTreeDrawer::enableOcTree(bool enabled) {
820  m_drawOcTreeGrid = enabled;
823  }
824  }
825 
826 
828  origin = t;
829  std::cout << "OcTreeDrawer: setting new global origin: " << t << std::endl;
830 
831  octomap::pose6d relative_transform = origin * initial_origin.inv();
832 
833  std::cout << "origin : " << origin << std::endl;
834  std::cout << "inv init orig : " << initial_origin.inv() << std::endl;
835  std::cout << "relative trans: " << relative_transform << std::endl;
836  }
837 
838  void OcTreeDrawer::drawAxes() const {
839 
840  octomap::pose6d relative_transform = origin * initial_origin.inv();
841 
842  glPushMatrix();
843 
844  float length = 0.15f;
845 
846  GLboolean lighting, colorMaterial;
847  glGetBooleanv(GL_LIGHTING, &lighting);
848  glGetBooleanv(GL_COLOR_MATERIAL, &colorMaterial);
849 
850  glDisable(GL_COLOR_MATERIAL);
851 
852  double angle= 2 * acos(initial_origin.rot().u());
853  double scale = sqrt (initial_origin.rot().x()*initial_origin.rot().x()
855  + initial_origin.rot().z()*initial_origin.rot().z());
856  double ax= initial_origin.rot().x() / scale;
857  double ay= initial_origin.rot().y() / scale;
858  double az= initial_origin.rot().z() / scale;
859 
860  if (angle > 0) glRotatef(OTD_RAD2DEG*angle, ax, ay, az);
861 
862  float color[4];
863  color[0] = 0.7f; color[1] = 0.7f; color[2] = 1.0f; color[3] = 1.0f;
864  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color);
865  QGLViewer::drawArrow(length, 0.01*length);
866 
867  color[0] = 1.0f; color[1] = 0.7f; color[2] = 0.7f; color[3] = 1.0f;
868  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color);
869  glPushMatrix();
870  glRotatef(90.0, 0.0, 1.0, 0.0);
871  QGLViewer::drawArrow(length, 0.01*length);
872  glPopMatrix();
873 
874  color[0] = 0.7f; color[1] = 1.0f; color[2] = 0.7f; color[3] = 1.0f;
875  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE, color);
876  glPushMatrix();
877  glRotatef(-90.0, 1.0, 0.0, 0.0);
878  QGLViewer::drawArrow(length, 0.01*length);
879  glPopMatrix();
880 
881  glTranslatef(relative_transform.trans().x(), relative_transform.trans().y(), relative_transform.trans().z());
882 
883  if (colorMaterial)
884  glEnable(GL_COLOR_MATERIAL);
885  if (!lighting)
886  glDisable(GL_LIGHTING);
887 
888  glPopMatrix();
889  }
890 
891 } // namespace
892 
893 
void setOcTree(const AbstractOcTree &octree)
sets a new OcTree that should be drawn by this drawer
Definition: OcTreeDrawer.h:43
static void drawArrow(float length=1.0f, float radius=-1.0f, int nbSubdivisions=12)
Definition: qglviewer.cpp:3419
unsigned int setCubeColorHeightmap(const octomap::OcTreeVolume &v, const unsigned int &current_array_idx, GLfloat **glColorArray)
unsigned int octree_grid_vertex_size
Definition: OcTreeDrawer.h:139
void clearCubes(GLfloat ***glArray, unsigned int &glArraySize, GLfloat **glColorArray=NULL)
clear OpenGL visualization
GLfloat ** m_occupiedArray
Definition: OcTreeDrawer.h:125
GLfloat * octree_grid_vertex_array
OpenGL representation of Octree (grid structure)
Definition: OcTreeDrawer.h:138
void clearOcTreeSelection()
clear the visualization of the OcTree selection
ColorMode m_colorMode
Definition: SceneObject.h:88
std::pair< point3d, double > OcTreeVolume
octomap::pose6d initial_origin
Definition: OcTreeDrawer.h:154
GLfloat * m_occupiedColorArray
Definition: OcTreeDrawer.h:134
void enableOcTree(bool enabled=true)
Pose6D inv() const
void initCubeTemplate(const octomath::Pose6D &origin, std::vector< octomath::Vector3 > &cube_template)
setup cube template
Vector3 rotate(const Vector3 &v) const
bool isNodeAtThreshold(const OcTreeNode *occupancyNode) const
void setOcTreeSelection(const std::list< octomap::OcTreeVolume > &selectedPoints)
sets a new selection of the current OcTree to be drawn
virtual void getMetricMin(double &x, double &y, double &z)
void generateCubes(const std::list< octomap::OcTreeVolume > &voxels, GLfloat ***glArray, unsigned int &glArraySize, octomath::Pose6D &origin, GLfloat **glColorArray=NULL)
GLfloat ** m_freeThresArray
Definition: OcTreeDrawer.h:123
void drawFreeVoxels() const
void drawAxes() const
void drawOctreeGrid() const
GLfloat ** m_occupiedThresArray
OpenGL representation of Octree cells (cubes)
Definition: OcTreeDrawer.h:121
unsigned int m_selectionSize
Definition: OcTreeDrawer.h:130
Vector3 & trans()
void heightMapGray(double h, GLfloat *glArrayPos) const
Definition: SceneObject.cpp:92
void drawOccupiedVoxels() const
unsigned int generateCube(const octomap::OcTreeVolume &v, const std::vector< octomath::Vector3 > &cube_template, const unsigned int &current_array_idx, GLfloat ***glArray)
add one cube to arrays
tree_iterator begin_tree(unsigned char maxDepth=0) const
virtual void getMetricMax(double &x, double &y, double &z)
void drawSelection() const
void initGLArrays(const unsigned int &num_cubes, unsigned int &glArraySize, GLfloat ***glArray, GLfloat **glColorArray)
setup OpenGL arrays
void heightMapColor(double h, GLfloat *glArrayPos) const
Definition: SceneObject.cpp:38
std::list< octomap::OcTreeVolume > m_grid_voxels
Definition: OcTreeDrawer.h:141
void drawCubes(GLfloat **cubeArray, unsigned int cubeArraySize, GLfloat *cubeColorArray=NULL) const
unsigned int m_occupiedThresSize
Definition: OcTreeDrawer.h:122
void setAlphaOccupied(double alpha)
sets alpha level for occupied cells
octomap::pose6d origin
Definition: OcTreeDrawer.h:153
Quaternion & rot()
octomath::Pose6D pose6d
unsigned int m_occupiedSize
Definition: OcTreeDrawer.h:126
unsigned int setCubeColorRGBA(const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a, const unsigned int &current_array_idx, GLfloat **glColorArray)
GLfloat ** m_selectionArray
Definition: OcTreeDrawer.h:129
unsigned int m_freeSize
Definition: OcTreeDrawer.h:128
GLfloat * m_occupiedThresColorArray
Color array for occupied cells (height)
Definition: OcTreeDrawer.h:133
void setOrigin(octomap::pose6d t)
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
unsigned int m_freeThresSize
Definition: OcTreeDrawer.h:124
#define OTD_RAD2DEG


octovis
Author(s): Kai M. Wurm , Armin Hornung
autogenerated on Mon Jun 10 2019 14:00:25