25 #ifndef OCTREEDRAWER_H_ 26 #define OCTREEDRAWER_H_ 82 void drawCubes(GLfloat** cubeArray,
unsigned int cubeArraySize,
83 GLfloat* cubeColorArray = NULL)
const;
90 void generateCubes(
const std::list<octomap::OcTreeVolume>& voxels,
91 GLfloat*** glArray,
unsigned int& glArraySize,
93 GLfloat** glColorArray = NULL);
96 void clearCubes(GLfloat*** glArray,
unsigned int& glArraySize,
97 GLfloat** glColorArray = NULL);
99 void initGLArrays(
const unsigned int& num_cubes,
unsigned int& glArraySize,
100 GLfloat*** glArray, GLfloat** glColorArray);
103 std::vector<octomath::Vector3>& cube_template);
106 const std::vector<octomath::Vector3>& cube_template,
107 const unsigned int& current_array_idx,
110 const unsigned int& current_array_idx,
111 GLfloat** glColorArray);
112 unsigned int setCubeColorRGBA(
const unsigned char& r,
const unsigned char& g,
113 const unsigned char& b,
const unsigned char& a,
114 const unsigned int& current_array_idx,
115 GLfloat** glColorArray);
bool m_alternativeDrawing
void setOcTree(const AbstractOcTree &octree)
sets a new OcTree that should be drawn by this drawer
void enableOcTreeCells(bool enabled=true)
unsigned int setCubeColorHeightmap(const octomap::OcTreeVolume &v, const unsigned int ¤t_array_idx, GLfloat **glColorArray)
unsigned int octree_grid_vertex_size
void enableAxes(bool enabled=true)
void drawFreeVoxels() const
void clearCubes(GLfloat ***glArray, unsigned int &glArraySize, GLfloat **glColorArray=NULL)
clear OpenGL visualization
GLfloat ** m_occupiedArray
GLfloat * octree_grid_vertex_array
OpenGL representation of Octree (grid structure)
void clearOcTreeSelection()
clear the visualization of the OcTree selection
void drawOccupiedVoxels() const
void clearOcTreeStructure()
std::pair< point3d, double > OcTreeVolume
octomap::pose6d initial_origin
GLfloat * m_occupiedColorArray
void enableOcTree(bool enabled=true)
void initCubeTemplate(const octomath::Pose6D &origin, std::vector< octomath::Vector3 > &cube_template)
setup cube template
void drawSelection() const
unsigned int m_max_tree_depth
void setOcTreeSelection(const std::list< octomap::OcTreeVolume > &selectedPoints)
sets a new selection of the current OcTree to be drawn
void drawOctreeGrid() const
void generateCubes(const std::list< octomap::OcTreeVolume > &voxels, GLfloat ***glArray, unsigned int &glArraySize, octomath::Pose6D &origin, GLfloat **glColorArray=NULL)
GLfloat ** m_freeThresArray
void setAlternativeDrawing(bool flag)
bool m_octree_grid_vis_initialized
GLfloat ** m_occupiedThresArray
OpenGL representation of Octree cells (cubes)
unsigned int m_selectionSize
void enableFreespace(bool enabled=true)
unsigned int generateCube(const octomap::OcTreeVolume &v, const std::vector< octomath::Vector3 > &cube_template, const unsigned int ¤t_array_idx, GLfloat ***glArray)
add one cube to arrays
void initGLArrays(const unsigned int &num_cubes, unsigned int &glArraySize, GLfloat ***glArray, GLfloat **glColorArray)
setup OpenGL arrays
std::list< octomap::OcTreeVolume > m_grid_voxels
unsigned int m_occupiedThresSize
void setAlphaOccupied(double alpha)
sets alpha level for occupied cells
void setMax_tree_depth(unsigned int max_tree_depth)
unsigned int m_occupiedSize
unsigned int setCubeColorRGBA(const unsigned char &r, const unsigned char &g, const unsigned char &b, const unsigned char &a, const unsigned int ¤t_array_idx, GLfloat **glColorArray)
GLfloat ** m_selectionArray
GLfloat * m_occupiedThresColorArray
Color array for occupied cells (height)
void setOrigin(octomap::pose6d t)
void drawCubes(GLfloat **cubeArray, unsigned int cubeArraySize, GLfloat *cubeColorArray=NULL) const
unsigned int m_freeThresSize
void enableSelection(bool enabled=true)