Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/uniform_sampling.h"
00038 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
00039 #include <pcl/keypoints/uniform_sampling.h>
00040 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
00041 #include <pcl/filters/uniform_sampling.h>
00042 #endif
00043 
00044 
00045 namespace jsk_pcl_ros
00046 {
00047   void UniformSampling::onInit()
00048   {
00049     DiagnosticNodelet::onInit();
00050     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00051     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00052       boost::bind (&UniformSampling::configCallback, this, _1, _2);
00053     srv_->setCallback (f);
00054 
00055     pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
00056 
00057     onInitPostProcess();
00058   }
00059 
00060   void UniformSampling::subscribe()
00061   {
00062     sub_ = pnh_->subscribe("input", 1, &UniformSampling::sampling, this);
00063   }
00064 
00065   void UniformSampling::unsubscribe()
00066   {
00067     sub_.shutdown();
00068   }
00069 
00070   void UniformSampling::configCallback(Config& config, uint32_t level)
00071   {
00072     boost::mutex::scoped_lock lock(mutex_);
00073     search_radius_ = config.search_radius;
00074   }
00075 
00076   void UniformSampling::sampling(
00077     const sensor_msgs::PointCloud2::ConstPtr& msg)
00078   {
00079     boost::mutex::scoped_lock lock(mutex_);
00080     pcl::PointCloud<pcl::PointXYZ>::Ptr
00081       cloud (new pcl::PointCloud<pcl::PointXYZ>);
00082     pcl::fromROSMsg(*msg, *cloud);
00083     pcl::UniformSampling<pcl::PointXYZ> uniform_sampling;
00084     uniform_sampling.setInputCloud(cloud);
00085     uniform_sampling.setRadiusSearch(search_radius_);
00086 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
00087     pcl::PointCloud<int> indices;
00088     uniform_sampling.compute(indices);
00089 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
00090     pcl::PointCloud<pcl::PointXYZ> output;
00091     uniform_sampling.filter(output);
00092     pcl::PointIndicesPtr indices_ptr;
00093     std::vector<int> &indices = *uniform_sampling.getIndices();
00094 #endif
00095     PCLIndicesMsg ros_indices;
00096 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
00097     for (size_t i = 0; i < indices.points.size(); i++) {
00098       ros_indices.indices.push_back(indices.points[i]);
00099     }
00100 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
00101     for (size_t i = 0; i < indices.size(); i++) {
00102       ros_indices.indices.push_back(indices[i]);
00103     }
00104 #endif
00105     ros_indices.header = msg->header;
00106     pub_.publish(ros_indices);
00107   }
00108 }
00109 
00110 #include <pluginlib/class_list_macros.h>
00111 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::UniformSampling, nodelet::Nodelet);