radius_outlier_removal.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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: radius_outlier_removal.cpp 33319 2010-10-15 04:49:28Z rusu $
35  *
36  */
37 
40 
42 bool
44 {
45  // Enable the dynamic reconfigure service
46  has_service = true;
47  srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig> > (nh);
48  dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig>::CallbackType f = boost::bind (&RadiusOutlierRemoval::config_callback, this, _1, _2);
49  srv_->setCallback (f);
50 
51  return (true);
52 }
53 
55 void
56 pcl_ros::RadiusOutlierRemoval::config_callback (pcl_ros::RadiusOutlierRemovalConfig &config, uint32_t level)
57 {
58  boost::mutex::scoped_lock lock (mutex_);
59 
60  if (impl_.getMinNeighborsInRadius () != config.min_neighbors)
61  {
62  impl_.setMinNeighborsInRadius (config.min_neighbors);
63  NODELET_DEBUG ("[%s::config_callback] Setting the number of neighbors in radius: %d.", getName ().c_str (), config.min_neighbors);
64  }
65 
66  if (impl_.getRadiusSearch () != config.radius_search)
67  {
68  impl_.setRadiusSearch (config.radius_search);
69  NODELET_DEBUG ("[%s::config_callback] Setting the radius to search neighbors: %f.", getName ().c_str (), config.radius_search);
70  }
71 
72 }
73 
74 
77 
f
pcl::RadiusOutlierRemoval< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
PLUGINLIB_EXPORT_CLASS(RadiusOutlierRemoval, nodelet::Nodelet)
const std::string & getName() const
virtual bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
pcl_ros::RadiusOutlierRemoval RadiusOutlierRemoval
RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain...
boost::mutex mutex_
Internal mutex.
Definition: filter.h:95
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::RadiusOutlierRemovalConfig > > srv_
Pointer to a dynamic reconfigure service.
#define NODELET_DEBUG(...)
void config_callback(pcl_ros::RadiusOutlierRemovalConfig &config, uint32_t level)
Dynamic reconfigure callback.


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52