#include <mesh_filter_base.h>
|
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 More...
|
|
void | deInitialize () |
| cleaning up More...
|
|
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 More...
|
|
void | doFilter (const void *sensor_data, const int encoding) const |
| the filter method that does the magic More...
|
|
void | addMeshHelper (MeshHandle handle, const shapes::Mesh &cmesh) |
| used within a Job to allow the main thread adding meshes More...
|
|
bool | removeMeshHelper (MeshHandle handle) |
| used within a Job to allow the main thread removing meshes More...
|
|
void | addJob (const JobPtr &job) const |
| add a Job for the main thread that needs to be executed there More...
|
|
void | setSize (unsigned int width, unsigned int height) |
| sets the size of the fram buffers More...
|
|
Definition at line 63 of file mesh_filter_base.h.
◆ TransformCallback
◆ anonymous enum
Enumerator |
---|
BACKGROUND | |
SHADOW | |
NEAR_CLIP | |
FAR_CLIP | |
FIRST_LABEL | |
Definition at line 71 of file mesh_filter_base.h.
◆ MeshFilterBase()
mesh_filter::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 = "" |
|
) |
| |
◆ ~MeshFilterBase()
mesh_filter::MeshFilterBase::~MeshFilterBase |
( |
| ) |
|
◆ addJob()
void mesh_filter::MeshFilterBase::addJob |
( |
const JobPtr & |
job | ) |
const |
|
protected |
add a Job for the main thread that needs to be executed there
- Parameters
-
[in] | job | the job object that has the function o be executed |
Definition at line 138 of file mesh_filter_base.cpp.
◆ addMesh()
◆ addMeshHelper()
void mesh_filter::MeshFilterBase::addMeshHelper |
( |
MeshHandle |
handle, |
|
|
const shapes::Mesh & |
cmesh |
|
) |
| |
|
protected |
used within a Job to allow the main thread adding meshes
- Parameters
-
[in] | handle | the handle of the mesh that is predetermined and passed |
[in] | cmesh | the mesh to be added to the corresponding handle |
Definition at line 191 of file mesh_filter_base.cpp.
◆ deInitialize()
void mesh_filter::MeshFilterBase::deInitialize |
( |
| ) |
|
|
protected |
◆ doFilter()
void mesh_filter::MeshFilterBase::doFilter |
( |
const void * |
sensor_data, |
|
|
const int |
encoding |
|
) |
| const |
|
protected |
the filter method that does the magic
- Parameters
-
[in] | sensor_data | pointer to the buffer containing the depth readings |
[in] | encoding | the representation of the depth readings in the buffer |
Definition at line 308 of file mesh_filter_base.cpp.
◆ filter()
void mesh_filter::MeshFilterBase::filter |
( |
const void * |
sensor_data, |
|
|
GLushort |
type, |
|
|
bool |
wait = false |
|
) |
| const |
◆ getFilteredDepth()
void mesh_filter::MeshFilterBase::getFilteredDepth |
( |
float * |
depth | ) |
const |
◆ getFilteredLabels()
void mesh_filter::MeshFilterBase::getFilteredLabels |
( |
LabelType * |
labels | ) |
const |
retrieves the labels of the input data
- Author
- Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
- Parameters
-
[out] | labels | pointer to buffer to be filled with labels |
- Note
- labels are corresponding 1-1 to the mesh handles. 0 and 1 are reserved indicating either background (0) or shadow (1) The upper 8bit of a label is filled with the user given flag (see addMesh)
Definition at line 259 of file mesh_filter_base.cpp.
◆ getModelDepth()
void mesh_filter::MeshFilterBase::getModelDepth |
( |
float * |
depth | ) |
const |
◆ getModelLabels()
void mesh_filter::MeshFilterBase::getModelLabels |
( |
LabelType * |
labels | ) |
const |
retrieves the labels of the rendered model
- Author
- Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
- Parameters
-
[out] | labels | pointer to buffer to be filled with labels |
- Note
- labels are corresponding 1-1 to the mesh handles. 0 and 1 are reserved indicating either background (0) or shadow (1) The upper 8bit of a label is filled with the user given flag (see addMesh)
- Todo:
- How is this data different from the filtered labels?
Definition at line 220 of file mesh_filter_base.cpp.
◆ initialize()
void mesh_filter::MeshFilterBase::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 |
|
) |
| |
|
protected |
◆ removeMesh()
void mesh_filter::MeshFilterBase::removeMesh |
( |
MeshHandle |
mesh_handle | ) |
|
◆ removeMeshHelper()
bool mesh_filter::MeshFilterBase::removeMeshHelper |
( |
MeshHandle |
handle | ) |
|
|
protected |
used within a Job to allow the main thread removing meshes
- Parameters
-
[in] | handle | the handle of the mesh to be removed |
Definition at line 209 of file mesh_filter_base.cpp.
◆ run()
void mesh_filter::MeshFilterBase::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 |
|
) |
| |
|
protected |
◆ setPaddingOffset()
void mesh_filter::MeshFilterBase::setPaddingOffset |
( |
float |
offset | ) |
|
set the offset component of padding. This value is added to the scaled sensor-specific constant component.
- Parameters
-
[in] | offset | the offset value |
Definition at line 390 of file mesh_filter_base.cpp.
◆ setPaddingScale()
void mesh_filter::MeshFilterBase::setPaddingScale |
( |
float |
scale | ) |
|
set the scale component of padding used to multiply with sensor-specific padding coefficients to get final coefficients.
- Parameters
-
Definition at line 395 of file mesh_filter_base.cpp.
◆ setShadowThreshold()
void mesh_filter::MeshFilterBase::setShadowThreshold |
( |
float |
threshold | ) |
|
set the shadow threshold. points that are further away than the rendered model are filtered out. Except they are further away than this threshold. Then these points are kept, but its label is set to 1 indicating that it is in the shadow of the model
- Author
- Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
- Parameters
-
[in] | threshold | shadow threshold in meters |
Definition at line 215 of file mesh_filter_base.cpp.
◆ setSize()
void mesh_filter::MeshFilterBase::setSize |
( |
unsigned int |
width, |
|
|
unsigned int |
height |
|
) |
| |
|
protected |
◆ setTransformCallback()
void mesh_filter::MeshFilterBase::setTransformCallback |
( |
const TransformCallback & |
transform_callback | ) |
|
◆ canvas_
GLuint mesh_filter::MeshFilterBase::canvas_ |
|
protected |
◆ depth_filter_
GLRendererPtr mesh_filter::MeshFilterBase::depth_filter_ |
|
protected |
second pass renderer for filtering the results of first pass
Definition at line 273 of file mesh_filter_base.h.
◆ filter_thread_
std::thread mesh_filter::MeshFilterBase::filter_thread_ |
|
protected |
the filtering thread that also holds the OpenGL context
Definition at line 249 of file mesh_filter_base.h.
◆ jobs_condition_
std::condition_variable mesh_filter::MeshFilterBase::jobs_condition_ |
|
mutableprotected |
condition variable to notify the filtering thread if a new image arrived
Definition at line 252 of file mesh_filter_base.h.
◆ jobs_mutex_
std::mutex mesh_filter::MeshFilterBase::jobs_mutex_ |
|
mutableprotected |
mutex required for synchronization of condition states
Definition at line 255 of file mesh_filter_base.h.
◆ jobs_queue_
std::queue<JobPtr> mesh_filter::MeshFilterBase::jobs_queue_ |
|
mutableprotected |
OpenGL job queue that need to be processed by the worker thread.
Definition at line 258 of file mesh_filter_base.h.
◆ mesh_renderer_
GLRendererPtr mesh_filter::MeshFilterBase::mesh_renderer_ |
|
protected |
◆ meshes_
std::map<MeshHandle, GLMeshPtr> mesh_filter::MeshFilterBase::meshes_ |
|
protected |
◆ meshes_mutex_
std::mutex mesh_filter::MeshFilterBase::meshes_mutex_ |
|
mutableprotected |
◆ min_handle_
MeshHandle mesh_filter::MeshFilterBase::min_handle_ |
|
protected |
Handle values below this are all taken (this variable is used for more efficient computation of next_label_)
Definition at line 246 of file mesh_filter_base.h.
◆ next_handle_
MeshHandle mesh_filter::MeshFilterBase::next_handle_ |
|
protected |
◆ padding_offset_
float mesh_filter::MeshFilterBase::padding_offset_ |
|
protected |
◆ padding_scale_
float mesh_filter::MeshFilterBase::padding_scale_ |
|
protected |
◆ sensor_depth_texture_
GLuint mesh_filter::MeshFilterBase::sensor_depth_texture_ |
|
protected |
◆ sensor_parameters_
SensorModel::ParametersPtr mesh_filter::MeshFilterBase::sensor_parameters_ |
|
protected |
◆ shadow_threshold_
float mesh_filter::MeshFilterBase::shadow_threshold_ |
|
protected |
◆ shadow_threshold_location_
GLuint mesh_filter::MeshFilterBase::shadow_threshold_location_ |
|
protected |
◆ stop_
bool mesh_filter::MeshFilterBase::stop_ |
|
protected |
◆ transform_callback_
callback function for retrieving the mesh transformations
Definition at line 285 of file mesh_filter_base.h.
◆ transform_callback_mutex_
std::mutex mesh_filter::MeshFilterBase::transform_callback_mutex_ |
|
mutableprotected |
mutex for synchronization of setting/calling transform_callback_
Definition at line 264 of file mesh_filter_base.h.
The documentation for this class was generated from the following files: