depth_self_filter_nodelet.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Suat Gedikli */
36 
37 #ifndef MOVEIT_DEPTH_SELF_FILTER_NODELET_
38 #define MOVEIT_DEPTH_SELF_FILTER_NODELET_
39 
40 #include <nodelet/nodelet.h>
42 #include <boost/thread.hpp>
43 #include <boost/thread/condition_variable.hpp>
47 #include <cv_bridge/cv_bridge.h>
48 #include <memory>
49 
50 namespace mesh_filter
51 {
57 class DepthSelfFiltering : public nodelet::Nodelet
58 {
59 public:
61  virtual void onInit();
62 
63 private:
65 
72 
77  void filter(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::CameraInfoConstPtr& info_msg);
78 
83  void connectCb();
84 
91  void depthCb(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::CameraInfoConstPtr& info_msg);
92 
93 private:
94  // member variables to handle ros messages
95  std::shared_ptr<image_transport::ImageTransport> input_depth_transport_;
96  std::shared_ptr<image_transport::ImageTransport> filtered_label_transport_;
97  std::shared_ptr<image_transport::ImageTransport> filtered_depth_transport_;
98  std::shared_ptr<image_transport::ImageTransport> model_depth_transport_;
99  std::shared_ptr<image_transport::ImageTransport> model_label_transport_;
105 
107  boost::mutex connect_mutex_;
110 
117 
120 
123 
126 
129 
132 };
133 
134 } // namespace mesh_filter
135 
136 #endif
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_
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_
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_
Class that caches and updates transformations for given frames.
double far_clipping_plane_distance_
distance of far clipping plane
virtual void onInit()
Nodelet init callback.
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.


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sun Oct 18 2020 13:17:23