statistical_outlier_removal.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, 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, Inc. 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  * $Id: statistical_outlier_removal.h 35876 2011-02-09 01:04:36Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_FILTERS_STATISTICALOUTLIERREMOVAL_H_
39 #define PCL_ROS_FILTERS_STATISTICALOUTLIERREMOVAL_H_
40 
41 // PCL includes
42 #include <pcl/filters/statistical_outlier_removal.h>
43 #include "pcl_ros/filters/filter.h"
44 
45 // Dynamic reconfigure
46 #include "pcl_ros/StatisticalOutlierRemovalConfig.h"
47 
48 namespace pcl_ros
49 {
62  {
63  protected:
66 
72  inline void
73  filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices,
74  PointCloud2 &output)
75  {
76  boost::mutex::scoped_lock lock (mutex_);
77  pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
78  pcl_conversions::toPCL(*(input), *(pcl_input));
79  impl_.setInputCloud (pcl_input);
80  impl_.setIndices (indices);
81  pcl::PCLPointCloud2 pcl_output;
82  impl_.filter (pcl_output);
83  pcl_conversions::moveFromPCL(pcl_output, output);
84  }
85 
90  bool child_init (ros::NodeHandle &nh, bool &has_service);
91 
96  void config_callback (pcl_ros::StatisticalOutlierRemovalConfig &config, uint32_t level);
97 
98  private:
100  pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2> impl_;
101  public:
102  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
103  };
104 }
105 
106 #endif //#ifndef PCL_FILTERS_STATISTICALOUTLIERREMOVAL_H_
filter.h
pcl_ros::Filter::mutex_
boost::mutex mutex_
Internal mutex.
Definition: filter.h:94
boost::shared_ptr
pcl_ros
Definition: boundary.h:46
pcl_ros::Filter::IndicesPtr
pcl::IndicesPtr IndicesPtr
Definition: filter.h:61
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
pcl_ros::StatisticalOutlierRemoval
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data....
Definition: statistical_outlier_removal.h:61
pcl_ros::Filter
Filter represents the base filter class. Some generic 3D operations that are applicable to all filter...
Definition: filter.h:56
pcl_ros::StatisticalOutlierRemoval::filter
void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
Definition: statistical_outlier_removal.h:73
pcl_ros::StatisticalOutlierRemoval::child_init
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Definition: statistical_outlier_removal.cpp:43
pcl_ros::StatisticalOutlierRemoval::srv_
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::StatisticalOutlierRemovalConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: statistical_outlier_removal.h:65
pcl_ros::StatisticalOutlierRemoval::config_callback
void config_callback(pcl_ros::StatisticalOutlierRemovalConfig &config, uint32_t level)
Dynamic reconfigure callback.
Definition: statistical_outlier_removal.cpp:56
pcl_ros::Filter::PointCloud2
sensor_msgs::PointCloud2 PointCloud2
Definition: filter.h:59
pcl_ros::StatisticalOutlierRemoval::impl_
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
Definition: statistical_outlier_removal.h:100
pcl_conversions::moveFromPCL
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
ros::NodeHandle


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40