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>
Public Member Functions | |
virtual void | onInit () |
Nodelet init callback. More... | |
Private Member Functions | |
void | addMeshes (mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > &mesh_filter) |
adding the meshes to a given mesh filter object. More... | |
void | connectCb () |
Callback for connection/deconnection of listener. More... | |
void | depthCb (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
Callback for subscribed depth images. More... | |
void | filter (const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg) |
main filtering routine More... | |
~DepthSelfFiltering () | |
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where a transformation can be provided for.
Definition at line 57 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 52 of file depth_self_filter_nodelet.cpp.
|
private |
adding the meshes to a given mesh filter object.
[in,out] | mesh_filter | mesh filter object that gets meshes from the robot description added to |
Definition at line 176 of file depth_self_filter_nodelet.cpp.
|
private |
Callback for connection/deconnection of listener.
Definition at line 194 of file depth_self_filter_nodelet.cpp.
|
private |
Callback for subscribed depth images.
depth_msg | depth image |
info_msg | camera information containing parameters frame, etc. |
Definition at line 210 of file depth_self_filter_nodelet.cpp.
|
private |
main filtering routine
Definition at line 108 of file depth_self_filter_nodelet.cpp.
|
virtual |
Nodelet init callback.
Definition at line 56 of file depth_self_filter_nodelet.cpp.
|
private |
required to avoid listener registration before we are all set
Definition at line 107 of file depth_self_filter_nodelet.h.
|
private |
distance of far clipping plane
Definition at line 119 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 111 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 97 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 112 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 96 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 95 of file depth_self_filter_nodelet.h.
|
private |
mesh filter object
Definition at line 131 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 113 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 98 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 114 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 99 of file depth_self_filter_nodelet.h.
|
private |
distance of near clipping plane
Definition at line 116 of file depth_self_filter_nodelet.h.
|
private |
the coefficient for the linear component of the padding function
Definition at line 128 of file depth_self_filter_nodelet.h.
|
private |
the coefficient for the square component of padding function in 1/m
Definition at line 125 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 101 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 102 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 103 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 104 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 108 of file depth_self_filter_nodelet.h.
|
private |
threshold that indicates a pixel to be in shadow, rather than being filtered out
Definition at line 122 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 100 of file depth_self_filter_nodelet.h.
|
private |
Definition at line 109 of file depth_self_filter_nodelet.h.