gl_renderer.h
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 #ifndef MOVEIT_MESH_FILTER_GLRENDERER_
00038 #define MOVEIT_MESH_FILTER_GLRENDERER_
00039 
00040 #include <moveit/macros/class_forward.h>
00041 #include <GL/glew.h>
00042 #ifdef __APPLE__
00043 #include <OpenGL/gl.h>
00044 #else
00045 #include <GL/gl.h>
00046 #endif
00047 #include <string>
00048 #include <boost/thread.hpp>
00049 
00050 namespace mesh_filter
00051 {
00052 MOVEIT_CLASS_FORWARD(GLRenderer);
00053 
00058 class GLRenderer
00059 {
00060 public:
00069   GLRenderer(unsigned width, unsigned height, float near = 0.1, float far = 10.0);
00070 
00072   ~GLRenderer();
00073 
00078   void begin() const;
00079 
00084   void end() const;
00085 
00091   void callList(GLuint list) const;
00092 
00098   void getColorBuffer(unsigned char* buffer) const;
00099 
00105   void getDepthBuffer(float* buffer) const;
00106 
00115   GLuint setShadersFromFile(const std::string& vertex_filename, const std::string& fragment_filename);
00116 
00124   GLuint setShadersFromString(const std::string& vertex_shader, const std::string& fragment_shader);
00125 
00134   void setCameraParameters(float fx, float fy, float cx, float cy);
00135 
00142   void setClippingRange(float near, float far);
00143 
00149   const float& getNearClippingDistance() const;
00150 
00156   const float& getFarClippingDistance() const;
00157 
00163   const unsigned getWidth() const;
00164 
00170   const unsigned getHeight() const;
00171 
00178   void setBufferSize(unsigned width, unsigned height);
00179 
00185   const GLuint& getProgramID() const;
00186 
00192   GLuint getDepthTexture() const;
00193 
00199   GLuint getColorTexture() const;
00200 
00201 private:
00206   void setCameraParameters() const;
00207 
00214   void readShaderCodeFromFile(const std::string& filename, std::string& source) const;
00215 
00223   GLuint loadShaders(const std::string& vertex_source, const std::string& fragment_source) const;
00224 
00232   GLuint createShader(GLuint shaderID, const std::string& source) const;
00233 
00238   void initFrameBuffers();
00239 
00244   void deleteFrameBuffers();
00245 
00250   static void createGLContext();
00251 
00256   static void deleteGLContext();
00257 
00259   unsigned width_;
00260 
00262   unsigned height_;
00263 
00265   GLuint fbo_id_;
00266 
00268   GLuint rbo_id_;
00269 
00271   GLuint rgb_id_;
00272 
00274   GLuint depth_id_;
00275 
00277   GLuint program_;
00278 
00280   float near_;
00281 
00283   float far_;
00284 
00286   float fx_;
00287 
00289   float fy_;
00290 
00292   float cx_;
00293 
00295   float cy_;
00296 
00298   static std::map<boost::thread::id, std::pair<unsigned, GLuint> > context_;
00299 
00300   /* \brief lock for context map */
00301   static boost::mutex context_lock_;
00302 
00303   static bool glutInitialized_;
00304 };
00305 }  // namespace mesh_filter
00306 #endif


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