Public Member Functions | List of all members
mesh_filter::MeshFilter< SensorType > Class Template Reference

MeshFilter filters out points that belong to given meshes in depth-images. More...

#include <mesh_filter.h>

Inheritance diagram for mesh_filter::MeshFilter< SensorType >:
Inheritance graph
[legend]

Public Member Functions

 MeshFilter (const TransformCallback &transform_callback=TransformCallback(), const typename SensorType::Parameters &sensor_parameters=typename SensorType::Parameters())
 Constructor. More...
 
 MOVEIT_DECLARE_PTR_MEMBER (MeshFilter)
 
SensorType::Parameters & parameters ()
 returns the Sensor Parameters More...
 
const SensorType::Parameters & parameters () const
 returns the Sensor Parameters More...
 
- Public Member Functions inherited from mesh_filter::MeshFilterBase
MeshHandle addMesh (const shapes::Mesh &mesh)
 adds a mesh to the filter object. More...
 
void filter (const void *sensor_data, GLushort type, bool wait=false) const
 label/remove pixels from input depth-image More...
 
void getFilteredDepth (float *depth) const
 retrieves the filtered depth values More...
 
void getFilteredLabels (LabelType *labels) const
 retrieves the labels of the input data More...
 
void getModelDepth (float *depth) const
 retrieves the depth values of the rendered model More...
 
void getModelLabels (LabelType *labels) const
 retrieves the labels of the rendered model More...
 
 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. More...
 
void removeMesh (MeshHandle mesh_handle)
 removes a mesh given by its handle More...
 
void setPaddingOffset (float offset)
 set the offset component of padding. This value is added to the scaled sensor-specific constant component. More...
 
void setPaddingScale (float scale)
 set the scale component of padding used to multiply with sensor-specific padding coefficients to get final coefficients. More...
 
void 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 More...
 
void setTransformCallback (const TransformCallback &transform_callback)
 set the callback for retrieving transformations for each mesh. More...
 
 ~MeshFilterBase ()
 Desctructor. More...
 

Additional Inherited Members

- Public Types inherited from mesh_filter::MeshFilterBase
enum  {
  Background = 0, Shadow = 1, NearClip = 2, FarClip = 3,
  FirstLabel = 16
}
 
typedef boost::function< bool(MeshHandle, Eigen::Affine3d &)> TransformCallback
 
- Protected Member Functions inherited from mesh_filter::MeshFilterBase
void addJob (const JobPtr &job) const
 add a Job for the main thread that needs to be executed there More...
 
void addMeshHelper (MeshHandle handle, const shapes::Mesh *cmesh)
 used within a Job to allow the main thread adding meshes More...
 
void deInitialize ()
 cleaning up More...
 
void doFilter (const void *sensor_data, const int encoding) const
 the filter method that does the magic More...
 
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...
 
bool removeMeshHelper (MeshHandle handle)
 used within a Job to allow the main thread removing meshes 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 setSize (unsigned int width, unsigned int height)
 sets the size of the fram buffers More...
 
- Protected Attributes inherited from mesh_filter::MeshFilterBase
GLuint canvas_
 canvas element (screen-filling quad) for second pass More...
 
GLRendererPtr depth_filter_
 second pass renderer for filtering the results of first pass More...
 
boost::thread filter_thread_
 the filtering thread that also holds the OpenGL context More...
 
boost::condition_variable jobs_condition_
 condition variable to notify the filtering thread if a new image arrived More...
 
boost::mutex jobs_mutex_
 mutex required for synchronization of condition states More...
 
std::queue< JobPtr > jobs_queue_
 OpenGL job queue that need to be processed by the worker thread. More...
 
GLRendererPtr mesh_renderer_
 first pass renderer for rendering the mesh More...
 
std::map< MeshHandle, GLMeshPtr > meshes_
 storage for meshed to be filtered More...
 
boost::mutex meshes_mutex_
 mutex for synchronization of updating filtered meshes More...
 
MeshHandle min_handle_
 Handle values below this are all taken (this variable is used for more efficient computation of next_label_) More...
 
MeshHandle next_handle_
 next handle to be used for next mesh that is added More...
 
float padding_offset_
 padding offset More...
 
float padding_scale_
 padding scale More...
 
GLuint sensor_depth_texture_
 handle depth texture from sensor data More...
 
SensorModel::ParametersPtr sensor_parameters_
 the parameters of the used sensor model More...
 
float shadow_threshold_
 threshold for shadowed pixels vs. filtered pixels More...
 
GLuint shadow_threshold_location_
 handle to GLSL location of shadow threshold More...
 
bool stop_
 indicates whether the filtering loop should stop More...
 
TransformCallback transform_callback_
 callback function for retrieving the mesh transformations More...
 
boost::mutex transform_callback_mutex_
 mutex for synchronization of setting/calling transform_callback_ More...
 

Detailed Description

template<typename SensorType>
class mesh_filter::MeshFilter< SensorType >

MeshFilter filters out points that belong to given meshes in depth-images.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)

Definition at line 63 of file mesh_filter.h.

Constructor & Destructor Documentation

template<typename SensorType>
mesh_filter::MeshFilter< SensorType >::MeshFilter ( const TransformCallback transform_callback = TransformCallback(),
const typename SensorType::Parameters &  sensor_parameters = typename SensorType::Parameters() 
)

Constructor.

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Parameters
[in]transform_callbackCallback function that is called for each mesh to obtain the current transformation.
Note
the callback expects the mesh handle but no time stamp. Its the users responsibility to return the correct transformation.

Definition at line 94 of file mesh_filter.h.

Member Function Documentation

template<typename SensorType>
mesh_filter::MeshFilter< SensorType >::MOVEIT_DECLARE_PTR_MEMBER ( MeshFilter< SensorType >  )
template<typename SensorType >
SensorType::Parameters & mesh_filter::MeshFilter< SensorType >::parameters ( )

returns the Sensor Parameters

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Returns
reference of the parameters object of the used Sensor

Definition at line 103 of file mesh_filter.h.

template<typename SensorType >
const SensorType::Parameters & mesh_filter::MeshFilter< SensorType >::parameters ( ) const

returns the Sensor Parameters

Author
Suat Gedikli (gedik.nosp@m.li@w.nosp@m.illow.nosp@m.gara.nosp@m.ge.co.nosp@m.m)
Returns
const reference of the parameters object of the used Sensor

Definition at line 109 of file mesh_filter.h.


The documentation for this class was generated from the following files:


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sun Oct 18 2020 13:17:23