36 #define BOOST_PARAMETER_MAX_ARITY 7 38 #include <pcl/segmentation/supervoxel_clustering.h> 43 DiagnosticNodelet::onInit();
44 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
45 dynamic_reconfigure::Server<Config>::CallbackType
f =
48 srv_->setCallback (f);
49 pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
50 *
pnh_,
"output/indices", 1);
51 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
52 *
pnh_,
"output/cloud", 1);
67 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
71 if (cloud_msg->data.size() > 0) {
72 pcl::PointCloud<PointT>::Ptr
cloud (
new pcl::PointCloud<PointT>);
77 super.setInputCloud(cloud);
81 std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr > supervoxel_clusters;
82 super.extract(supervoxel_clusters);
83 pcl::PointCloud<PointT>::Ptr
output (
new pcl::PointCloud<PointT>);
84 std::vector<pcl::PointIndices> all_indices;
85 for (std::map<uint32_t, pcl::Supervoxel<PointT>::Ptr >::iterator
86 it = supervoxel_clusters.begin();
87 it != supervoxel_clusters.end();
89 pcl::Supervoxel<PointT>::Ptr super_voxel = it->second;
90 pcl::PointCloud<PointT>::Ptr super_voxel_cloud = super_voxel->voxels_;
91 pcl::PointIndices indices;
93 for (
size_t i = 0; i < super_voxel_cloud->size(); i++) {
94 indices.indices.push_back(i + output->points.size());
96 all_indices.push_back(indices);
97 *output = *output + *super_voxel_cloud;
99 sensor_msgs::PointCloud2 ros_cloud;
101 ros_cloud.header = cloud_msg->header;
102 jsk_recognition_msgs::ClusterPointIndices ros_indices;
106 ros_indices.header = cloud_msg->header;
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_indices_
void publish(const boost::shared_ptr< M > &message) const
virtual void unsubscribe()
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::SupervoxelSegmentation, nodelet::Nodelet)
void output(int index, double value)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
ros::Publisher pub_cloud_
SupervoxelSegmentationConfig Config
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices::Ptr > cluster_indices, const std_msgs::Header &header)
double normal_importance_
double spatial_importance_
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)