mesh_filter_base.cpp
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 
40 
43 #include <Eigen/Eigen>
44 
45 #include <memory>
46 #include <stdexcept>
47 #include <sstream>
48 
49 #include <ros/console.h>
50 
51 // include SSE headers
52 #ifdef HAVE_SSE_EXTENSIONS
53 #include <xmmintrin.h>
54 #endif
55 
57  const SensorModel::Parameters& sensor_parameters,
58  const std::string& render_vertex_shader,
59  const std::string& render_fragment_shader,
60  const std::string& filter_vertex_shader,
61  const std::string& filter_fragment_shader)
62  : sensor_parameters_(sensor_parameters.clone())
63  , next_handle_(FIRST_LABEL) // 0 and 1 are reserved!
64  , min_handle_(FIRST_LABEL)
65  , stop_(false)
66  , transform_callback_(transform_callback)
67  , padding_scale_(1.0)
68  , padding_offset_(0.01)
69  , shadow_threshold_(0.5)
70 {
72  std::thread([this, render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader] {
73  run(render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader);
74  });
75 }
76 
77 void mesh_filter::MeshFilterBase::initialize(const std::string& render_vertex_shader,
78  const std::string& render_fragment_shader,
79  const std::string& filter_vertex_shader,
80  const std::string& filter_fragment_shader)
81 {
82  mesh_renderer_ = std::make_shared<GLRenderer>(sensor_parameters_->getWidth(), sensor_parameters_->getHeight(),
83  sensor_parameters_->getNearClippingPlaneDistance(),
84  sensor_parameters_->getFarClippingPlaneDistance());
85  depth_filter_ = std::make_shared<GLRenderer>(sensor_parameters_->getWidth(), sensor_parameters_->getHeight(),
86  sensor_parameters_->getNearClippingPlaneDistance(),
87  sensor_parameters_->getFarClippingPlaneDistance());
88 
89  mesh_renderer_->setShadersFromString(render_vertex_shader, render_fragment_shader);
90  depth_filter_->setShadersFromString(filter_vertex_shader, filter_fragment_shader);
91 
92  depth_filter_->begin();
93 
94  glGenTextures(1, &sensor_depth_texture_);
95 
96  glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(), "sensor"), 0);
97  glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(), "depth"), 2);
98  glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(), "label"), 4);
99 
100  shadow_threshold_location_ = glGetUniformLocation(depth_filter_->getProgramID(), "shadow_threshold");
101 
102  depth_filter_->end();
103 
104  canvas_ = glGenLists(1);
105  glNewList(canvas_, GL_COMPILE);
106  glBegin(GL_QUADS);
107 
108  glColor3f(1, 1, 1);
109  glTexCoord2f(0, 0);
110  glVertex3f(-1, -1, 1);
111 
112  glTexCoord2f(1, 0);
113  glVertex3f(1, -1, 1);
114 
115  glTexCoord2f(1, 1);
116  glVertex3f(1, 1, 1);
117 
118  glTexCoord2f(0, 1);
119  glVertex3f(-1, 1, 1);
120 
121  glEnd();
122  glEndList();
123 }
124 
126 {
127  {
128  std::unique_lock<std::mutex> lock(jobs_mutex_);
129  stop_ = true;
130  while (!jobs_queue_.empty())
131  {
132  jobs_queue_.front()->cancel();
133  jobs_queue_.pop();
134  }
135  }
136  jobs_condition_.notify_one();
137  filter_thread_.join();
138 }
139 
140 void mesh_filter::MeshFilterBase::addJob(const JobPtr& job) const
141 {
142  {
143  std::unique_lock<std::mutex> _(jobs_mutex_);
144  jobs_queue_.push(job);
145  }
146  jobs_condition_.notify_one();
147 }
148 
150 {
151  glDeleteLists(canvas_, 1);
152  glDeleteTextures(1, &sensor_depth_texture_);
153 
154  meshes_.clear();
155  mesh_renderer_.reset();
156  depth_filter_.reset();
157 }
158 
159 void mesh_filter::MeshFilterBase::setSize(unsigned int width, unsigned int height)
160 {
161  mesh_renderer_->setBufferSize(width, height);
162  mesh_renderer_->setCameraParameters(width, width, width >> 1, height >> 1);
163 
164  depth_filter_->setBufferSize(width, height);
165  depth_filter_->setCameraParameters(width, width, width >> 1, height >> 1);
166 }
167 
169 {
170  std::unique_lock<std::mutex> _(transform_callback_mutex_);
171  transform_callback_ = transform_callback;
172 }
173 
175 {
176  std::unique_lock<std::mutex> _(meshes_mutex_);
177 
178  JobPtr job(new FilterJob<void>([this, &mesh] { addMeshHelper(next_handle_, mesh); }));
179  addJob(job);
180  job->wait();
181  mesh_filter::MeshHandle ret = next_handle_;
182  const std::size_t sz = min_handle_ + meshes_.size() + 1;
183  for (std::size_t i = min_handle_; i < sz; ++i)
184  if (meshes_.find(i) == meshes_.end())
185  {
186  next_handle_ = i;
187  break;
188  }
189  min_handle_ = next_handle_;
190  return ret;
191 }
192 
194 {
195  meshes_[handle] = std::make_shared<GLMesh>(cmesh, handle);
196 }
197 
199 {
200  std::unique_lock<std::mutex> _(meshes_mutex_);
201  FilterJob<bool>* remover = new FilterJob<bool>([this, handle] { return removeMeshHelper(handle); });
202  JobPtr job(remover);
203  addJob(job);
204  job->wait();
205 
206  if (!remover->getResult())
207  throw std::runtime_error("Could not remove mesh. Mesh not found!");
208  min_handle_ = std::min(handle, min_handle_);
209 }
210 
212 {
213  std::size_t erased = meshes_.erase(handle);
214  return (erased != 0);
215 }
216 
218 {
219  shadow_threshold_ = threshold;
220 }
221 
223 {
224  JobPtr job(
225  new FilterJob<void>([&renderer = *mesh_renderer_, labels] { renderer.getColorBuffer((unsigned char*)labels); }));
226  addJob(job);
227  job->wait();
228 }
229 
231 {
232  JobPtr job1(new FilterJob<void>([&renderer = *mesh_renderer_, depth] { renderer.getDepthBuffer(depth); }));
233  JobPtr job2(new FilterJob<void>(
234  [&parameters = *sensor_parameters_, depth] { parameters.transformModelDepthToMetricDepth(depth); }));
235  {
236  std::unique_lock<std::mutex> lock(jobs_mutex_);
237  jobs_queue_.push(job1);
238  jobs_queue_.push(job2);
239  }
240  jobs_condition_.notify_one();
241  job1->wait();
242  job2->wait();
243 }
244 
246 {
247  JobPtr job1(new FilterJob<void>([&filter = *depth_filter_, depth] { filter.getDepthBuffer(depth); }));
248  JobPtr job2(new FilterJob<void>(
249  [&parameters = *sensor_parameters_, depth] { parameters.transformFilteredDepthToMetricDepth(depth); }));
250  {
251  std::unique_lock<std::mutex> lock(jobs_mutex_);
252  jobs_queue_.push(job1);
253  jobs_queue_.push(job2);
254  }
255  jobs_condition_.notify_one();
256  job1->wait();
257  job2->wait();
258 }
259 
261 {
262  JobPtr job(new FilterJob<void>([&filter = *depth_filter_, labels] { filter.getColorBuffer((unsigned char*)labels); }));
263  addJob(job);
264  job->wait();
265 }
266 
267 void mesh_filter::MeshFilterBase::run(const std::string& render_vertex_shader,
268  const std::string& render_fragment_shader,
269  const std::string& filter_vertex_shader,
270  const std::string& filter_fragment_shader)
271 {
272  initialize(render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader);
273 
274  while (!stop_)
275  {
276  std::unique_lock<std::mutex> lock(jobs_mutex_);
277  // check if we have new sensor data to be processed. If not, wait until we get notified.
278  if (jobs_queue_.empty())
279  jobs_condition_.wait(lock);
280 
281  if (!jobs_queue_.empty())
282  {
283  JobPtr job = jobs_queue_.front();
284  jobs_queue_.pop();
285  lock.unlock();
286  job->execute();
287  lock.lock();
288  }
289  }
290  deInitialize();
291 }
292 
293 void mesh_filter::MeshFilterBase::filter(const void* sensor_data, GLushort type, bool wait) const
294 {
295  if (type != GL_FLOAT && type != GL_UNSIGNED_SHORT)
296  {
297  std::stringstream msg;
298  msg << "unknown type \"" << type << "\". Allowed values are GL_FLOAT or GL_UNSIGNED_SHORT.";
299  throw std::runtime_error(msg.str());
300  }
301 
302  JobPtr job(new FilterJob<void>([this, sensor_data, type] { doFilter(sensor_data, type); }));
303  addJob(job);
304  if (wait)
305  job->wait();
306 }
307 
308 void mesh_filter::MeshFilterBase::doFilter(const void* sensor_data, const int encoding) const
309 {
310  std::unique_lock<std::mutex> _(transform_callback_mutex_);
311 
312  mesh_renderer_->begin();
313  sensor_parameters_->setRenderParameters(*mesh_renderer_);
314 
315  glEnable(GL_TEXTURE_2D);
316  glEnable(GL_DEPTH_TEST);
317  glDepthFunc(GL_LESS);
318  glEnable(GL_CULL_FACE);
319  glCullFace(GL_FRONT);
320  glDisable(GL_ALPHA_TEST);
321  glDisable(GL_BLEND);
322 
323  GLuint padding_coefficients_id = glGetUniformLocation(mesh_renderer_->getProgramID(), "padding_coefficients");
324  Eigen::Vector3f padding_coefficients =
325  sensor_parameters_->getPaddingCoefficients() * padding_scale_ + Eigen::Vector3f(0, 0, padding_offset_);
326  glUniform3f(padding_coefficients_id, padding_coefficients[0], padding_coefficients[1], padding_coefficients[2]);
327 
328  Eigen::Isometry3d transform;
329  for (const std::pair<const MeshHandle, GLMeshPtr>& mesh : meshes_)
330  if (transform_callback_(mesh.first, transform))
331  mesh.second->render(transform);
332 
333  mesh_renderer_->end();
334 
335  // now filter the depth_map with the second rendering stage
336  // depth_filter_.setBufferSize (width, height);
337  // depth_filter_.setCameraParameters (fx, fy, cx, cy);
338  depth_filter_->begin();
339  sensor_parameters_->setFilterParameters(*depth_filter_);
340  glEnable(GL_TEXTURE_2D);
341  glEnable(GL_DEPTH_TEST);
342  glDepthFunc(GL_ALWAYS);
343  glDisable(GL_CULL_FACE);
344  glDisable(GL_ALPHA_TEST);
345  glDisable(GL_BLEND);
346 
347  // glUniform1f (near_location_, depth_filter_.getNearClippingDistance ());
348  // glUniform1f (far_location_, depth_filter_.getFarClippingDistance ());
349  glUniform1f(shadow_threshold_location_, shadow_threshold_);
350 
351  GLuint depth_texture = mesh_renderer_->getDepthTexture();
352  GLuint color_texture = mesh_renderer_->getColorTexture();
353 
354  // bind sensor depth
355  glActiveTexture(GL_TEXTURE0);
356  glBindTexture(GL_TEXTURE_2D, sensor_depth_texture_);
357 
358  float scale =
359  1.0 / (sensor_parameters_->getFarClippingPlaneDistance() - sensor_parameters_->getNearClippingPlaneDistance());
360 
361  if (encoding == GL_UNSIGNED_SHORT)
362  // unsigned shorts shorts will be mapped to the range 0-1 during transfer. Afterwards we can apply another scale +
363  // offset to
364  // map the values between near and far clipping plane to 0 - 1. -> scale = (65535 * depth - near ) / (far - near)
365  // we have: [0 - 65535] -> [0 - 1]
366  // we want: [near - far] -> [0 - 1]
367  glPixelTransferf(GL_DEPTH_SCALE, scale * 65.535);
368  else
369  glPixelTransferf(GL_DEPTH_SCALE, scale);
370  glPixelTransferf(GL_DEPTH_BIAS, -scale * sensor_parameters_->getNearClippingPlaneDistance());
371 
372  glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT, sensor_parameters_->getWidth(), sensor_parameters_->getHeight(), 0,
373  GL_DEPTH_COMPONENT, encoding, sensor_data);
374  glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
375  glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
376  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
377  glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
378 
379  // bind depth map
380  glActiveTexture(GL_TEXTURE2);
381  glBindTexture(GL_TEXTURE_2D, depth_texture);
382 
383  // bind labels
384  glActiveTexture(GL_TEXTURE4);
385  glBindTexture(GL_TEXTURE_2D, color_texture);
386  glCallList(canvas_);
387  depth_filter_->end();
388 }
389 
391 {
392  padding_offset_ = offset;
393 }
394 
396 {
397  padding_scale_ = scale;
398 }
mesh_filter::MeshFilterBase::setPaddingScale
void setPaddingScale(float scale)
set the scale component of padding used to multiply with sensor-specific padding coefficients to get ...
Definition: mesh_filter_base.cpp:395
initialize
bool initialize(MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup)
mesh_filter::FilterJob
Definition: filter_job.h:120
mesh_filter::MeshFilterBase::~MeshFilterBase
~MeshFilterBase()
Desctructor.
Definition: mesh_filter_base.cpp:125
mesh_filter::MeshFilterBase::getModelDepth
void getModelDepth(float *depth) const
retrieves the depth values of the rendered model
Definition: mesh_filter_base.cpp:230
shape_operations.h
mesh_filter::MeshFilterBase::deInitialize
void deInitialize()
cleaning up
Definition: mesh_filter_base.cpp:149
filter_job.h
wait
void wait(int seconds)
gl_mesh.h
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
shapes::Mesh
mesh_filter::FilterJob::getResult
const ReturnType & getResult() const
Definition: filter_job.h:146
mesh_filter::MeshFilterBase::getFilteredLabels
void getFilteredLabels(LabelType *labels) const
retrieves the labels of the input data
Definition: mesh_filter_base.cpp:260
mesh_filter::FilterJob< void >
Definition: filter_job.h:153
mesh_filter::MeshFilterBase::setTransformCallback
void setTransformCallback(const TransformCallback &transform_callback)
set the callback for retrieving transformations for each mesh.
Definition: mesh_filter_base.cpp:168
mesh_filter::MeshFilterBase::getFilteredDepth
void getFilteredDepth(float *depth) const
retrieves the filtered depth values
Definition: mesh_filter_base.cpp:245
console.h
mesh_filter::MeshFilterBase::addMeshHelper
void addMeshHelper(MeshHandle handle, const shapes::Mesh &cmesh)
used within a Job to allow the main thread adding meshes
Definition: mesh_filter_base.cpp:193
mesh_filter::MeshFilterBase::getModelLabels
void getModelLabels(LabelType *labels) const
retrieves the labels of the rendered model
Definition: mesh_filter_base.cpp:222
mesh_filter::MeshFilterBase::run
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
Definition: mesh_filter_base.cpp:267
mesh_filter::MeshFilterBase::doFilter
void doFilter(const void *sensor_data, const int encoding) const
the filter method that does the magic
Definition: mesh_filter_base.cpp:308
mesh_filter::LabelType
uint32_t LabelType
Definition: mesh_filter_base.h:61
mesh_filter::MeshFilterBase::addJob
void addJob(const JobPtr &job) const
add a Job for the main thread that needs to be executed there
Definition: mesh_filter_base.cpp:140
mesh_filter::MeshFilterBase::initialize
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
Definition: mesh_filter_base.cpp:77
shapes.h
mesh_filter::SensorModel::Parameters
Abstract Interface defining Sensor Parameters.
Definition: sensor_model.h:92
mesh_filter::MeshFilterBase::filter
void filter(const void *sensor_data, GLushort type, bool wait=false) const
label/remove pixels from input depth-image
Definition: mesh_filter_base.cpp:293
mesh_filter::MeshFilterBase::setShadowThreshold
void setShadowThreshold(float threshold)
set the shadow threshold. points that are further away than the rendered model are filtered out....
Definition: mesh_filter_base.cpp:217
mesh_filter::MeshFilterBase::setPaddingOffset
void setPaddingOffset(float offset)
set the offset component of padding. This value is added to the scaled sensor-specific constant compo...
Definition: mesh_filter_base.cpp:390
mesh_filter::MeshFilterBase::MeshFilterBase
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.
Definition: mesh_filter_base.cpp:56
mesh_filter::MeshFilterBase::TransformCallback
std::function< bool(MeshHandle, Eigen::Isometry3d &)> TransformCallback
Definition: mesh_filter_base.h:67
mesh_filter::MeshHandle
unsigned int MeshHandle
Definition: mesh_filter_base.h:60
mesh_filter::MeshFilterBase::filter_thread_
std::thread filter_thread_
the filtering thread that also holds the OpenGL context
Definition: mesh_filter_base.h:249
mesh_filter::MeshFilterBase::removeMeshHelper
bool removeMeshHelper(MeshHandle handle)
used within a Job to allow the main thread removing meshes
Definition: mesh_filter_base.cpp:211
mesh_filter_base.h
mesh_filter::Job::wait
void wait() const
Definition: filter_job.h:100
mesh_filter::MeshFilterBase::addMesh
MeshHandle addMesh(const shapes::Mesh &mesh)
adds a mesh to the filter object.
Definition: mesh_filter_base.cpp:174
mesh_filter::MeshFilterBase::removeMesh
void removeMesh(MeshHandle mesh_handle)
removes a mesh given by its handle
Definition: mesh_filter_base.cpp:198
mesh_filter::MeshFilterBase::setSize
void setSize(unsigned int width, unsigned int height)
sets the size of the fram buffers
Definition: mesh_filter_base.cpp:159


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Fri Jun 21 2024 02:26:30