41 #include "jsk_recognition_msgs/ClusterPointIndices.h" 49 ConnectionBasedNodelet::onInit();
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 dynamic_reconfigure::Server<Config>::CallbackType
f=
53 srv_->setCallback (f);
54 pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*
pnh_,
"output", 1);
89 pcl::search::Search <pcl::PointXYZRGB>::Ptr tree =
90 pcl::search::Search <pcl::PointXYZRGB>::Ptr (
new pcl::search::KdTree<pcl::PointXYZRGB>);
91 pcl::PointCloud <pcl::PointXYZRGB>::Ptr
cloud (
new pcl::PointCloud <pcl::PointXYZRGB>);
94 std::vector<int> indices;
95 pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
97 pcl::RegionGrowingRGB<pcl::PointXYZRGB>
reg;
98 reg.setInputCloud (cloud);
99 reg.setSearchMethod (tree);
105 std::vector <pcl::PointIndices> clusters;
106 reg.extract (clusters);
108 jsk_recognition_msgs::ClusterPointIndices
output;
109 output.header = msg->header;
111 for (
size_t i = 0; i < clusters.size(); i++) {
113 indices.header = msg->header;
114 indices.indices = clusters[i].indices;
115 output.cluster_indices.push_back(indices);
int region_color_threshold_
void publish(const boost::shared_ptr< M > &message) const
int point_color_threshold_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void unsubscribe()
jsk_pcl_ros::ColorBasedRegionGrowingSegmentationConfig Config
void output(int index, double value)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ColorBasedRegionGrowingSegmentation, nodelet::Nodelet)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual void configCallback(Config &config, uint32_t level)
pcl::PointIndices PCLIndicesMsg