moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
41#include <geometric_shapes/shapes.h>
42#include <geometric_shapes/shape_operations.h>
43#include <Eigen/Eigen>
44
45#include <memory>
46#include <stdexcept>
47#include <sstream>
48
49// include SSE headers
50#ifdef HAVE_SSE_EXTENSIONS
51#include <xmmintrin.h>
52#endif
53
55 const SensorModel::Parameters& sensor_parameters,
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) // 0 and 1 are reserved!
62 , min_handle_(FIRST_LABEL)
63 , stop_(false)
64 , transform_callback_(transform_callback)
65 , padding_scale_(1.0)
66 , padding_offset_(0.01)
67 , shadow_threshold_(0.5)
68{
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);
72 });
73}
74
75void mesh_filter::MeshFilterBase::initialize(const std::string& render_vertex_shader,
76 const std::string& render_fragment_shader,
77 const std::string& filter_vertex_shader,
78 const std::string& filter_fragment_shader)
79{
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());
86
87 mesh_renderer_->setShadersFromString(render_vertex_shader, render_fragment_shader);
88 depth_filter_->setShadersFromString(filter_vertex_shader, filter_fragment_shader);
89
90 depth_filter_->begin();
91
92 glGenTextures(1, &sensor_depth_texture_);
93
94 glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(), "sensor"), 0);
95 glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(), "depth"), 2);
96 glUniform1i(glGetUniformLocation(depth_filter_->getProgramID(), "label"), 4);
97
98 shadow_threshold_location_ = glGetUniformLocation(depth_filter_->getProgramID(), "shadow_threshold");
99
100 depth_filter_->end();
101
102 canvas_ = glGenLists(1);
103 glNewList(canvas_, GL_COMPILE);
104 glBegin(GL_QUADS);
105
106 glColor3f(1, 1, 1);
107 glTexCoord2f(0, 0);
108 glVertex3f(-1, -1, 1);
109
110 glTexCoord2f(1, 0);
111 glVertex3f(1, -1, 1);
112
113 glTexCoord2f(1, 1);
114 glVertex3f(1, 1, 1);
115
116 glTexCoord2f(0, 1);
117 glVertex3f(-1, 1, 1);
118
119 glEnd();
120 glEndList();
121}
122
124{
125 {
126 std::unique_lock<std::mutex> lock(jobs_mutex_);
127 stop_ = true;
128 while (!jobs_queue_.empty())
129 {
130 jobs_queue_.front()->cancel();
131 jobs_queue_.pop();
132 }
133 }
134 jobs_condition_.notify_one();
135 filter_thread_.join();
136}
137
138void mesh_filter::MeshFilterBase::addJob(const JobPtr& job) const
139{
140 {
141 std::unique_lock<std::mutex> _(jobs_mutex_);
142 jobs_queue_.push(job);
143 }
144 jobs_condition_.notify_one();
145}
146
148{
149 glDeleteLists(canvas_, 1);
150 glDeleteTextures(1, &sensor_depth_texture_);
151
152 meshes_.clear();
153 mesh_renderer_.reset();
154 depth_filter_.reset();
155}
156
157void mesh_filter::MeshFilterBase::setSize(unsigned int width, unsigned int height)
158{
159 mesh_renderer_->setBufferSize(width, height);
160 mesh_renderer_->setCameraParameters(width, width, width >> 1, height >> 1);
161
162 depth_filter_->setBufferSize(width, height);
163 depth_filter_->setCameraParameters(width, width, width >> 1, height >> 1);
164}
165
167{
168 std::unique_lock<std::mutex> _(transform_callback_mutex_);
169 transform_callback_ = transform_callback;
170}
171
173{
174 std::unique_lock<std::mutex> _(meshes_mutex_);
175
176 JobPtr job(new FilterJob<void>([this, &mesh] { addMeshHelper(next_handle_, mesh); }));
177 addJob(job);
178 job->wait();
179 mesh_filter::MeshHandle ret = next_handle_;
180 const std::size_t sz = min_handle_ + meshes_.size() + 1;
181 for (std::size_t i = min_handle_; i < sz; ++i)
182 {
183 if (meshes_.find(i) == meshes_.end())
184 {
185 next_handle_ = i;
186 break;
187 }
188 }
189 min_handle_ = next_handle_;
190 return ret;
191}
192
193void mesh_filter::MeshFilterBase::addMeshHelper(MeshHandle handle, const shapes::Mesh& cmesh)
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(new FilterJob<void>(
225 [&renderer = *mesh_renderer_, labels] { renderer.getColorBuffer(reinterpret_cast<unsigned char*>(labels)); }));
226 addJob(job);
227 job->wait();
228}
229
231{
232 JobPtr job1 =
233 std::make_shared<FilterJob<void>>([&renderer = *mesh_renderer_, depth] { renderer.getDepthBuffer(depth); });
234 JobPtr job2 = std::make_shared<FilterJob<void>>(
235 [&parameters = *sensor_parameters_, depth] { parameters.transformModelDepthToMetricDepth(depth); });
236 {
237 std::unique_lock<std::mutex> lock(jobs_mutex_);
238 jobs_queue_.push(job1);
239 jobs_queue_.push(job2);
240 }
241 jobs_condition_.notify_one();
242 job1->wait();
243 job2->wait();
244}
245
247{
248 JobPtr job1 = std::make_shared<FilterJob<void>>([&filter = *depth_filter_, depth] { filter.getDepthBuffer(depth); });
249 JobPtr job2 = std::make_shared<FilterJob<void>>(
250 [&parameters = *sensor_parameters_, depth] { parameters.transformFilteredDepthToMetricDepth(depth); });
251 {
252 std::unique_lock<std::mutex> lock(jobs_mutex_);
253 jobs_queue_.push(job1);
254 jobs_queue_.push(job2);
255 }
256 jobs_condition_.notify_one();
257 job1->wait();
258 job2->wait();
259}
260
262{
263 JobPtr job = std::make_shared<FilterJob<void>>(
264 [&filter = *depth_filter_, labels] { filter.getColorBuffer(reinterpret_cast<unsigned char*>(labels)); });
265 addJob(job);
266 job->wait();
267}
268
269void mesh_filter::MeshFilterBase::run(const std::string& render_vertex_shader,
270 const std::string& render_fragment_shader,
271 const std::string& filter_vertex_shader,
272 const std::string& filter_fragment_shader)
273{
274 initialize(render_vertex_shader, render_fragment_shader, filter_vertex_shader, filter_fragment_shader);
275
276 while (!stop_)
277 {
278 std::unique_lock<std::mutex> lock(jobs_mutex_);
279 // check if we have new sensor data to be processed. If not, wait until we get notified.
280 if (jobs_queue_.empty())
281 jobs_condition_.wait(lock);
282
283 if (!jobs_queue_.empty())
284 {
285 JobPtr job = jobs_queue_.front();
286 jobs_queue_.pop();
287 lock.unlock();
288 job->execute();
289 lock.lock();
290 }
291 }
292 deInitialize();
293}
294
295void mesh_filter::MeshFilterBase::filter(const void* sensor_data, GLushort type, bool wait) const
296{
297 if (type != GL_FLOAT && type != GL_UNSIGNED_SHORT)
298 {
299 std::stringstream msg;
300 msg << "unknown type \"" << type << "\". Allowed values are GL_FLOAT or GL_UNSIGNED_SHORT.";
301 throw std::runtime_error(msg.str());
302 }
303
304 JobPtr job = std::make_shared<FilterJob<void>>([this, sensor_data, type] { doFilter(sensor_data, type); });
305 addJob(job);
306 if (wait)
307 job->wait();
308}
309
310void mesh_filter::MeshFilterBase::doFilter(const void* sensor_data, const int encoding) const
311{
312 std::unique_lock<std::mutex> _(transform_callback_mutex_);
313
314 mesh_renderer_->begin();
315 sensor_parameters_->setRenderParameters(*mesh_renderer_);
316
317 glEnable(GL_TEXTURE_2D);
318 glEnable(GL_DEPTH_TEST);
319 glDepthFunc(GL_LESS);
320 glEnable(GL_CULL_FACE);
321 glCullFace(GL_FRONT);
322 glDisable(GL_ALPHA_TEST);
323 glDisable(GL_BLEND);
324
325 GLuint padding_coefficients_id = glGetUniformLocation(mesh_renderer_->getProgramID(), "padding_coefficients");
326 Eigen::Vector3f padding_coefficients =
327 sensor_parameters_->getPaddingCoefficients() * padding_scale_ + Eigen::Vector3f(0, 0, padding_offset_);
328 glUniform3f(padding_coefficients_id, padding_coefficients[0], padding_coefficients[1], padding_coefficients[2]);
329
330 Eigen::Isometry3d transform;
331 for (const std::pair<const MeshHandle, GLMeshPtr>& mesh : meshes_)
332 {
333 if (transform_callback_(mesh.first, transform))
334 mesh.second->render(transform);
335 }
336
337 mesh_renderer_->end();
338
339 // now filter the depth_map with the second rendering stage
340 // depth_filter_.setBufferSize (width, height);
341 // depth_filter_.setCameraParameters (fx, fy, cx, cy);
342 depth_filter_->begin();
343 sensor_parameters_->setFilterParameters(*depth_filter_);
344 glEnable(GL_TEXTURE_2D);
345 glEnable(GL_DEPTH_TEST);
346 glDepthFunc(GL_ALWAYS);
347 glDisable(GL_CULL_FACE);
348 glDisable(GL_ALPHA_TEST);
349 glDisable(GL_BLEND);
350
351 // glUniform1f (near_location_, depth_filter_.getNearClippingDistance ());
352 // glUniform1f (far_location_, depth_filter_.getFarClippingDistance ());
353 glUniform1f(shadow_threshold_location_, shadow_threshold_);
354
355 GLuint depth_texture = mesh_renderer_->getDepthTexture();
356 GLuint color_texture = mesh_renderer_->getColorTexture();
357
358 // bind sensor depth
359 glActiveTexture(GL_TEXTURE0);
360 glBindTexture(GL_TEXTURE_2D, sensor_depth_texture_);
361
362 float scale =
363 1.0 / (sensor_parameters_->getFarClippingPlaneDistance() - sensor_parameters_->getNearClippingPlaneDistance());
364
365 if (encoding == GL_UNSIGNED_SHORT)
366 {
367 // unsigned shorts shorts will be mapped to the range 0-1 during transfer. Afterwards we can apply another scale +
368 // offset to
369 // map the values between near and far clipping plane to 0 - 1. -> scale = (65535 * depth - near ) / (far - near)
370 // we have: [0 - 65535] -> [0 - 1]
371 // we want: [near - far] -> [0 - 1]
372 glPixelTransferf(GL_DEPTH_SCALE, scale * 65.535);
373 }
374 else
375 {
376 glPixelTransferf(GL_DEPTH_SCALE, scale);
377 }
378 glPixelTransferf(GL_DEPTH_BIAS, -scale * sensor_parameters_->getNearClippingPlaneDistance());
379
380 glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT, sensor_parameters_->getWidth(), sensor_parameters_->getHeight(), 0,
381 GL_DEPTH_COMPONENT, encoding, sensor_data);
382 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE);
383 glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE);
384 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_NEAREST);
385 glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_NEAREST);
386
387 // bind depth map
388 glActiveTexture(GL_TEXTURE2);
389 glBindTexture(GL_TEXTURE_2D, depth_texture);
390
391 // bind labels
392 glActiveTexture(GL_TEXTURE4);
393 glBindTexture(GL_TEXTURE_2D, color_texture);
394 glCallList(canvas_);
395 depth_filter_->end();
396}
397
399{
400 padding_offset_ = offset;
401}
402
404{
405 padding_scale_ = scale;
406}
const ReturnType & getResult() const
Definition filter_job.h:114
void wait() const
Definition filter_job.h:68
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
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....
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 frame buffers
Abstract Interface defining Sensor Parameters.
unsigned int MeshHandle
uint32_t LabelType