37 #ifndef MOVEIT_DEPTH_SELF_FILTER_NODELET_ 38 #define MOVEIT_DEPTH_SELF_FILTER_NODELET_ 40 #include <nodelet/nodelet.h> 42 #include <boost/thread.hpp> 43 #include <boost/thread/condition_variable.hpp> 77 void filter(
const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg);
91 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg);
std::shared_ptr< image_transport::ImageTransport > model_depth_transport_
image_transport::CameraPublisher pub_filtered_depth_image_
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where...
image_transport::CameraPublisher pub_model_depth_image_
image_transport::CameraPublisher pub_model_label_image_
cv_bridge::CvImagePtr model_label_ptr_
double padding_scale_
the coefficient for the square component of padding function in 1/m
void filter(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
main filtering routine
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Callback for subscribed depth images.
std::shared_ptr< image_transport::ImageTransport > filtered_depth_transport_
std::shared_ptr< image_transport::ImageTransport > filtered_label_transport_
cv_bridge::CvImagePtr filtered_depth_ptr_
cv_bridge::CvImagePtr model_depth_ptr_
double shadow_threshold_
threshold that indicates a pixel to be in shadow, rather than being filtered out
image_transport::CameraSubscriber sub_depth_image_
double padding_offset_
the coefficient for the linear component of the padding function
std::shared_ptr< image_transport::ImageTransport > model_label_transport_
MeshFilter< StereoCameraModel >::Ptr mesh_filter_
std::shared_ptr< image_transport::ImageTransport > input_depth_transport_
cv_bridge::CvImagePtr filtered_label_ptr_
double far_clipping_plane_distance_
distance of far clipping plane
virtual void onInit()
Nodelet init callback.
TransformProvider transform_provider_
double near_clipping_plane_distance_
distance of near clipping plane
image_transport::CameraPublisher pub_filtered_label_image_
void connectCb()
Callback for connection/deconnection of listener.
boost::mutex connect_mutex_
required to avoid listener registration before we are all set
void addMeshes(mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > &mesh_filter)
adding the meshes to a given mesh filter object.