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 
00026 #include <octovis/PointcloudDrawer.h>
00027 
00028 namespace octomap {
00029 
00030   PointcloudDrawer::PointcloudDrawer()
00031     : ScanGraphDrawer(), m_pointsArray(NULL), m_numberPoints(0)
00032   {
00033   }
00034 
00035   PointcloudDrawer::PointcloudDrawer(const ScanGraph& graph)
00036     : ScanGraphDrawer(), m_pointsArray(NULL), m_numberPoints(0)
00037   {
00038     this->setScanGraph(graph);
00039 
00040   }
00041 
00042   PointcloudDrawer::~PointcloudDrawer() {
00043     clear();
00044 
00045   }
00046 
00047   void PointcloudDrawer::setScanGraph(const ScanGraph& graph){
00048     clear();
00049 
00050     
00051     for (octomap::ScanGraph::const_iterator it = graph.begin(); it != graph.end(); it++) {
00052       m_numberPoints += (*it)->scan->size();
00053     }
00054 
00055     m_pointsArray = new GLfloat[3*m_numberPoints];
00056 
00057     unsigned i = 0;
00058     for (octomap::ScanGraph::const_iterator graph_it = graph.begin(); graph_it != graph.end(); graph_it++) {
00059       octomap::Pointcloud* scan = new Pointcloud((*graph_it)->scan);
00060       scan->transformAbsolute((*graph_it)->pose);
00061 
00062       for (Pointcloud::iterator pc_it = scan->begin(); pc_it != scan->end(); ++pc_it){
00063         m_pointsArray[3*i] = pc_it->x();
00064         m_pointsArray[3*i +1] = pc_it->y();
00065         m_pointsArray[3*i +2] = pc_it->z();
00066 
00067         i++;
00068       }
00069       delete scan;
00070     }
00071   }
00072 
00073   void PointcloudDrawer::clear(){
00074 
00075     if (m_numberPoints != 0) {
00076       delete[] m_pointsArray;
00077       m_numberPoints = 0;
00078     }
00079   }
00080 
00081   void PointcloudDrawer::draw() const{
00082     if (m_numberPoints == 0)
00083       return;
00084 
00085     glEnable(GL_POINT_SMOOTH);
00086     glEnableClientState(GL_VERTEX_ARRAY);
00087 
00088    
00089 
00090 
00091 
00092 
00093 
00094 
00095 
00096 
00097 
00098     glPointSize(1.0);
00099     glColor4f(1.0, 0.0, 0.0, 1.);
00100 
00101     glVertexPointer(3, GL_FLOAT, 0, m_pointsArray);
00102     glDrawArrays(GL_POINTS, 0, m_numberPoints);
00103     glDisableClientState(GL_VERTEX_ARRAY);
00104   }
00105 
00106 }