ColorOcTreeDrawer.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 
26 
27 namespace octomap {
28 
30  : OcTreeDrawer() {
31  }
32 
34  }
35 
37  const octomap::pose6d& origin_,
38  int map_id_) {
39 
40  const ColorOcTree& tree = ((const ColorOcTree&) tree_pnt);
41 
42  this->map_id = map_id_;
43 
44  // save origin used during cube generation
45  this->initial_origin = octomap::pose6d(octomap::point3d(0,0,0), origin_.rot());
46  // origin is in global coords
47  this->origin = origin_;
48 
49  // maximum size to prevent crashes on large maps: (should be checked in a better way than a constant)
50  bool showAll = (tree.size() < 5 * 1e6);
51  bool uses_origin = ( (origin_.rot().x() != 0.) && (origin_.rot().y() != 0.)
52  && (origin_.rot().z() != 0.) && (origin_.rot().u() != 1.) );
53 
54  // walk the tree one to find the number of nodes in each category
55  // (this is used to set up the OpenGL arrays)
56  // TODO: this step may be left out, if we maintained the GLArrays in std::vectors instead...
57  unsigned int cnt_occupied(0), cnt_occupied_thres(0), cnt_free(0), cnt_free_thres(0);
58  for(ColorOcTree::tree_iterator it = tree.begin_tree(this->m_max_tree_depth),
59  end=tree.end_tree(); it!= end; ++it) {
60  if (it.isLeaf()) {
61  if (tree.isNodeOccupied(*it)){ // occupied voxels
62  if (tree.isNodeAtThreshold(*it)) ++cnt_occupied_thres;
63  else ++cnt_occupied;
64  }
65  else if (showAll) { // freespace voxels
66  if (tree.isNodeAtThreshold(*it)) ++cnt_free_thres;
67  else ++cnt_free;
68  }
69  }
70  }
71  // setup GL arrays for cube quads and cube colors
74  initGLArrays(cnt_free , m_freeSize , &m_freeArray, NULL);
75  initGLArrays(cnt_free_thres , m_freeThresSize , &m_freeThresArray, NULL);
76 
77  std::vector<octomath::Vector3> cube_template;
78  initCubeTemplate(origin, cube_template);
79 
80  unsigned int idx_occupied(0), idx_occupied_thres(0), idx_free(0), idx_free_thres(0);
81  unsigned int color_idx_occupied(0), color_idx_occupied_thres(0);
82 
83  m_grid_voxels.clear();
84  OcTreeVolume voxel; // current voxel, possibly transformed
85  for(ColorOcTree::tree_iterator it = tree.begin_tree(this->m_max_tree_depth),
86  end=tree.end_tree(); it!= end; ++it) {
87 
88  if (it.isLeaf()) { // voxels for leaf nodes
89  if (uses_origin)
90  voxel = OcTreeVolume(origin.rot().rotate(it.getCoordinate()), it.getSize());
91  else
92  voxel = OcTreeVolume(it.getCoordinate(), it.getSize());
93 
94  if (tree.isNodeOccupied(*it)){ // occupied voxels
95  if (tree.isNodeAtThreshold(*it)) {
96  idx_occupied_thres = generateCube(voxel, cube_template, idx_occupied_thres, &m_occupiedThresArray);
97  color_idx_occupied_thres = setCubeColorRGBA(it->getColor().r, it->getColor().g, it->getColor().b,
98  (unsigned char) (it->getOccupancy() * 255.),
99  color_idx_occupied_thres, &m_occupiedThresColorArray);
100  }
101  else {
102  idx_occupied = generateCube(voxel, cube_template, idx_occupied, &m_occupiedArray);
103  color_idx_occupied = setCubeColorRGBA(it->getColor().r, it->getColor().g, it->getColor().b,
104  (unsigned char)(it->getOccupancy() * 255.),
105  color_idx_occupied, &m_occupiedColorArray);
106  }
107  }
108  else if (showAll) { // freespace voxels
109  if (tree.isNodeAtThreshold(*it)) {
110  idx_free_thres = generateCube(voxel, cube_template, idx_free_thres, &m_freeThresArray);
111  }
112  else {
113  idx_free = generateCube(voxel, cube_template, idx_free, &m_freeArray);
114  }
115  }
116 
117  // grid structure voxel
118  if (showAll) m_grid_voxels.push_back(voxel);
119  }
120 
121  else { // inner node voxels (for grid structure only)
122  if (showAll) {
123  if (uses_origin)
124  voxel = OcTreeVolume(origin.rot().rotate(it.getCoordinate()), it.getSize());
125  else
126  voxel = OcTreeVolume(it.getCoordinate(), it.getSize());
127  m_grid_voxels.push_back(voxel);
128  }
129  }
130  } // end for all voxels
131 
133 
134  if(m_drawOcTreeGrid)
136  }
137 
138 } // end namespace
GLfloat ** m_occupiedArray
Definition: OcTreeDrawer.h:125
std::pair< point3d, double > OcTreeVolume
octomap::pose6d initial_origin
Definition: OcTreeDrawer.h:154
GLfloat * m_occupiedColorArray
Definition: OcTreeDrawer.h:134
void initCubeTemplate(const octomath::Pose6D &origin, std::vector< octomath::Vector3 > &cube_template)
setup cube template
Vector3 rotate(const Vector3 &v) const
virtual void setOcTree(const AbstractOcTree &tree_pnt, const pose6d &origin, int map_id_)
bool isNodeAtThreshold(const OcTreeNode *occupancyNode) const
GLfloat ** m_freeThresArray
Definition: OcTreeDrawer.h:123
GLfloat ** m_occupiedThresArray
OpenGL representation of Octree cells (cubes)
Definition: OcTreeDrawer.h:121
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
void initGLArrays(const unsigned int &num_cubes, unsigned int &glArraySize, GLfloat ***glArray, GLfloat **glColorArray)
setup OpenGL arrays
std::list< octomap::OcTreeVolume > m_grid_voxels
Definition: OcTreeDrawer.h:141
unsigned int m_occupiedThresSize
Definition: OcTreeDrawer.h:122
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)
unsigned int m_freeSize
Definition: OcTreeDrawer.h:128
GLfloat * m_occupiedThresColorArray
Color array for occupied cells (height)
Definition: OcTreeDrawer.h:133
bool isNodeOccupied(const OcTreeNode *occupancyNode) const
unsigned int m_freeThresSize
Definition: OcTreeDrawer.h:124


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