41 #include <geometric_shapes/shapes.h>
42 #include <geometric_shapes/shape_operations.h>
43 #include <Eigen/Eigen>
50 #ifdef HAVE_SSE_EXTENSIONS
51 #include <xmmintrin.h>
56 const std::string& render_vertex_shader,
57 const std::string& render_fragment_shader,
58 const std::string& filter_vertex_shader,
59 const std::string& filter_fragment_shader)
60 : sensor_parameters_(sensor_parameters.clone())
61 , next_handle_(FIRST_LABEL)
62 , min_handle_(FIRST_LABEL)
64 , transform_callback_(transform_callback)
66 , padding_offset_(0.01)
67 , shadow_threshold_(0.5)
70 std::thread([
this, render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader] {
71 run(render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader);
76 const std::string& render_fragment_shader,
77 const std::string& filter_vertex_shader,
78 const std::string& filter_fragment_shader)
80 mesh_renderer_ = std::make_shared<GLRenderer>(sensor_parameters_->getWidth(), sensor_parameters_->getHeight(),
81 sensor_parameters_->getNearClippingPlaneDistance(),
82 sensor_parameters_->getFarClippingPlaneDistance());
83 depth_filter_ = std::make_shared<GLRenderer>(sensor_parameters_->getWidth(), sensor_parameters_->getHeight(),
84 sensor_parameters_->getNearClippingPlaneDistance(),
85 sensor_parameters_->getFarClippingPlaneDistance());
87 mesh_renderer_->setShadersFromString(render_vertex_shader, render_fragment_shader);
88 depth_filter_->setShadersFromString(filter_vertex_shader, filter_fragment_shader);
90 depth_filter_->begin();
92 glGenTextures(1, &sensor_depth_texture_);
94 glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(),
"sensor"), 0);
95 glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(),
"depth"), 2);
96 glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(),
"label"), 4);
98 shadow_threshold_location_ = glGetUniformLocation(depth_filter_->getProgramID(),
"shadow_threshold");
100 depth_filter_->end();
102 canvas_ = glGenLists(1);
103 glNewList(canvas_, GL_COMPILE);
108 glVertex3f(-1, -1, 1);
111 glVertex3f(1, -1, 1);
117 glVertex3f(-1, 1, 1);
126 std::unique_lock<std::mutex> lock(jobs_mutex_);
128 while (!jobs_queue_.empty())
130 jobs_queue_.front()->cancel();
134 jobs_condition_.notify_one();
135 filter_thread_.join();
141 std::unique_lock<std::mutex> _(jobs_mutex_);
142 jobs_queue_.push(job);
144 jobs_condition_.notify_one();
149 glDeleteLists(canvas_, 1);
150 glDeleteTextures(1, &sensor_depth_texture_);
153 mesh_renderer_.reset();
154 depth_filter_.reset();
159 mesh_renderer_->setBufferSize(width, height);
160 mesh_renderer_->setCameraParameters(width, width, width >> 1, height >> 1);
162 depth_filter_->setBufferSize(width, height);
163 depth_filter_->setCameraParameters(width, width, width >> 1, height >> 1);
168 std::unique_lock<std::mutex> _(transform_callback_mutex_);
169 transform_callback_ = transform_callback;
174 std::unique_lock<std::mutex> _(meshes_mutex_);
176 JobPtr job(
new FilterJob<void>([
this, &mesh] { addMeshHelper(next_handle_, mesh); }));
180 const std::size_t sz = min_handle_ + meshes_.size() + 1;
181 for (std::size_t i = min_handle_; i < sz; ++i)
182 if (meshes_.find(i) == meshes_.end())
187 min_handle_ = next_handle_;
193 meshes_[handle] = std::make_shared<GLMesh>(cmesh, handle);
198 std::unique_lock<std::mutex> _(meshes_mutex_);
205 throw std::runtime_error(
"Could not remove mesh. Mesh not found!");
206 min_handle_ = std::min(handle, min_handle_);
211 std::size_t erased = meshes_.erase(handle);
212 return (erased != 0);
217 shadow_threshold_ = threshold;
223 new FilterJob<void>([&renderer = *mesh_renderer_, labels] { renderer.getColorBuffer((
unsigned char*)labels); }));
231 std::make_shared<FilterJob<void>>([&renderer = *mesh_renderer_, depth] { renderer.getDepthBuffer(depth); });
232 JobPtr job2 = std::make_shared<FilterJob<void>>(
233 [¶meters = *sensor_parameters_, depth] { parameters.transformModelDepthToMetricDepth(depth); });
235 std::unique_lock<std::mutex> lock(jobs_mutex_);
236 jobs_queue_.push(job1);
237 jobs_queue_.push(job2);
239 jobs_condition_.notify_one();
246 JobPtr job1 = std::make_shared<FilterJob<void>>([&filter = *depth_filter_, depth] { filter.getDepthBuffer(depth); });
247 JobPtr job2 = std::make_shared<FilterJob<void>>(
248 [¶meters = *sensor_parameters_, depth] { parameters.transformFilteredDepthToMetricDepth(depth); });
250 std::unique_lock<std::mutex> lock(jobs_mutex_);
251 jobs_queue_.push(job1);
252 jobs_queue_.push(job2);
254 jobs_condition_.notify_one();
261 JobPtr job = std::make_shared<FilterJob<void>>(
262 [&filter = *depth_filter_, labels] { filter.getColorBuffer((
unsigned char*)labels); });
268 const std::string& render_fragment_shader,
269 const std::string& filter_vertex_shader,
270 const std::string& filter_fragment_shader)
272 initialize(render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader);
276 std::unique_lock<std::mutex> lock(jobs_mutex_);
278 if (jobs_queue_.empty())
279 jobs_condition_.wait(lock);
281 if (!jobs_queue_.empty())
283 JobPtr job = jobs_queue_.front();
295 if (
type != GL_FLOAT &&
type != GL_UNSIGNED_SHORT)
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());
302 JobPtr job = std::make_shared<FilterJob<void>>([
this, sensor_data,
type] { doFilter(sensor_data,
type); });
310 std::unique_lock<std::mutex> _(transform_callback_mutex_);
312 mesh_renderer_->begin();
313 sensor_parameters_->setRenderParameters(*mesh_renderer_);
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);
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]);
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);
333 mesh_renderer_->end();
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);
349 glUniform1f(shadow_threshold_location_, shadow_threshold_);
351 GLuint depth_texture = mesh_renderer_->getDepthTexture();
352 GLuint color_texture = mesh_renderer_->getColorTexture();
355 glActiveTexture(GL_TEXTURE0);
356 glBindTexture(GL_TEXTURE_2D, sensor_depth_texture_);
359 1.0 / (sensor_parameters_->getFarClippingPlaneDistance() - sensor_parameters_->getNearClippingPlaneDistance());
367 glPixelTransferf(GL_DEPTH_SCALE, scale * 65.535);
369 glPixelTransferf(GL_DEPTH_SCALE, scale);
370 glPixelTransferf(GL_DEPTH_BIAS, -scale * sensor_parameters_->getNearClippingPlaneDistance());
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);
380 glActiveTexture(GL_TEXTURE2);
381 glBindTexture(GL_TEXTURE_2D, depth_texture);
384 glActiveTexture(GL_TEXTURE4);
385 glBindTexture(GL_TEXTURE_2D, color_texture);
387 depth_filter_->end();
392 padding_offset_ = offset;
397 padding_scale_ = scale;
const ReturnType & getResult() const
void setTransformCallback(const TransformCallback &transform_callback)
set the callback for retrieving transformations for each mesh.
void doFilter(const void *sensor_data, const int encoding) const
the filter method that does the magic
void getModelLabels(LabelType *labels) const
retrieves the labels of the rendered model
void filter(const void *sensor_data, GLushort type, bool wait=false) const
label/remove pixels from input depth-image
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.
bool removeMeshHelper(MeshHandle handle)
used within a Job to allow the main thread removing meshes
~MeshFilterBase()
Destructor.
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 addMeshHelper(MeshHandle handle, const shapes::Mesh &cmesh)
used within a Job to allow the main thread adding meshes
void removeMesh(MeshHandle mesh_handle)
removes a mesh given by its handle
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 addJob(const JobPtr &job) const
add a Job for the main thread that needs to be executed there
void setShadowThreshold(float threshold)
set the shadow threshold. points that are further away than the rendered model are filtered out....
void deInitialize()
cleaning up
MeshHandle addMesh(const shapes::Mesh &mesh)
adds a mesh to the filter object.
std::function< bool(MeshHandle, Eigen::Isometry3d &)> TransformCallback
void setPaddingOffset(float offset)
set the offset component of padding. This value is added to the scaled sensor-specific constant compo...
void getModelDepth(float *depth) const
retrieves the depth values of the rendered model
void getFilteredLabels(LabelType *labels) const
retrieves the labels of the input data
std::thread filter_thread_
the filtering thread that also holds the OpenGL context
void getFilteredDepth(float *depth) const
retrieves the filtered depth values
void setPaddingScale(float scale)
set the scale component of padding used to multiply with sensor-specific padding coefficients to get ...
void setSize(unsigned int width, unsigned int height)
sets the size of the fram buffers
Abstract Interface defining Sensor Parameters.