Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
mesh_filter::MeshFilterBase Class Reference

#include <mesh_filter_base.h>

Inheritance diagram for mesh_filter::MeshFilterBase:
Inheritance graph
[legend]

List of all members.

Public Types

enum  {
  Background = 0, Shadow = 1, NearClip = 2, FarClip = 3,
  FirstLabel = 16
}
typedef boost::function< bool(MeshHandle,
Eigen::Affine3d &)> 
TransformCallback

Public Member Functions

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

Protected Member Functions

void addJob (const JobPtr &job) const
 add a Job for the main thread that needs to be executed there
void addMeshHelper (MeshHandle handle, const shapes::Mesh *cmesh)
 used within a Job to allow the main thread adding meshes
void deInitialize ()
 cleaning up
void doFilter (const void *sensor_data, const int encoding) const
 the filter method that does the magic
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
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 setSize (unsigned int width, unsigned int height)
 sets the size of the fram buffers

Protected Attributes

GLuint canvas_
 canvas element (screen-filling quad) for second pass
GLRendererPtr depth_filter_
 second pass renderer for filtering the results of first pass
boost::thread filter_thread_
 the filtering thread that also holds the OpenGL context
boost::condition_variable jobs_condition_
 condition variable to notify the filtering thread if a new image arrived
boost::mutex jobs_mutex_
 mutex required for synchronization of condition states
std::queue< JobPtr > jobs_queue_
 OpenGL job queue that need to be processed by the worker thread.
GLRendererPtr mesh_renderer_
 first pass renderer for rendering the mesh
std::map< MeshHandle, GLMeshPtr > meshes_
 storage for meshed to be filtered
boost::mutex meshes_mutex_
 mutex for synchronization of updating filtered meshes
MeshHandle min_handle_
 Handle values below this are all taken (this variable is used for more efficient computation of next_label_)
MeshHandle next_handle_
 next handle to be used for next mesh that is added
float padding_offset_
 padding offset
float padding_scale_
 padding scale
GLuint sensor_depth_texture_
 handle depth texture from sensor data
SensorModel::ParametersPtr sensor_parameters_
 the parameters of the used sensor model
float shadow_threshold_
 threshold for shadowed pixels vs. filtered pixels
GLuint shadow_threshold_location_
 handle to GLSL location of shadow threshold
bool stop_
 indicates whether the filtering loop should stop
TransformCallback transform_callback_
 callback function for retrieving the mesh transformations
boost::mutex transform_callback_mutex_
 mutex for synchronization of setting/calling transform_callback_

Detailed Description

Definition at line 63 of file mesh_filter_base.h.


Member Typedef Documentation

typedef boost::function<bool(MeshHandle, Eigen::Affine3d&)> mesh_filter::MeshFilterBase::TransformCallback

Definition at line 67 of file mesh_filter_base.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
Background 
Shadow 
NearClip 
FarClip 
FirstLabel 

Definition at line 71 of file mesh_filter_base.h.


Constructor & Destructor Documentation

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 = "" 
)

Constructor.

Author:
Suat Gedikli (gedikli@willowgarage.com)
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 55 of file mesh_filter_base.cpp.

Desctructor.

Definition at line 122 of file mesh_filter_base.cpp.


Member Function Documentation

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]jobthe job object that has the function o be executed

Definition at line 137 of file mesh_filter_base.cpp.

adds a mesh to the filter object.

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[in]meshthe mesh to be added
Returns:
handle to the mesh. This handle is used in the transform callback function to identify the mesh and retrieve the correct transformation.

Definition at line 171 of file mesh_filter_base.cpp.

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]handlethe handle of the mesh that is predetermined and passed
[in]cmeshthe mesh to be added to the corresponding handle

Definition at line 190 of file mesh_filter_base.cpp.

cleaning up

Definition at line 146 of file mesh_filter_base.cpp.

void mesh_filter::MeshFilterBase::doFilter ( const void *  sensor_data,
const int  encoding 
) const [protected]

the filter method that does the magic

Parameters:
[in]sensor_datapointer to the buffer containing the depth readings
[in]encodingthe representation of the depth readings in the buffer

Definition at line 306 of file mesh_filter_base.cpp.

void mesh_filter::MeshFilterBase::filter ( const void *  sensor_data,
GLushort  type,
bool  wait = false 
) const

label/remove pixels from input depth-image

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[in]sensor_datapointer to the input depth image from sensor readings.
Todo:
what is type?

Definition at line 291 of file mesh_filter_base.cpp.

void mesh_filter::MeshFilterBase::getFilteredDepth ( float *  depth) const

retrieves the filtered depth values

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[out]depthpointer to buffer to be filled with depth values.

Definition at line 242 of file mesh_filter_base.cpp.

retrieves the labels of the input data

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[out]labelspointer 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 257 of file mesh_filter_base.cpp.

void mesh_filter::MeshFilterBase::getModelDepth ( float *  depth) const

retrieves the depth values of the rendered model

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[out]depthpointer to buffer to be filled with depth values.

Definition at line 227 of file mesh_filter_base.cpp.

retrieves the labels of the rendered model

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[out]labelspointer 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 219 of file mesh_filter_base.cpp.

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]

initializes OpenGL related things as well as renderers

Definition at line 74 of file mesh_filter_base.cpp.

removes a mesh given by its handle

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[in]mesh_handlethe handle of the mesh to be removed.

Definition at line 195 of file mesh_filter_base.cpp.

used within a Job to allow the main thread removing meshes

Parameters:
[in]handlethe handle of the mesh to be removed

Definition at line 208 of file mesh_filter_base.cpp.

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]

filtering thread

Definition at line 265 of file mesh_filter_base.cpp.

set the offset component of padding. This value is added to the scaled sensor-specific constant component.

Parameters:
[in]offsetthe offset value

Definition at line 388 of file mesh_filter_base.cpp.

set the scale component of padding used to multiply with sensor-specific padding coefficients to get final coefficients.

Parameters:
[in]scalethe scale value

Definition at line 393 of file mesh_filter_base.cpp.

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 (gedikli@willowgarage.com)
Parameters:
[in]thresholdshadow threshold in meters

Definition at line 214 of file mesh_filter_base.cpp.

void mesh_filter::MeshFilterBase::setSize ( unsigned int  width,
unsigned int  height 
) [protected]

sets the size of the fram buffers

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[in]widthwidth of frame buffers in pixels
[in]heightheight of frame buffers in pixels

Definition at line 156 of file mesh_filter_base.cpp.

set the callback for retrieving transformations for each mesh.

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
[in]transform_callbackthe callback

Definition at line 165 of file mesh_filter_base.cpp.


Member Data Documentation

canvas element (screen-filling quad) for second pass

Definition at line 276 of file mesh_filter_base.h.

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.

the filtering thread that also holds the OpenGL context

Definition at line 249 of file mesh_filter_base.h.

boost::condition_variable mesh_filter::MeshFilterBase::jobs_condition_ [mutable, protected]

condition variable to notify the filtering thread if a new image arrived

Definition at line 252 of file mesh_filter_base.h.

boost::mutex mesh_filter::MeshFilterBase::jobs_mutex_ [mutable, protected]

mutex required for synchronization of condition states

Definition at line 255 of file mesh_filter_base.h.

std::queue<JobPtr> mesh_filter::MeshFilterBase::jobs_queue_ [mutable, protected]

OpenGL job queue that need to be processed by the worker thread.

Definition at line 258 of file mesh_filter_base.h.

first pass renderer for rendering the mesh

Definition at line 270 of file mesh_filter_base.h.

std::map<MeshHandle, GLMeshPtr> mesh_filter::MeshFilterBase::meshes_ [protected]

storage for meshed to be filtered

Definition at line 236 of file mesh_filter_base.h.

boost::mutex mesh_filter::MeshFilterBase::meshes_mutex_ [mutable, protected]

mutex for synchronization of updating filtered meshes

Definition at line 261 of file mesh_filter_base.h.

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 to be used for next mesh that is added

Definition at line 242 of file mesh_filter_base.h.

padding offset

Definition at line 291 of file mesh_filter_base.h.

padding scale

Definition at line 288 of file mesh_filter_base.h.

handle depth texture from sensor data

Definition at line 279 of file mesh_filter_base.h.

SensorModel::ParametersPtr mesh_filter::MeshFilterBase::sensor_parameters_ [protected]

the parameters of the used sensor model

Definition at line 239 of file mesh_filter_base.h.

threshold for shadowed pixels vs. filtered pixels

Definition at line 294 of file mesh_filter_base.h.

handle to GLSL location of shadow threshold

Definition at line 282 of file mesh_filter_base.h.

indicates whether the filtering loop should stop

Definition at line 267 of file mesh_filter_base.h.

callback function for retrieving the mesh transformations

Definition at line 285 of file mesh_filter_base.h.

boost::mutex mesh_filter::MeshFilterBase::transform_callback_mutex_ [mutable, protected]

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:


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Wed Jun 19 2019 19:24:12