39 #include <nodelet/nodelet.h>
40 #include <image_transport/image_transport.h>
44 #include <cv_bridge/cv_bridge.h>
74 void filter(
const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg);
88 void depthCb(
const sensor_msgs::ImageConstPtr& depth_msg,
const sensor_msgs::CameraInfoConstPtr& info_msg);
92 std::shared_ptr<image_transport::ImageTransport> input_depth_transport_;
93 std::shared_ptr<image_transport::ImageTransport> filtered_label_transport_;
94 std::shared_ptr<image_transport::ImageTransport> filtered_depth_transport_;
95 std::shared_ptr<image_transport::ImageTransport> model_depth_transport_;
96 std::shared_ptr<image_transport::ImageTransport> model_label_transport_;
97 image_transport::CameraSubscriber sub_depth_image_;
98 image_transport::CameraPublisher pub_filtered_depth_image_;
99 image_transport::CameraPublisher pub_filtered_label_image_;
100 image_transport::CameraPublisher pub_model_depth_image_;
101 image_transport::CameraPublisher pub_model_label_image_;
104 std::mutex connect_mutex_;
108 std::shared_ptr<cv_bridge::CvImage> filtered_depth_ptr_;
109 std::shared_ptr<cv_bridge::CvImage> filtered_label_ptr_;
110 std::shared_ptr<cv_bridge::CvImage> model_depth_ptr_;
111 std::shared_ptr<cv_bridge::CvImage> model_label_ptr_;
113 double near_clipping_plane_distance_;
116 double far_clipping_plane_distance_;
119 double shadow_threshold_;
122 double padding_scale_;
125 double padding_offset_;
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where...
void onInit() override
Nodelet init callback.