gl_renderer.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Suat Gedikli */
00036 
00037 #include <GL/glew.h>
00038 #ifdef __APPLE__
00039 #include <OpenGL/glu.h>
00040 #else
00041 #include <GL/glu.h>
00042 #endif
00043 #include <GL/glut.h>
00044 #include <GL/freeglut.h>
00045 #include <moveit/mesh_filter/gl_renderer.h>
00046 #include <sstream>
00047 #include <fstream>
00048 #include <stdexcept>
00049 #include <vector>
00050 #include <iostream>
00051 #include <boost/thread.hpp>
00052 #include <ros/console.h>
00053 
00054 using namespace std;
00055 
00056 mesh_filter::GLRenderer::GLRenderer(unsigned width, unsigned height, float near, float far)
00057   : width_(width)
00058   , height_(height)
00059   , fbo_id_(0)
00060   , rbo_id_(0)
00061   , rgb_id_(0)
00062   , depth_id_(0)
00063   , program_(0)
00064   , near_(near)
00065   , far_(far)
00066   , fx_(width >> 1)  // 90 degree wide angle
00067   , fy_(fx_)
00068   , cx_(width >> 1)
00069   , cy_(height >> 1)
00070 {
00071   createGLContext();
00072   initFrameBuffers();
00073 }
00074 
00075 mesh_filter::GLRenderer::~GLRenderer()
00076 {
00077   if (program_)
00078     glDeleteProgram(program_);
00079 
00080   deleteFrameBuffers();
00081   deleteGLContext();
00082 }
00083 
00084 void mesh_filter::GLRenderer::setBufferSize(unsigned width, unsigned height)
00085 {
00086   if (width_ != width || height_ != height)
00087   {
00088     width_ = width;
00089     height_ = height;
00090     deleteFrameBuffers();
00091     initFrameBuffers();
00092   }
00093 }
00094 
00095 void mesh_filter::GLRenderer::setClippingRange(float near, float far)
00096 {
00097   if (near_ <= 0)
00098     throw runtime_error("near clipping plane distance needs to be larger than 0");
00099   if (far_ <= near_)
00100     throw runtime_error("far clipping plane needs to be larger than near clipping plane distance");
00101   near_ = near;
00102   far_ = far;
00103 }
00104 
00105 void mesh_filter::GLRenderer::setCameraParameters(float fx, float fy, float cx, float cy)
00106 {
00107   fx_ = fx;
00108   fy_ = fy;
00109   cx_ = cx;
00110   cy_ = cy;
00111 }
00112 
00113 void mesh_filter::GLRenderer::setCameraParameters() const
00114 {
00115   float left = near_ * -cx_ / fx_;
00116   float right = near_ * (width_ - cx_) / fx_;
00117   float top = near_ * cy_ / fy_;
00118   float bottom = near_ * (cy_ - height_) / fy_;
00119 
00120   glMatrixMode(GL_PROJECTION);
00121   glLoadIdentity();
00122   glFrustum(left, right, bottom, top, near_, far_);
00123 
00124   glMatrixMode(GL_MODELVIEW);
00125   glLoadIdentity();
00126   gluLookAt(0, 0, 0, 0, 0, 1, 0, -1, 0);
00127 }
00128 
00129 void mesh_filter::GLRenderer::initFrameBuffers()
00130 {
00131   glGenTextures(1, &rgb_id_);
00132   glBindTexture(GL_TEXTURE_2D, rgb_id_);
00133   glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA, width_, height_, 0, GL_RGBA, GL_UNSIGNED_BYTE, NULL);
00134   glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
00135   glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
00136   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
00137   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
00138   glBindTexture(GL_TEXTURE_2D, 0);
00139 
00140   glGenTextures(1, &depth_id_);
00141   glBindTexture(GL_TEXTURE_2D, depth_id_);
00142   glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT, width_, height_, 0, GL_DEPTH_COMPONENT, GL_FLOAT, 0);
00143   glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
00144   glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
00145   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
00146   glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR);
00147   glBindTexture(GL_TEXTURE_2D, 0);
00148 
00149   glGenFramebuffers(1, &fbo_id_);
00150   glBindFramebuffer(GL_FRAMEBUFFER, fbo_id_);
00151   glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, rgb_id_, 0);
00152 
00153   glGenRenderbuffers(1, &rbo_id_);
00154   glBindRenderbuffer(GL_RENDERBUFFER, rbo_id_);
00155   glRenderbufferStorage(GL_RENDERBUFFER, GL_DEPTH_COMPONENT, width_, height_);
00156   glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER, rbo_id_);
00157   glFramebufferTexture2D(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_TEXTURE_2D, depth_id_, 0);
00158   glBindRenderbuffer(GL_RENDERBUFFER, 0);
00159 
00160   GLenum DrawBuffers[2] = { GL_COLOR_ATTACHMENT0, GL_DEPTH_ATTACHMENT };
00161   glDrawBuffers(2, DrawBuffers);
00162 
00163   GLenum status = glCheckFramebufferStatus(GL_FRAMEBUFFER);
00164 
00165   if (status != GL_FRAMEBUFFER_COMPLETE)  // If the frame buffer does not report back as complete
00166     throw runtime_error("Couldn't create frame buffer");
00167 
00168   glBindFramebuffer(GL_FRAMEBUFFER, 0);  // Unbind our frame buffer
00169 }
00170 
00171 void mesh_filter::GLRenderer::deleteFrameBuffers()
00172 {
00173   if (rbo_id_)
00174     glDeleteRenderbuffers(1, &rbo_id_);
00175   if (fbo_id_)
00176     glDeleteFramebuffers(1, &fbo_id_);
00177   if (depth_id_)
00178     glDeleteTextures(1, &depth_id_);
00179   if (rgb_id_)
00180     glDeleteTextures(1, &rgb_id_);
00181 
00182   rbo_id_ = fbo_id_ = depth_id_ = rgb_id_ = 0;
00183 }
00184 
00185 void mesh_filter::GLRenderer::begin() const
00186 {
00187   glPushAttrib(GL_VIEWPORT_BIT | GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT | GL_POLYGON_BIT);
00188   glBindFramebuffer(GL_FRAMEBUFFER, fbo_id_);
00189   glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
00190   glViewport(0, 0, width_, height_);
00191   glUseProgram(program_);
00192   setCameraParameters();
00193 }
00194 
00195 void mesh_filter::GLRenderer::callList(GLuint list) const
00196 {
00197   begin();
00198   glCallList(list);
00199   end();
00200 }
00201 
00202 void mesh_filter::GLRenderer::end() const
00203 {
00204   glFlush();
00205   glPopAttrib();
00206   glBindFramebuffer(GL_FRAMEBUFFER, 0);
00207 }
00208 
00209 void mesh_filter::GLRenderer::getColorBuffer(unsigned char* buffer) const
00210 {
00211   glBindFramebuffer(GL_FRAMEBUFFER, fbo_id_);
00212   glBindTexture(GL_TEXTURE_2D, rgb_id_);
00213   glGetTexImage(GL_TEXTURE_2D, 0, GL_RGBA, GL_UNSIGNED_BYTE, buffer);
00214   glBindFramebuffer(GL_FRAMEBUFFER, 0);
00215 }
00216 
00217 void mesh_filter::GLRenderer::getDepthBuffer(float* buffer) const
00218 {
00219   glBindFramebuffer(GL_FRAMEBUFFER, fbo_id_);
00220   glBindTexture(GL_TEXTURE_2D, depth_id_);
00221   glGetTexImage(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT, GL_FLOAT, buffer);
00222   glBindFramebuffer(GL_FRAMEBUFFER, 0);
00223 }
00224 
00225 GLuint mesh_filter::GLRenderer::setShadersFromFile(const string& vertex_filename, const string& fragment_filename)
00226 {
00227   if (program_)
00228     glDeleteProgram(program_);
00229 
00230   string vertex_source, fragment_source;
00231   readShaderCodeFromFile(vertex_filename, vertex_source);
00232   readShaderCodeFromFile(fragment_filename, fragment_source);
00233 
00234   program_ = loadShaders(vertex_source, fragment_source);
00235   return program_;
00236 }
00237 
00238 GLuint mesh_filter::GLRenderer::setShadersFromString(const string& vertex_source, const string& fragment_source)
00239 {
00240   program_ = loadShaders(vertex_source, fragment_source);
00241   return program_;
00242 }
00243 
00244 const GLuint& mesh_filter::GLRenderer::getProgramID() const
00245 {
00246   return program_;
00247 }
00248 
00249 const float& mesh_filter::GLRenderer::getNearClippingDistance() const
00250 {
00251   return near_;
00252 }
00253 
00254 const float& mesh_filter::GLRenderer::getFarClippingDistance() const
00255 {
00256   return far_;
00257 }
00258 
00259 GLuint mesh_filter::GLRenderer::createShader(GLuint shaderType, const string& ShaderCode) const
00260 {
00261   GLuint ShaderID = glCreateShader(shaderType);
00262 
00263   // Compile Shader
00264   char const* SourcePointer = ShaderCode.c_str();
00265   glShaderSource(ShaderID, 1, &SourcePointer, NULL);
00266   glCompileShader(ShaderID);
00267 
00268   // Check Shader
00269   GLint Result = GL_FALSE;
00270   glGetShaderiv(ShaderID, GL_COMPILE_STATUS, &Result);
00271   if (Result != GL_TRUE)
00272   {
00273     int InfoLogLength;
00274     glGetShaderiv(ShaderID, GL_INFO_LOG_LENGTH, &InfoLogLength);
00275     if (InfoLogLength > 0)
00276     {
00277       vector<char> ShaderErrorMessage(InfoLogLength + 1);
00278       glGetShaderInfoLog(ShaderID, InfoLogLength, NULL, &ShaderErrorMessage[0]);
00279       stringstream errorStream;
00280       errorStream << "Could not compile shader: " << (const char*)&ShaderErrorMessage[0];
00281 
00282       glDeleteShader(ShaderID);
00283       throw runtime_error(errorStream.str());
00284     }
00285   }
00286   return ShaderID;
00287 }
00288 
00289 void mesh_filter::GLRenderer::readShaderCodeFromFile(const string& filename, string& shader) const
00290 {
00291   if (filename.empty())
00292     shader = "";
00293   else
00294   {
00295     string ShaderCode;
00296     fstream ShaderFile(filename.c_str(), ios::in);
00297     if (ShaderFile.is_open())
00298     {
00299       stringstream buffer;
00300       buffer << ShaderFile.rdbuf();
00301       shader = buffer.str();
00302     }
00303     else
00304     {
00305       stringstream errorStream;
00306       errorStream << "Could not open shader code in file \"" << filename << "\"";
00307       throw runtime_error(errorStream.str());
00308     }
00309   }
00310 }
00311 
00312 GLuint mesh_filter::GLRenderer::loadShaders(const string& vertex_source, const string& fragment_source) const
00313 {
00314   if (vertex_source.empty() && fragment_source.empty())
00315     return 0;
00316 
00317   GLuint ProgramID = glCreateProgram();
00318   GLuint VertexShaderID = 0;
00319   GLuint FragmentShaderID = 0;
00320 
00321   if (!vertex_source.empty())
00322   {
00323     GLuint VertexShaderID = createShader(GL_VERTEX_SHADER, vertex_source);
00324     glAttachShader(ProgramID, VertexShaderID);
00325   }
00326 
00327   if (!fragment_source.empty())
00328   {
00329     GLuint FragmentShaderID = createShader(GL_FRAGMENT_SHADER, fragment_source);
00330     glAttachShader(ProgramID, FragmentShaderID);
00331   }
00332 
00333   glLinkProgram(ProgramID);
00334 
00335   // Check the program
00336   GLint Result = GL_FALSE;
00337   GLint InfoLogLength;
00338   glGetProgramiv(ProgramID, GL_LINK_STATUS, &Result);
00339   glGetProgramiv(ProgramID, GL_INFO_LOG_LENGTH, &InfoLogLength);
00340   if (InfoLogLength > 0)
00341   {
00342     vector<char> ProgramErrorMessage(InfoLogLength + 1);
00343     glGetProgramInfoLog(ProgramID, InfoLogLength, NULL, &ProgramErrorMessage[0]);
00344     std::size_t l = strnlen(&ProgramErrorMessage[0], ProgramErrorMessage.size());
00345     if (l > 0)
00346       ROS_ERROR("%s\n", &ProgramErrorMessage[0]);
00347   }
00348 
00349   if (VertexShaderID)
00350     glDeleteShader(VertexShaderID);
00351 
00352   if (FragmentShaderID)
00353     glDeleteShader(FragmentShaderID);
00354 
00355   return ProgramID;
00356 }
00357 
00358 map<boost::thread::id, pair<unsigned, GLuint> > mesh_filter::GLRenderer::context_;
00359 boost::mutex mesh_filter::GLRenderer::context_lock_;
00360 bool mesh_filter::GLRenderer::glutInitialized_ = false;
00361 
00362 namespace
00363 {
00364 void nullDisplayFunction(){};
00365 }
00366 
00367 void mesh_filter::GLRenderer::createGLContext()
00368 {
00369   boost::mutex::scoped_lock _(context_lock_);
00370   if (!glutInitialized_)
00371   {
00372     char buffer[1];
00373     char* args = buffer;
00374     int n = 1;
00375 
00376     glutInit(&n, &args);
00377     glutInitDisplayMode(GLUT_SINGLE | GLUT_RGB | GLUT_DEPTH);
00378     glutInitialized_ = true;
00379   }
00380 
00381   // check if our thread is initialized
00382   boost::thread::id threadID = boost::this_thread::get_id();
00383   map<boost::thread::id, pair<unsigned, GLuint> >::iterator contextIt = context_.find(threadID);
00384 
00385   if (contextIt == context_.end())
00386   {
00387     context_[threadID] = std::pair<unsigned, GLuint>(1, 0);
00388     map<boost::thread::id, pair<unsigned, GLuint> >::iterator contextIt = context_.find(threadID);
00389 
00390     glutInitWindowPosition(glutGet(GLUT_SCREEN_WIDTH) + 30000, 0);
00391     glutInitWindowSize(1, 1);
00392     GLuint window_id = glutCreateWindow("mesh_filter");
00393     glutDisplayFunc(nullDisplayFunction);
00394 
00395     GLenum err = glewInit();
00396     if (GLEW_OK != err)
00397     {
00398       stringstream errorStream;
00399       errorStream << "Unable to initialize GLEW: " << glewGetErrorString(err);
00400 
00401       throw(runtime_error(errorStream.str()));
00402     }
00403     glutIconifyWindow();
00404     glutHideWindow();
00405 
00406     for (int i = 0; i < 10; ++i)
00407       glutMainLoopEvent();
00408 
00409     context_[threadID] = std::pair<unsigned, GLuint>(1, window_id);
00410   }
00411   else
00412     ++(contextIt->second.first);
00413 }
00414 
00415 void mesh_filter::GLRenderer::deleteGLContext()
00416 {
00417   boost::mutex::scoped_lock _(context_lock_);
00418   boost::thread::id threadID = boost::this_thread::get_id();
00419   map<boost::thread::id, pair<unsigned, GLuint> >::iterator contextIt = context_.find(threadID);
00420   if (contextIt == context_.end())
00421   {
00422     stringstream errorMsg;
00423     errorMsg << "No OpenGL context exists for Thread " << threadID;
00424     throw runtime_error(errorMsg.str());
00425   }
00426 
00427   if (--(contextIt->second.first) == 0)
00428   {
00429     glutDestroyWindow(contextIt->second.second);
00430     context_.erase(contextIt);
00431   }
00432 }
00433 
00434 GLuint mesh_filter::GLRenderer::getColorTexture() const
00435 {
00436   return rgb_id_;
00437 }
00438 
00439 GLuint mesh_filter::GLRenderer::getDepthTexture() const
00440 {
00441   return depth_id_;
00442 }
00443 
00444 const unsigned mesh_filter::GLRenderer::getWidth() const
00445 {
00446   return width_;
00447 }
00448 
00449 const unsigned mesh_filter::GLRenderer::getHeight() const
00450 {
00451   return height_;
00452 }


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Mon Jul 24 2017 02:21:13