Public Member Functions | Private Member Functions | Private Attributes
mesh_filter::DepthSelfFiltering Class Reference

Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where a transformation can be provided for. More...

#include <depth_self_filter_nodelet.h>

List of all members.

Public Member Functions

virtual void onInit ()
 Nodelet init callback.

Private Member Functions

void addMeshes (mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > &mesh_filter)
 adding the meshes to a given mesh filter object.
void connectCb ()
 Callback for connection/deconnection of listener.
void depthCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 Callback for subscribed depth images.
void filter (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
 main filtering routine
 ~DepthSelfFiltering ()

Private Attributes

boost::mutex connect_mutex_
 required to avoid listener registration before we are all set
double far_clipping_plane_distance_
 distance of far clipping plane
cv_bridge::CvImagePtr filtered_depth_ptr_
boost::shared_ptr
< image_transport::ImageTransport
filtered_depth_transport_
cv_bridge::CvImagePtr filtered_label_ptr_
boost::shared_ptr
< image_transport::ImageTransport
filtered_label_transport_
boost::shared_ptr
< image_transport::ImageTransport
input_depth_transport_
boost::shared_ptr< MeshFilter
< StereoCameraModel > > 
mesh_filter_
cv_bridge::CvImagePtr model_depth_ptr_
boost::shared_ptr
< image_transport::ImageTransport
model_depth_transport_
cv_bridge::CvImagePtr model_label_ptr_
boost::shared_ptr
< image_transport::ImageTransport
model_label_transport_
double near_clipping_plane_distance_
 distance of near clipping plane
double padding_offset_
 the coefficient for the linear component of the padding function
double padding_scale_
 the coefficient for the square component of padding function in 1/m
image_transport::CameraPublisher pub_filtered_depth_image_
image_transport::CameraPublisher pub_filtered_label_image_
image_transport::CameraPublisher pub_model_depth_image_
image_transport::CameraPublisher pub_model_label_image_
int queue_size_
double shadow_threshold_
 threshold that indicates a pixel to be in shadow, rather than being filtered out
image_transport::CameraSubscriber sub_depth_image_
TransformProvider transform_provider_

Detailed Description

Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where a transformation can be provided for.

Author:
Suat Gedikli (gedikli@willowgarage.com)

Definition at line 58 of file depth_self_filter_nodelet.h.


Constructor & Destructor Documentation

Definition at line 53 of file depth_self_filter_nodelet.cpp.


Member Function Documentation

adding the meshes to a given mesh filter object.

Parameters:
[in,out]mesh_filtermesh filter object that gets meshes from the robot description added to
Author:
Suat Gedikli (gedikli@willowgarage.com)

Definition at line 172 of file depth_self_filter_nodelet.cpp.

Callback for connection/deconnection of listener.

Author:
Suat Gedikli (gedikli@willowgarage.com)

Definition at line 190 of file depth_self_filter_nodelet.cpp.

void mesh_filter::DepthSelfFiltering::depthCb ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
) [private]

Callback for subscribed depth images.

Author:
Suat Gedikli (gedikli@willowgarage.com)
Parameters:
depth_msgdepth image
info_msgcamera information containing parameters frame, etc.

Definition at line 207 of file depth_self_filter_nodelet.cpp.

void mesh_filter::DepthSelfFiltering::filter ( const sensor_msgs::ImageConstPtr &  depth_msg,
const sensor_msgs::CameraInfoConstPtr &  info_msg 
) [private]

main filtering routine

Author:
Suat Gedikli (gedikli@willowgarage.com)

Definition at line 104 of file depth_self_filter_nodelet.cpp.

Nodelet init callback.

Definition at line 57 of file depth_self_filter_nodelet.cpp.


Member Data Documentation

required to avoid listener registration before we are all set

Definition at line 108 of file depth_self_filter_nodelet.h.

distance of far clipping plane

Definition at line 120 of file depth_self_filter_nodelet.h.

Definition at line 112 of file depth_self_filter_nodelet.h.

Definition at line 98 of file depth_self_filter_nodelet.h.

Definition at line 113 of file depth_self_filter_nodelet.h.

Definition at line 97 of file depth_self_filter_nodelet.h.

Definition at line 96 of file depth_self_filter_nodelet.h.

mesh filter object

Definition at line 132 of file depth_self_filter_nodelet.h.

Definition at line 114 of file depth_self_filter_nodelet.h.

Definition at line 99 of file depth_self_filter_nodelet.h.

Definition at line 115 of file depth_self_filter_nodelet.h.

Definition at line 100 of file depth_self_filter_nodelet.h.

distance of near clipping plane

Definition at line 117 of file depth_self_filter_nodelet.h.

the coefficient for the linear component of the padding function

Definition at line 129 of file depth_self_filter_nodelet.h.

the coefficient for the square component of padding function in 1/m

Definition at line 126 of file depth_self_filter_nodelet.h.

Definition at line 102 of file depth_self_filter_nodelet.h.

Definition at line 103 of file depth_self_filter_nodelet.h.

Definition at line 104 of file depth_self_filter_nodelet.h.

Definition at line 105 of file depth_self_filter_nodelet.h.

Definition at line 109 of file depth_self_filter_nodelet.h.

threshold that indicates a pixel to be in shadow, rather than being filtered out

Definition at line 123 of file depth_self_filter_nodelet.h.

Definition at line 101 of file depth_self_filter_nodelet.h.

Definition at line 110 of file depth_self_filter_nodelet.h.


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


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Wed Aug 26 2015 12:43:21