point_cloud_drawable.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #include <sstream>
00029 
00030 #include "point_cloud_drawable.h"
00031 #include "rtabmap/utilite/ULogger.h"
00032 #include "rtabmap/utilite/UConversion.h"
00033 #include <opencv2/imgproc/imgproc.hpp>
00034 #include "util.h"
00035 
00036 #include <GLES2/gl2.h>
00037 
00038 PointCloudDrawable::PointCloudDrawable(
00039                 GLuint cloudShaderProgram,
00040                 GLuint textureShaderProgram,
00041                 const pcl::PointCloud<pcl::PointXYZRGB>::Ptr & cloud,
00042                 const std::vector<pcl::Vertices> & polygons,
00043                 const cv::Mat & image) :
00044                 vertex_buffers_(0),
00045                 textures_(0),
00046                 nPoints_(0),
00047                 pose_(1.0f),
00048                 visible_(true),
00049                 cloud_shader_program_(cloudShaderProgram),
00050                 texture_shader_program_(textureShaderProgram)
00051 {
00052         UASSERT(!cloud->empty());
00053 
00054         glGenBuffers(1, &vertex_buffers_);
00055         if(!vertex_buffers_)
00056         {
00057                 LOGE("OpenGL: could not generate vertex buffers\n");
00058                 return;
00059         }
00060 
00061         if(!cloud->is_dense && !image.empty())
00062         {
00063                 LOGI("cloud=%dx%d image=%dx%d\n", (int)cloud->width, (int)cloud->height, image.cols, image.rows);
00064                 UASSERT(polygons.size() && !cloud->is_dense && !image.empty() && image.type() == CV_8UC3);
00065                 glGenTextures(1, &textures_);
00066                 if(!textures_)
00067                 {
00068                         vertex_buffers_ = 0;
00069                         LOGE("OpenGL: could not generate vertex buffers\n");
00070                         return;
00071                 }
00072         }
00073 
00074         LOGI("Creating cloud buffer %d", vertex_buffers_);
00075         std::vector<float> vertices;
00076         if(textures_)
00077         {
00078                 vertices = std::vector<float>(cloud->size()*6);
00079                 for(unsigned int i=0; i<cloud->size(); ++i)
00080                 {
00081                         vertices[i*6] = cloud->at(i).x;
00082                         vertices[i*6+1] = cloud->at(i).y;
00083                         vertices[i*6+2] = cloud->at(i).z;
00084 
00085                         // rgb
00086                         vertices[i*6+3] = cloud->at(i).rgb;
00087 
00088                         // texture uv
00089                         vertices[i*6+4] = float(i % cloud->width)/float(cloud->width); //u
00090                         vertices[i*6+5] = float(i/cloud->width)/float(cloud->height);  //v
00091                 }
00092         }
00093         else
00094         {
00095                 vertices = std::vector<float>(cloud->size()*4);
00096                 for(unsigned int i=0; i<cloud->size(); ++i)
00097                 {
00098                         vertices[i*4] = cloud->at(i).x;
00099                         vertices[i*4+1] = cloud->at(i).y;
00100                         vertices[i*4+2] = cloud->at(i).z;
00101                         vertices[i*4+3] = cloud->at(i).rgb;
00102                 }
00103         }
00104 
00105         glBindBuffer(GL_ARRAY_BUFFER, vertex_buffers_);
00106         glBufferData(GL_ARRAY_BUFFER, sizeof(GLfloat) * (int)vertices.size(), (const void *)vertices.data(), GL_STATIC_DRAW);
00107         glBindBuffer(GL_ARRAY_BUFFER, 0);
00108 
00109         GLint error = glGetError();
00110         if(error != GL_NO_ERROR)
00111         {
00112                 LOGE("OpenGL: Could not allocate point cloud (0x%x)\n", error);
00113                 vertex_buffers_ = 0;
00114                 return;
00115         }
00116 
00117         if(textures_)
00118         {
00119                 // gen texture from image
00120                 glBindTexture(GL_TEXTURE_2D, textures_);
00121                 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
00122                 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
00123                 cv::Mat rgbImage;
00124                 cv::cvtColor(image, rgbImage, CV_BGR2RGB);
00125                 glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, rgbImage.cols, rgbImage.rows, 0, GL_RGB, GL_UNSIGNED_BYTE, rgbImage.data);
00126 
00127                 GLint error = glGetError();
00128                 if(error != GL_NO_ERROR)
00129                 {
00130                         LOGE("OpenGL: Could not allocate texture (0x%x)\n", error);
00131                         textures_ = 0;
00132 
00133                         glDeleteBuffers(1, &vertex_buffers_);
00134                         vertex_buffers_ = 0;
00135                         return;
00136                 }
00137         }
00138 
00139         nPoints_ = cloud->size();
00140 
00141         if(polygons.size())
00142         {
00143                 int polygonSize = polygons[0].vertices.size();
00144                 UASSERT(polygonSize == 3);
00145                 polygons_.resize(polygons.size() * polygonSize);
00146                 int oi = 0;
00147                 for(unsigned int i=0; i<polygons.size(); ++i)
00148                 {
00149                         UASSERT((int)polygons[i].vertices.size() == polygonSize);
00150                         for(int j=0; j<polygonSize; ++j)
00151                         {
00152                                 polygons_[oi++] = (unsigned short)polygons[i].vertices[j];
00153                         }
00154                 }
00155         }
00156 }
00157 
00158 PointCloudDrawable::~PointCloudDrawable()
00159 {
00160         LOGI("Freeing cloud buffer %d", vertex_buffers_);
00161         if (vertex_buffers_)
00162         {
00163                 glDeleteBuffers(1, &vertex_buffers_);
00164                 tango_gl::util::CheckGlError("PointCloudDrawable::~PointCloudDrawable()");
00165                 vertex_buffers_ = 0;
00166         }
00167 
00168         if (textures_)
00169         {
00170                 glDeleteTextures(1, &textures_);
00171                 tango_gl::util::CheckGlError("PointCloudDrawable::~PointCloudDrawable()");
00172                 textures_ = 0;
00173         }
00174 }
00175 
00176 void PointCloudDrawable::setPose(const rtabmap::Transform & pose)
00177 {
00178         UASSERT(!pose.isNull());
00179 
00180         pose_ = glmFromTransform(pose);
00181 }
00182 
00183 void PointCloudDrawable::Render(const glm::mat4 & projectionMatrix, const glm::mat4 & viewMatrix, bool meshRendering, float pointSize) {
00184 
00185         if(vertex_buffers_ && nPoints_ && visible_)
00186         {
00187                 if(meshRendering && textures_)
00188                 {
00189                         glUseProgram(texture_shader_program_);
00190 
00191                         GLuint mvp_handle_ = glGetUniformLocation(texture_shader_program_, "mvp");
00192                         glm::mat4 mvp_mat = projectionMatrix * viewMatrix * pose_;
00193                         glUniformMatrix4fv(mvp_handle_, 1, GL_FALSE, glm::value_ptr(mvp_mat));
00194 
00195                         // Texture activate unit 0
00196                         glActiveTexture(GL_TEXTURE0);
00197                         // Bind the texture to this unit.
00198                         glBindTexture(GL_TEXTURE_2D, textures_);
00199                         // Tell the texture uniform sampler to use this texture in the shader by binding to texture unit 0.
00200                         GLuint texture_handle = glGetUniformLocation(texture_shader_program_, "u_Texture");
00201                         glUniform1i(texture_handle, 0);
00202 
00203                         GLint attribute_vertex = glGetAttribLocation(texture_shader_program_, "vertex");
00204                         GLint attribute_texture = glGetAttribLocation(texture_shader_program_, "a_TexCoordinate");
00205 
00206                         glEnableVertexAttribArray(attribute_vertex);
00207                         glEnableVertexAttribArray(attribute_texture);
00208                         glBindBuffer(GL_ARRAY_BUFFER, vertex_buffers_);
00209                         glVertexAttribPointer(attribute_vertex, 3, GL_FLOAT, GL_FALSE, 6*sizeof(GLfloat), 0);
00210                         glVertexAttribPointer(attribute_texture, 2, GL_FLOAT, GL_FALSE, 6*sizeof(GLfloat), (GLvoid*) (4 * sizeof(GLfloat)));
00211 
00212                         glDrawElements(GL_TRIANGLES, polygons_.size(), GL_UNSIGNED_SHORT, polygons_.data());
00213                 }
00214                 else // point cloud or colored mesh
00215                 {
00216                         glUseProgram(cloud_shader_program_);
00217 
00218                         GLuint mvp_handle_ = glGetUniformLocation(cloud_shader_program_, "mvp");
00219                         glm::mat4 mvp_mat = projectionMatrix * viewMatrix * pose_;
00220                         glUniformMatrix4fv(mvp_handle_, 1, GL_FALSE, glm::value_ptr(mvp_mat));
00221 
00222                         GLuint point_size_handle_ = glGetUniformLocation(cloud_shader_program_, "point_size");
00223                         glUniform1f(point_size_handle_, pointSize);
00224 
00225                         GLint attribute_vertex = glGetAttribLocation(cloud_shader_program_, "vertex");
00226                         GLint attribute_color = glGetAttribLocation(cloud_shader_program_, "color");
00227 
00228                         glEnableVertexAttribArray(attribute_vertex);
00229                         glEnableVertexAttribArray(attribute_color);
00230                         glBindBuffer(GL_ARRAY_BUFFER, vertex_buffers_);
00231                         if(textures_)
00232                         {
00233                                 glVertexAttribPointer(attribute_vertex, 3, GL_FLOAT, GL_FALSE, 6*sizeof(GLfloat), 0);
00234                                 glVertexAttribPointer(attribute_color, 3, GL_UNSIGNED_BYTE, GL_TRUE, 6*sizeof(GLfloat), (GLvoid*) (3 * sizeof(GLfloat)));
00235                         }
00236                         else
00237                         {
00238                                 glVertexAttribPointer(attribute_vertex, 3, GL_FLOAT, GL_FALSE, 4*sizeof(GLfloat), 0);
00239                                 glVertexAttribPointer(attribute_color, 3, GL_UNSIGNED_BYTE, GL_TRUE, 4*sizeof(GLfloat), (GLvoid*) (3 * sizeof(GLfloat)));
00240                         }
00241                         if(meshRendering && polygons_.size())
00242                         {
00243                                 glDrawElements(GL_TRIANGLES, polygons_.size(), GL_UNSIGNED_SHORT, polygons_.data());
00244                         }
00245                         else
00246                         {
00247                                 glDrawArrays(GL_POINTS, 0, nPoints_);
00248                         }
00249                 }
00250                 glDisableVertexAttribArray(0);
00251                 glBindBuffer(GL_ARRAY_BUFFER, 0);
00252 
00253                 glUseProgram(0);
00254                 tango_gl::util::CheckGlError("Pointcloud::Render()");
00255         }
00256 }
00257 


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17