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 #include <pcl/keypoints/uniform_sampling.h>
00039
00040
00041 namespace jsk_pcl_ros
00042 {
00043 void UniformSampling::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00047 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00048 boost::bind (&UniformSampling::configCallback, this, _1, _2);
00049 srv_->setCallback (f);
00050
00051 pub_ = advertise<PCLIndicesMsg>(*pnh_, "output", 1);
00052 }
00053
00054 void UniformSampling::subscribe()
00055 {
00056 sub_ = pnh_->subscribe("input", 1, &UniformSampling::sampling, this);
00057 }
00058
00059 void UniformSampling::unsubscribe()
00060 {
00061 sub_.shutdown();
00062 }
00063
00064 void UniformSampling::configCallback(Config& config, uint32_t level)
00065 {
00066 boost::mutex::scoped_lock lock(mutex_);
00067 search_radius_ = config.search_radius;
00068 }
00069
00070 void UniformSampling::sampling(
00071 const sensor_msgs::PointCloud2::ConstPtr& msg)
00072 {
00073 boost::mutex::scoped_lock lock(mutex_);
00074 pcl::PointCloud<pcl::PointXYZ>::Ptr
00075 cloud (new pcl::PointCloud<pcl::PointXYZ>);
00076 pcl::PointCloud<int> indices;
00077 pcl::fromROSMsg(*msg, *cloud);
00078 pcl::UniformSampling<pcl::PointXYZ> uniform_sampling;
00079 uniform_sampling.setInputCloud(cloud);
00080 uniform_sampling.setRadiusSearch(search_radius_);
00081 uniform_sampling.compute(indices);
00082 PCLIndicesMsg ros_indices;
00083 for (size_t i = 0; i < indices.points.size(); i++) {
00084 ros_indices.indices.push_back(indices.points[i]);
00085 }
00086 ros_indices.header = msg->header;
00087 pub_.publish(ros_indices);
00088 }
00089 }
00090
00091 #include <pluginlib/class_list_macros.h>
00092 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::UniformSampling, nodelet::Nodelet);