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 #pragma once
38 
39 #include <nodelet/nodelet.h>
44 #include <cv_bridge/cv_bridge.h>
45 #include <memory>
46 
47 namespace mesh_filter
48 {
55 {
56 public:
58  void onInit() override;
59 
60 private:
61  ~DepthSelfFiltering() override;
62 
69 
74  void filter(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::CameraInfoConstPtr& info_msg);
75 
80  void connectCb();
81 
88  void depthCb(const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::CameraInfoConstPtr& info_msg);
89 
90 private:
91  // member variables to handle ros messages
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_;
102 
104  std::mutex connect_mutex_;
105  int queue_size_;
107 
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_;
114 
117 
119  double shadow_threshold_;
120 
122  double padding_scale_;
123 
125  double padding_offset_;
126 
129 };
130 
131 } // namespace mesh_filter
mesh_filter::DepthSelfFiltering::model_depth_transport_
std::shared_ptr< image_transport::ImageTransport > model_depth_transport_
Definition: depth_self_filter_nodelet.h:159
mesh_filter::DepthSelfFiltering::filter
void filter(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
main filtering routine
Definition: depth_self_filter_nodelet.cpp:108
mesh_filter::DepthSelfFiltering::padding_scale_
double padding_scale_
the coefficient for the square component of padding function in 1/m
Definition: depth_self_filter_nodelet.h:186
mesh_filter::DepthSelfFiltering::pub_filtered_label_image_
image_transport::CameraPublisher pub_filtered_label_image_
Definition: depth_self_filter_nodelet.h:163
mesh_filter::DepthSelfFiltering::sub_depth_image_
image_transport::CameraSubscriber sub_depth_image_
Definition: depth_self_filter_nodelet.h:161
mesh_filter::DepthSelfFiltering::addMeshes
void addMeshes(mesh_filter::MeshFilter< mesh_filter::StereoCameraModel > &mesh_filter)
adding the meshes to a given mesh filter object.
Definition: depth_self_filter_nodelet.cpp:182
mesh_filter::DepthSelfFiltering::connectCb
void connectCb()
Callback for connection/deconnection of listener.
Definition: depth_self_filter_nodelet.cpp:203
mesh_filter::DepthSelfFiltering::pub_filtered_depth_image_
image_transport::CameraPublisher pub_filtered_depth_image_
Definition: depth_self_filter_nodelet.h:162
mesh_filter::DepthSelfFiltering
Nodelet for filtering meshes from depth images. e.g. meshes of the robot or any attached object where...
Definition: depth_self_filter_nodelet.h:86
stereo_camera_model.h
mesh_filter.h
mesh_filter::DepthSelfFiltering::far_clipping_plane_distance_
double far_clipping_plane_distance_
distance of far clipping plane
Definition: depth_self_filter_nodelet.h:180
mesh_filter::DepthSelfFiltering::pub_model_label_image_
image_transport::CameraPublisher pub_model_label_image_
Definition: depth_self_filter_nodelet.h:165
mesh_filter::DepthSelfFiltering::queue_size_
int queue_size_
Definition: depth_self_filter_nodelet.h:169
image_transport::CameraSubscriber
mesh_filter::DepthSelfFiltering::model_label_ptr_
std::shared_ptr< cv_bridge::CvImage > model_label_ptr_
Definition: depth_self_filter_nodelet.h:175
mesh_filter::DepthSelfFiltering::onInit
void onInit() override
Nodelet init callback.
Definition: depth_self_filter_nodelet.cpp:54
mesh_filter::DepthSelfFiltering::filtered_depth_ptr_
std::shared_ptr< cv_bridge::CvImage > filtered_depth_ptr_
Definition: depth_self_filter_nodelet.h:172
image_transport::CameraPublisher
mesh_filter::DepthSelfFiltering::model_label_transport_
std::shared_ptr< image_transport::ImageTransport > model_label_transport_
Definition: depth_self_filter_nodelet.h:160
mesh_filter::DepthSelfFiltering::input_depth_transport_
std::shared_ptr< image_transport::ImageTransport > input_depth_transport_
Definition: depth_self_filter_nodelet.h:156
mesh_filter::DepthSelfFiltering::padding_offset_
double padding_offset_
the coefficient for the linear component of the padding function
Definition: depth_self_filter_nodelet.h:189
image_transport.h
mesh_filter::DepthSelfFiltering::transform_provider_
TransformProvider transform_provider_
Definition: depth_self_filter_nodelet.h:170
transform_provider.h
mesh_filter::DepthSelfFiltering::pub_model_depth_image_
image_transport::CameraPublisher pub_model_depth_image_
Definition: depth_self_filter_nodelet.h:164
mesh_filter::DepthSelfFiltering::model_depth_ptr_
std::shared_ptr< cv_bridge::CvImage > model_depth_ptr_
Definition: depth_self_filter_nodelet.h:174
mesh_filter::DepthSelfFiltering::near_clipping_plane_distance_
double near_clipping_plane_distance_
distance of near clipping plane
Definition: depth_self_filter_nodelet.h:177
nodelet::Nodelet
nodelet.h
cv_bridge.h
mesh_filter::DepthSelfFiltering::connect_mutex_
std::mutex connect_mutex_
required to avoid listener registration before we are all set
Definition: depth_self_filter_nodelet.h:168
TransformProvider
Class that caches and updates transformations for given frames.
Definition: transform_provider.h:55
mesh_filter::DepthSelfFiltering::mesh_filter_
MeshFilter< StereoCameraModel >::Ptr mesh_filter_
Definition: depth_self_filter_nodelet.h:192
mesh_filter::MeshFilter< mesh_filter::StereoCameraModel >
mesh_filter::DepthSelfFiltering::filtered_depth_transport_
std::shared_ptr< image_transport::ImageTransport > filtered_depth_transport_
Definition: depth_self_filter_nodelet.h:158
mesh_filter::DepthSelfFiltering::depthCb
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Callback for subscribed depth images.
Definition: depth_self_filter_nodelet.cpp:219
mesh_filter::DepthSelfFiltering::filtered_label_ptr_
std::shared_ptr< cv_bridge::CvImage > filtered_label_ptr_
Definition: depth_self_filter_nodelet.h:173
mesh_filter::DepthSelfFiltering::~DepthSelfFiltering
~DepthSelfFiltering() override
Definition: depth_self_filter_nodelet.cpp:50
mesh_filter::DepthSelfFiltering::shadow_threshold_
double shadow_threshold_
threshold that indicates a pixel to be in shadow, rather than being filtered out
Definition: depth_self_filter_nodelet.h:183
mesh_filter::DepthSelfFiltering::filtered_label_transport_
std::shared_ptr< image_transport::ImageTransport > filtered_label_transport_
Definition: depth_self_filter_nodelet.h:157
mesh_filter
Definition: depth_self_filter_nodelet.h:47


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Fri Jun 21 2024 02:26:30