gl_renderer.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Suat Gedikli */
36 
37 #ifndef MOVEIT_MESH_FILTER_GLRENDERER_
38 #define MOVEIT_MESH_FILTER_GLRENDERER_
39 
41 #include <GL/glew.h>
42 #ifdef __APPLE__
43 #include <OpenGL/gl.h>
44 #else
45 #include <GL/gl.h>
46 #endif
47 #include <string>
48 #include <boost/thread.hpp>
49 
50 namespace mesh_filter
51 {
52 MOVEIT_CLASS_FORWARD(GLRenderer);
53 
59 {
60 public:
69  GLRenderer(unsigned width, unsigned height, float near = 0.1, float far = 10.0);
70 
72  ~GLRenderer();
73 
78  void begin() const;
79 
84  void end() const;
85 
91  void callList(GLuint list) const;
92 
98  void getColorBuffer(unsigned char* buffer) const;
99 
105  void getDepthBuffer(float* buffer) const;
106 
115  GLuint setShadersFromFile(const std::string& vertex_filename, const std::string& fragment_filename);
116 
124  GLuint setShadersFromString(const std::string& vertex_shader, const std::string& fragment_shader);
125 
134  void setCameraParameters(float fx, float fy, float cx, float cy);
135 
142  void setClippingRange(float near, float far);
143 
149  const float& getNearClippingDistance() const;
150 
156  const float& getFarClippingDistance() const;
157 
163  const unsigned getWidth() const;
164 
170  const unsigned getHeight() const;
171 
178  void setBufferSize(unsigned width, unsigned height);
179 
185  const GLuint& getProgramID() const;
186 
192  GLuint getDepthTexture() const;
193 
199  GLuint getColorTexture() const;
200 
201 private:
206  void setCameraParameters() const;
207 
214  void readShaderCodeFromFile(const std::string& filename, std::string& source) const;
215 
223  GLuint loadShaders(const std::string& vertex_source, const std::string& fragment_source) const;
224 
232  GLuint createShader(GLuint shaderID, const std::string& source) const;
233 
238  void initFrameBuffers();
239 
244  void deleteFrameBuffers();
245 
250  static void createGLContext();
251 
256  static void deleteGLContext();
257 
259  unsigned width_;
260 
262  unsigned height_;
263 
265  GLuint fbo_id_;
266 
268  GLuint rbo_id_;
269 
271  GLuint rgb_id_;
272 
274  GLuint depth_id_;
275 
277  GLuint program_;
278 
280  float near_;
281 
283  float far_;
284 
286  float fx_;
287 
289  float fy_;
290 
292  float cx_;
293 
295  float cy_;
296 
298  static std::map<boost::thread::id, std::pair<unsigned, GLuint> > context_;
299 
300  /* \brief lock for context map */
301  static boost::mutex context_lock_;
302 
303  static bool glutInitialized_;
304 };
305 } // namespace mesh_filter
306 #endif
void getDepthBuffer(float *buffer) const
retrieves the depth buffer from OpenGL
const GLuint & getProgramID() const
GLuint loadShaders(const std::string &vertex_source, const std::string &fragment_source) const
Compiles, Links and adds the GLSL shaders from strings containing the source codes.
filename
GLuint rgb_id_
handle to color buffer
Definition: gl_renderer.h:271
float far_
distance of far clipping plane in meters
Definition: gl_renderer.h:283
float fy_
focal length in y-direction of camera in pixels
Definition: gl_renderer.h:289
static bool glutInitialized_
Definition: gl_renderer.h:303
GLuint rbo_id_
handle to render buffer object
Definition: gl_renderer.h:268
void callList(GLuint list) const
executes a OpenGL list
unsigned height_
height of frame buffer objects in pixels
Definition: gl_renderer.h:262
const float & getFarClippingDistance() const
returns the distance of the far clipping plane in meters
GLuint setShadersFromString(const std::string &vertex_shader, const std::string &fragment_shader)
loads, compiles, links and adds GLSL shaders from string to the current OpenGL context.
void deleteFrameBuffers()
deletes the frame buffer objects
const unsigned getWidth() const
returns the width of the frame buffer objectsin pixels
const float & getNearClippingDistance() const
returns the distance of the near clipping plane in meters
GLuint fbo_id_
handle to frame buffer object
Definition: gl_renderer.h:265
void initFrameBuffers()
initializes the frame buffer objects
Abstracts the OpenGL frame buffer objects, and provides an interface to render meshes, and retrieve the color and depth ap from opengl.
Definition: gl_renderer.h:58
float cx_
x-coordinate of principal point of camera in pixels
Definition: gl_renderer.h:292
GLuint depth_id_
handle to depth buffer
Definition: gl_renderer.h:274
static void deleteGLContext()
deletes OpenGL context for the current thread
float near_
distance of near clipping plane in meters
Definition: gl_renderer.h:280
GLuint getColorTexture() const
returns the handle of the color buffer as an OpenGL texture object
void end() const
finalizes the frame buffers after rendering and/or manipulating
~GLRenderer()
destructor, destroys frame buffer objects and OpenGL context
Definition: gl_renderer.cpp:75
GLuint createShader(GLuint shaderID, const std::string &source) const
create a OpenGL shader object from the shader source code
GLuint setShadersFromFile(const std::string &vertex_filename, const std::string &fragment_filename)
loads, compiles, links and adds GLSL shaders from files to the current OpenGL context.
static void createGLContext()
create the OpenGL context if required. Only on context is created for each thread ...
MOVEIT_CLASS_FORWARD(Job)
void setCameraParameters() const
sets the OpenGL camera parameters
void readShaderCodeFromFile(const std::string &filename, std::string &source) const
reads shader source code from file to a string
void begin() const
initializes the frame buffers for rendering and or manipulating
GLRenderer(unsigned width, unsigned height, float near=0.1, float far=10.0)
constructs the frame buffer object in a new OpenGL context.
Definition: gl_renderer.cpp:56
static boost::mutex context_lock_
Definition: gl_renderer.h:301
static std::map< boost::thread::id, std::pair< unsigned, GLuint > > context_
map from thread id to OpenGL context
Definition: gl_renderer.h:298
const unsigned getHeight() const
returns the height of the frame buffer objects in pixels
float cy_
y-coordinate of principal point of camera in pixels
Definition: gl_renderer.h:295
GLuint getDepthTexture() const
returns the handle of the depth buffer as an OpenGL texture object
GLuint program_
handle to program that is currently used
Definition: gl_renderer.h:277
void setBufferSize(unsigned width, unsigned height)
set the size of fram buffers
Definition: gl_renderer.cpp:84
float fx_
focal length in x-direction of camera in pixels
Definition: gl_renderer.h:286
void setClippingRange(float near, float far)
sets the near and far clipping plane distances in meters
Definition: gl_renderer.cpp:95
unsigned width_
width of frame buffer objects in pixels
Definition: gl_renderer.h:259
void getColorBuffer(unsigned char *buffer) const
retrieves the color buffer from OpenGL


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sun Oct 18 2020 13:17:23