43 #include <Eigen/Eigen> 51 #ifdef HAVE_SSE_EXTENSIONS 52 #include <xmmintrin.h> 57 const std::string& render_vertex_shader,
58 const std::string& render_fragment_shader,
59 const std::string& filter_vertex_shader,
60 const std::string& filter_fragment_shader)
61 : sensor_parameters_(sensor_parameters.clone())
62 , next_handle_(FirstLabel)
63 , min_handle_(FirstLabel)
65 , transform_callback_(transform_callback)
67 , padding_offset_(0.01)
68 , shadow_threshold_(0.5)
71 filter_vertex_shader, filter_fragment_shader));
75 const std::string& render_fragment_shader,
76 const std::string& filter_vertex_shader,
77 const std::string& filter_fragment_shader)
86 mesh_renderer_->setShadersFromString(render_vertex_shader, render_fragment_shader);
87 depth_filter_->setShadersFromString(filter_vertex_shader, filter_fragment_shader);
93 glUniform1i(glGetUniformLocation(
depth_filter_->getProgramID(),
"sensor"), 0);
94 glUniform1i(glGetUniformLocation(
depth_filter_->getProgramID(),
"depth"), 2);
95 glUniform1i(glGetUniformLocation(
depth_filter_->getProgramID(),
"label"), 4);
102 glNewList(
canvas_, GL_COMPILE);
107 glVertex3f(-1, -1, 1);
110 glVertex3f(1, -1, 1);
116 glVertex3f(-1, 1, 1);
125 boost::unique_lock<boost::mutex> lock(
jobs_mutex_);
159 mesh_renderer_->setCameraParameters(width, width, width >> 1, height >> 1);
162 depth_filter_->setCameraParameters(width, width, width >> 1, height >> 1);
204 throw std::runtime_error(
"Could not remove mesh. Mesh not found!");
210 std::size_t erased =
meshes_.erase(handle);
211 return (erased != 0);
233 boost::unique_lock<boost::mutex> lock(
jobs_mutex_);
248 boost::unique_lock<boost::mutex> lock(
jobs_mutex_);
266 const std::string& render_fragment_shader,
267 const std::string& filter_vertex_shader,
268 const std::string& filter_fragment_shader)
270 initialize(render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader);
274 boost::unique_lock<boost::mutex> lock(
jobs_mutex_);
293 if (type != GL_FLOAT && type != GL_UNSIGNED_SHORT)
295 std::stringstream msg;
296 msg <<
"unknown type \"" << type <<
"\". Allowed values are GL_FLOAT or GL_UNSIGNED_SHORT.";
297 throw std::runtime_error(msg.str());
313 glEnable(GL_TEXTURE_2D);
314 glEnable(GL_DEPTH_TEST);
315 glDepthFunc(GL_LESS);
316 glEnable(GL_CULL_FACE);
317 glCullFace(GL_FRONT);
318 glDisable(GL_ALPHA_TEST);
321 GLuint padding_coefficients_id = glGetUniformLocation(
mesh_renderer_->getProgramID(),
"padding_coefficients");
322 Eigen::Vector3f padding_coefficients =
324 glUniform3f(padding_coefficients_id, padding_coefficients[0], padding_coefficients[1], padding_coefficients[2]);
326 Eigen::Affine3d transform;
327 for (std::map<MeshHandle, GLMeshPtr>::const_iterator meshIt =
meshes_.begin(); meshIt !=
meshes_.end(); ++meshIt)
329 meshIt->second->render(transform);
338 glEnable(GL_TEXTURE_2D);
339 glEnable(GL_DEPTH_TEST);
340 glDepthFunc(GL_ALWAYS);
341 glDisable(GL_CULL_FACE);
342 glDisable(GL_ALPHA_TEST);
353 glActiveTexture(GL_TEXTURE0);
359 if (encoding == GL_UNSIGNED_SHORT)
365 glPixelTransferf(GL_DEPTH_SCALE, scale * 65.535);
367 glPixelTransferf(GL_DEPTH_SCALE, scale);
368 glPixelTransferf(GL_DEPTH_BIAS, -scale *
sensor_parameters_->getNearClippingPlaneDistance());
371 GL_DEPTH_COMPONENT, encoding, sensor_data);
372 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
373 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
374 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
375 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
378 glActiveTexture(GL_TEXTURE2);
379 glBindTexture(GL_TEXTURE_2D, depth_texture);
382 glActiveTexture(GL_TEXTURE4);
383 glBindTexture(GL_TEXTURE_2D, color_texture);
void addJob(const JobPtr &job) const
add a Job for the main thread that needs to be executed there
void getDepthBuffer(float *buffer) const
retrieves the depth buffer from OpenGL
bool removeMeshHelper(MeshHandle handle)
used within a Job to allow the main thread removing meshes
void setPaddingScale(float scale)
set the scale component of padding used to multiply with sensor-specific padding coefficients to get ...
float padding_offset_
padding offset
boost::mutex meshes_mutex_
mutex for synchronization of updating filtered meshes
boost::mutex jobs_mutex_
mutex required for synchronization of condition states
void setTransformCallback(const TransformCallback &transform_callback)
set the callback for retrieving transformations for each mesh.
GLRendererPtr mesh_renderer_
first pass renderer for rendering the mesh
void getFilteredDepth(float *depth) const
retrieves the filtered depth values
float padding_scale_
padding scale
GLuint sensor_depth_texture_
handle depth texture from sensor data
MeshHandle addMesh(const shapes::Mesh &mesh)
adds a mesh to the filter object.
GLMesh represents a mesh from geometric_shapes for rendering in GL frame buffers. ...
~MeshFilterBase()
Desctructor.
GLuint canvas_
canvas element (screen-filling quad) for second pass
MeshFilterBase(const TransformCallback &transform_callback, const SensorModel::Parameters &sensor_parameters, const std::string &render_vertex_shader="", const std::string &render_fragment_shader="", const std::string &filter_vertex_shader="", const std::string &filter_fragment_shader="")
Constructor.
TransformCallback transform_callback_
callback function for retrieving the mesh transformations
SensorModel::ParametersPtr sensor_parameters_
the parameters of the used sensor model
Abstracts the OpenGL frame buffer objects, and provides an interface to render meshes, and retrieve the color and depth ap from opengl.
MeshHandle min_handle_
Handle values below this are all taken (this variable is used for more efficient computation of next_...
void run(const std::string &render_vertex_shader, const std::string &render_fragment_shader, const std::string &filter_vertex_shader, const std::string &filter_fragment_shader)
filtering thread
void removeMesh(MeshHandle mesh_handle)
removes a mesh given by its handle
MeshHandle next_handle_
next handle to be used for next mesh that is added
float shadow_threshold_
threshold for shadowed pixels vs. filtered pixels
void initialize(const std::string &render_vertex_shader, const std::string &render_fragment_shader, const std::string &filter_vertex_shader, const std::string &filter_fragment_shader)
initializes OpenGL related things as well as renderers
void getFilteredLabels(LabelType *labels) const
retrieves the labels of the input data
Abstract Interface defining Sensor Parameters.
bool stop_
indicates whether the filtering loop should stop
boost::condition_variable jobs_condition_
condition variable to notify the filtering thread if a new image arrived
virtual void transformModelDepthToMetricDepth(float *depth) const
transforms depth values from rendered model to metric depth values
void getModelDepth(float *depth) const
retrieves the depth values of the rendered model
boost::thread filter_thread_
the filtering thread that also holds the OpenGL context
void getModelLabels(LabelType *labels) const
retrieves the labels of the rendered model
void doFilter(const void *sensor_data, const int encoding) const
the filter method that does the magic
const ReturnType & getResult() const
void deInitialize()
cleaning up
virtual void transformFilteredDepthToMetricDepth(float *depth) const
transforms depth values from filtered depth to metric depth values
std::map< MeshHandle, GLMeshPtr > meshes_
storage for meshed to be filtered
boost::mutex transform_callback_mutex_
mutex for synchronization of setting/calling transform_callback_
void setPaddingOffset(float offset)
set the offset component of padding. This value is added to the scaled sensor-specific constant compo...
void setSize(unsigned int width, unsigned int height)
sets the size of the fram buffers
void addMeshHelper(MeshHandle handle, const shapes::Mesh *cmesh)
used within a Job to allow the main thread adding meshes
GLuint shadow_threshold_location_
handle to GLSL location of shadow threshold
void setShadowThreshold(float threshold)
set the shadow threshold. points that are further away than the rendered model are filtered out...
void getColorBuffer(unsigned char *buffer) const
retrieves the color buffer from OpenGL
void filter(const void *sensor_data, GLushort type, bool wait=false) const
label/remove pixels from input depth-image
std::queue< JobPtr > jobs_queue_
OpenGL job queue that need to be processed by the worker thread.
boost::function< bool(MeshHandle, Eigen::Affine3d &)> TransformCallback
GLRendererPtr depth_filter_
second pass renderer for filtering the results of first pass