00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: radius_outlier_removal.cpp 34685 2010-12-12 04:25:36Z rusu $ 00035 * 00036 */ 00037 00038 #include "pcl/impl/instantiate.hpp" 00039 #include "pcl/point_types.h" 00040 #include "pcl/filters/radius_outlier_removal.h" 00041 #include "pcl/filters/impl/radius_outlier_removal.hpp" 00042 #include "pcl/ros/conversions.h" 00043 00045 void 00046 pcl::RadiusOutlierRemoval<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output) 00047 { 00048 output.is_dense = true; 00049 // If fields x/y/z are not present, we cannot filter 00050 if (x_idx_ == -1 || y_idx_ == -1 || z_idx_ == -1) 00051 { 00052 ROS_ERROR ("[pcl::%s::applyFilter] Input dataset doesn't have x-y-z coordinates!", getClassName ().c_str ()); 00053 output.width = output.height = 0; 00054 output.data.clear (); 00055 return; 00056 } 00057 00058 if (search_radius_ == 0.0) 00059 { 00060 ROS_ERROR ("[pcl::%s::applyFilter] No radius defined!", getClassName ().c_str ()); 00061 output.width = output.height = 0; 00062 output.data.clear (); 00063 return; 00064 } 00065 // Initialize the spatial locator 00066 //initTree (spatial_locator_type_, tree_, k_); 00067 00068 // TODO: fix this 00069 tree_ = boost::make_shared<KdTreeFLANN<pcl::PointXYZ> >(); 00070 00071 // Send the input dataset to the spatial locator 00072 pcl::PointCloud<pcl::PointXYZ> cloud; 00073 pcl::fromROSMsg (*input_, cloud); 00074 tree_->setInputCloud (cloud.makeShared ()); 00075 00076 // Allocate enough space to hold the results 00077 std::vector<int> nn_indices (indices_->size ()); 00078 std::vector<float> nn_dists (indices_->size ()); 00079 00080 // Copy the common fields 00081 output.is_bigendian = input_->is_bigendian; 00082 output.point_step = input_->point_step; 00083 output.height = 1; 00084 00085 output.data.resize (input_->width * input_->point_step); // reserve enough space 00086 00087 int nr_p = 0; 00088 // Go over all the points and check which doesn't have enough neighbors 00089 for (size_t cp = 0; cp < indices_->size (); ++cp) 00090 { 00091 int k = tree_->radiusSearch ((*indices_)[cp], search_radius_, nn_indices, nn_dists); 00092 // Check if the number of neighbors is larger than the user imposed limit 00093 if (k < min_pts_radius_) 00094 continue; 00095 00096 memcpy (&output.data[nr_p * output.point_step], &input_->data[(*indices_)[cp] * output.point_step], output.point_step); 00097 nr_p++; 00098 } 00099 output.width = nr_p; 00100 output.height = 1; 00101 output.data.resize (output.width * output.point_step); 00102 output.row_step = output.point_step * output.width; 00103 } 00104 00105 // Instantiations of specific point types 00106 PCL_INSTANTIATE(RadiusOutlierRemoval, PCL_XYZ_POINT_TYPES); 00107