moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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#pragma once
38
40#include <GL/glew.h>
41#ifdef __APPLE__
42#include <OpenGL/gl.h>
43#else
44#include <GL/gl.h>
45#endif
46#include <string>
47#include <thread>
48#include <mutex>
49#include <map>
50
51#undef near
52#undef far
53
54namespace mesh_filter
55{
56MOVEIT_CLASS_FORWARD(GLRenderer); // Defines GLRendererPtr, ConstPtr, WeakPtr... etc
57
63{
64public:
73 GLRenderer(unsigned width, unsigned height, double near = 0.1, double far = 10.0);
74
77
82 void begin() const;
83
88 void end() const;
89
95 void callList(GLuint list) const;
96
102 void getColorBuffer(unsigned char* buffer) const;
103
109 void getDepthBuffer(float* buffer) const;
110
119 GLuint setShadersFromFile(const std::string& vertex_filename, const std::string& fragment_filename);
120
128 GLuint setShadersFromString(const std::string& vertex_shader, const std::string& fragment_shader);
129
138 void setCameraParameters(double fx, double fy, double cx, double cy);
139
146 void setClippingRange(double near, double far);
147
153 const double& getNearClippingDistance() const;
154
160 const double& getFarClippingDistance() const;
161
167 unsigned getWidth() const;
168
174 unsigned getHeight() const;
175
182 void setBufferSize(unsigned width, unsigned height);
183
189 const GLuint& getProgramID() const;
190
196 GLuint getDepthTexture() const;
197
203 GLuint getColorTexture() const;
204
205private:
210 void setCameraParameters() const;
211
218 void readShaderCodeFromFile(const std::string& filename, std::string& source) const;
219
227 GLuint loadShaders(const std::string& vertex_source, const std::string& fragment_source) const;
228
236 GLuint createShader(GLuint shaderID, const std::string& source) const;
237
242 void initFrameBuffers();
243
248 void deleteFrameBuffers();
249
254 static void createGLContext();
255
260 static void deleteGLContext();
261
263 unsigned width_;
264
266 unsigned height_;
267
269 GLuint fbo_id_;
270
272 GLuint rbo_id_;
273
275 GLuint rgb_id_;
276
278 GLuint depth_id_;
279
281 GLuint program_;
282
284 double near_;
285
287 double far_;
288
290 float fx_;
291
293 float fy_;
294
296 float cx_;
297
299 float cy_;
300
302 static std::map<std::thread::id, std::pair<unsigned, GLuint> > s_context;
303
304 /* \brief lock for context map */
305 static std::mutex s_context_lock;
306
307 static bool s_glut_initialized;
308};
309} // namespace mesh_filter
#define MOVEIT_CLASS_FORWARD(C)
Abstracts the OpenGL frame buffer objects, and provides an interface to render meshes,...
Definition gl_renderer.h:63
const double & getFarClippingDistance() const
returns the distance of the far clipping plane in meters
void getDepthBuffer(float *buffer) const
retrieves the depth buffer from OpenGL
void setBufferSize(unsigned width, unsigned height)
set the size of frame buffers
void callList(GLuint list) const
executes a OpenGL list
GLuint getColorTexture() const
returns the handle of the color buffer as an OpenGL texture object
GLuint getDepthTexture() const
returns the handle of the depth buffer as an OpenGL texture object
unsigned getWidth() const
returns the width of the frame buffer objectsin pixels
void end() const
finalizes the frame buffers after rendering and/or manipulating
void begin() const
initializes the frame buffers for rendering and or manipulating
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.
void setClippingRange(double near, double far)
sets the near and far clipping plane distances in meters
void getColorBuffer(unsigned char *buffer) const
retrieves the color buffer from OpenGL
unsigned getHeight() const
returns the height of the frame buffer objects in pixels
const double & getNearClippingDistance() const
returns the distance of the near 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.
~GLRenderer()
destructor, destroys frame buffer objects and OpenGL context
void setCameraParameters(double fx, double fy, double cx, double cy)
set the camera parameters
const GLuint & getProgramID() const