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 #include <pluginlib/class_list_macros.h>
00036 #include "jsk_pcl_ros/euclidean_cluster_extraction_nodelet.h"
00037 #include <jsk_recognition_utils/pcl_util.h>
00038
00039 using namespace std;
00040 using namespace pcl;
00041
00042 namespace jsk_pcl_ros
00043 {
00044
00045 void EuclideanClustering::extract(
00046 const sensor_msgs::PointCloud2ConstPtr &input)
00047 {
00048 boost::mutex::scoped_lock lock(mutex_);
00049 vital_checker_->poke();
00050 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
00051 (new pcl::PointCloud<pcl::PointXYZ>);
00052 pcl::fromROSMsg(*input, *cloud);
00053
00054 std::vector<pcl::PointIndices> cluster_indices;
00055
00056
00057 pcl::PointIndices::Ptr nonnan_indices (new pcl::PointIndices);
00058 for (size_t i = 0; i < cloud->points.size(); i++) {
00059 pcl::PointXYZ p = cloud->points[i];
00060 if (!std::isnan(p.x) && !std::isnan(p.y) && !std::isnan(p.z)) {
00061 nonnan_indices->indices.push_back(i);
00062 }
00063 }
00064
00065 if (nonnan_indices->indices.size() == 0) {
00066
00067 jsk_recognition_msgs::ClusterPointIndices result;
00068 result.header = input->header;
00069 result_pub_.publish(result);
00070
00071 jsk_recognition_msgs::Int32Stamped::Ptr cluster_num_msg (new jsk_recognition_msgs::Int32Stamped);
00072 cluster_num_msg->header = input->header;
00073 cluster_num_msg->data = 0;
00074 cluster_num_pub_.publish(cluster_num_msg);
00075 return;
00076 }
00077
00078 EuclideanClusterExtraction<pcl::PointXYZ> impl;
00079 {
00080 jsk_topic_tools::ScopedTimer timer = kdtree_acc_.scopedTimer();
00081 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
00082 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00083 tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
00084 #else
00085 pcl::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZ>);
00086 tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
00087 #endif
00088 tree->setInputCloud (cloud);
00089 impl.setClusterTolerance (tolerance);
00090 impl.setMinClusterSize (minsize_);
00091 impl.setMaxClusterSize (maxsize_);
00092 impl.setSearchMethod (tree);
00093 impl.setIndices(nonnan_indices);
00094 impl.setInputCloud (cloud);
00095 }
00096
00097 {
00098 jsk_topic_tools::ScopedTimer timer = segmentation_acc_.scopedTimer();
00099 impl.extract (cluster_indices);
00100 }
00101
00102
00103 jsk_recognition_msgs::ClusterPointIndices result;
00104 result.cluster_indices.resize(cluster_indices.size());
00105 cluster_counter_.add(cluster_indices.size());
00106 result.header = input->header;
00107 if (cogs_.size() != 0 && cogs_.size() == cluster_indices.size()) {
00108
00109
00110
00111
00112
00113 Vector4fVector new_cogs;
00114 computeCentroidsOfClusters(new_cogs, cloud, cluster_indices);
00115 double D[cogs_.size() * new_cogs.size()];
00116 computeDistanceMatrix(D, cogs_, new_cogs);
00117 std::vector<int> pivot_table = buildLabelTrackingPivotTable(D, cogs_, new_cogs, label_tracking_tolerance);
00118 if (pivot_table.size() != 0) {
00119 cluster_indices = pivotClusterIndices(pivot_table, cluster_indices);
00120 }
00121 }
00122 Vector4fVector tmp_cogs;
00123 computeCentroidsOfClusters(tmp_cogs, cloud, cluster_indices);
00124 cogs_ = tmp_cogs;
00125
00126 for (size_t i = 0; i < cluster_indices.size(); i++) {
00127 #if ROS_VERSION_MINIMUM(1, 10, 0)
00128
00129 result.cluster_indices[i].header
00130 = pcl_conversions::fromPCL(cluster_indices[i].header);
00131 #else
00132
00133 result.cluster_indices[i].header = cluster_indices[i].header;
00134 #endif
00135 result.cluster_indices[i].indices = cluster_indices[i].indices;
00136 }
00137
00138 result_pub_.publish(result);
00139
00140 jsk_recognition_msgs::Int32Stamped::Ptr cluster_num_msg (new jsk_recognition_msgs::Int32Stamped);
00141 cluster_num_msg->header = input->header;
00142 cluster_num_msg->data = cluster_indices.size();
00143 cluster_num_pub_.publish(cluster_num_msg);
00144
00145 diagnostic_updater_->update();
00146 }
00147
00148
00149 bool EuclideanClustering::serviceCallback(
00150 jsk_recognition_msgs::EuclideanSegment::Request &req,
00151 jsk_recognition_msgs::EuclideanSegment::Response &res)
00152 {
00153 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00154 pcl::fromROSMsg(req.input, *cloud);
00155
00156 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
00157 pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00158 tree = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
00159 #else
00160 pcl::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::KdTreeFLANN<pcl::PointXYZ>);
00161 tree = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
00162 #endif
00163
00164 vector<pcl::PointIndices> cluster_indices;
00165 EuclideanClusterExtraction<pcl::PointXYZ> impl;
00166 double tor;
00167 if ( req.tolerance < 0) {
00168 tor = tolerance;
00169 } else {
00170 tor = req.tolerance;
00171 }
00172 impl.setClusterTolerance (tor);
00173 impl.setMinClusterSize (minsize_);
00174 impl.setMaxClusterSize (maxsize_);
00175 impl.setSearchMethod (tree);
00176 impl.setInputCloud (cloud);
00177 impl.extract (cluster_indices);
00178
00179 res.output.resize( cluster_indices.size() );
00180 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 )
00181 pcl::PCLPointCloud2::Ptr pcl_cloud(new pcl::PCLPointCloud2);
00182 pcl_conversions::toPCL(req.input, *pcl_cloud);
00183 pcl::ExtractIndices<pcl::PCLPointCloud2> ex;
00184 ex.setInputCloud(pcl_cloud);
00185 #else
00186 pcl::ExtractIndices<sensor_msgs::PointCloud2> ex;
00187 ex.setInputCloud ( boost::make_shared< sensor_msgs::PointCloud2 > (req.input) );
00188 #endif
00189 for ( size_t i = 0; i < cluster_indices.size(); i++ ) {
00190 ex.setIndices ( boost::make_shared< pcl::PointIndices > (cluster_indices[i]) );
00191 ex.setNegative ( false );
00192 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 7 )
00193 pcl::PCLPointCloud2 output_cloud;
00194 ex.filter ( output_cloud );
00195 pcl_conversions::fromPCL(output_cloud, res.output[i]);
00196 #else
00197 ex.filter ( res.output[i] );
00198 #endif
00199 }
00200 return true;
00201 }
00202
00203 void EuclideanClustering::onInit()
00204 {
00205 DiagnosticNodelet::onInit();
00206
00208
00210 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00211 dynamic_reconfigure::Server<Config>::CallbackType f =
00212 boost::bind (&EuclideanClustering::configCallback, this, _1, _2);
00213 srv_->setCallback (f);
00214
00216
00218 result_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices> (*pnh_, "output", 1);
00219 cluster_num_pub_ = advertise<jsk_recognition_msgs::Int32Stamped> (*pnh_, "cluster_num", 1);
00220 service_ = pnh_->advertiseService(pnh_->resolveName("euclidean_clustering"),
00221 &EuclideanClustering::serviceCallback, this);
00222
00223 onInitPostProcess();
00224 }
00225
00226 void EuclideanClustering::subscribe()
00227 {
00229
00231 sub_input_ = pnh_->subscribe("input", 1, &EuclideanClustering::extract, this);
00232 }
00233
00234 void EuclideanClustering::unsubscribe()
00235 {
00236 sub_input_.shutdown();
00237 }
00238
00239 void EuclideanClustering::updateDiagnostic(
00240 diagnostic_updater::DiagnosticStatusWrapper &stat)
00241 {
00242 if (vital_checker_->isAlive()) {
00243 stat.summary(
00244 diagnostic_msgs::DiagnosticStatus::OK,
00245 "EuclideanSegmentation running");
00246
00247 jsk_topic_tools::addDiagnosticInformation(
00248 "Kdtree Construction", kdtree_acc_, stat);
00249 jsk_topic_tools::addDiagnosticInformation(
00250 "Euclidean Segmentation", segmentation_acc_, stat);
00251 stat.add("Cluster Num (Avg.)", cluster_counter_.mean());
00252 stat.add("Max Size of the cluster", maxsize_);
00253 stat.add("Min Size of the cluster", minsize_);
00254 stat.add("Cluster tolerance", tolerance);
00255 stat.add("Tracking tolerance", label_tracking_tolerance);
00256 }
00257 DiagnosticNodelet::updateDiagnostic(stat);
00258 }
00259
00260 void EuclideanClustering::configCallback (Config &config, uint32_t level)
00261 {
00262 boost::mutex::scoped_lock lock(mutex_);
00263 tolerance = config.tolerance;
00264 label_tracking_tolerance = config.label_tracking_tolerance;
00265 maxsize_ = config.max_size;
00266 minsize_ = config.min_size;
00267 }
00268
00269 std::vector<pcl::PointIndices> EuclideanClustering::pivotClusterIndices(
00270 std::vector<int>& pivot_table,
00271 std::vector<pcl::PointIndices>& cluster_indices)
00272 {
00273 std::vector<pcl::PointIndices> new_cluster_indices;
00274 new_cluster_indices.resize(pivot_table.size());
00275 for (size_t i = 0; i < pivot_table.size(); i++) {
00276 new_cluster_indices[i] = cluster_indices[pivot_table[i]];
00277 }
00278 return new_cluster_indices;
00279 }
00280 std::vector<int> EuclideanClustering::buildLabelTrackingPivotTable(
00281 double* D, Vector4fVector cogs, Vector4fVector new_cogs,
00282 double label_tracking_tolerance)
00283 {
00284 std::vector<int> pivot_table;
00285
00286 pivot_table.resize(cogs.size());
00287 for (size_t i = 0; i < pivot_table.size(); i++)
00288 pivot_table[i] = i;
00289 for (size_t pivot_counter = 0; pivot_counter < pivot_table.size();
00290 pivot_counter++)
00291 {
00292 double minimum_distance = DBL_MAX;
00293 size_t minimum_previous_index = 0;
00294 size_t minimum_next_index = 0;
00295 for (size_t i = 0; i < cogs.size(); i++)
00296 {
00297 for (size_t j = 0; j < new_cogs.size(); j++)
00298 {
00299 double distance = D[i * cogs.size() + j];
00300
00301 if (distance < minimum_distance)
00302 {
00303 minimum_distance = distance;
00304 minimum_previous_index = i;
00305 minimum_next_index = j;
00306 }
00307 }
00308 }
00309 if (minimum_distance > label_tracking_tolerance)
00310 {
00311
00312
00313 std::vector<int> dummy;
00314 return dummy;
00315 }
00316 pivot_table[minimum_previous_index] = minimum_next_index;
00317
00318 for (size_t j = 0; j < new_cogs.size(); j++)
00319 {
00320 D[minimum_previous_index * cogs.size() + j] = DBL_MAX;
00321 }
00322 }
00323 return pivot_table;
00324 }
00325
00326 void EuclideanClustering::computeDistanceMatrix(
00327 double* D,
00328 Vector4fVector& old_cogs,
00329 Vector4fVector& new_cogs)
00330 {
00331 for (size_t i = 0; i < old_cogs.size(); i++) {
00332 Eigen::Vector4f previous_cog = old_cogs[i];
00333 for (size_t j = 0; j < new_cogs.size(); j++) {
00334 Eigen::Vector4f next_cog = new_cogs[j];
00335 double distance = (next_cog - previous_cog).norm();
00336 D[i * old_cogs.size() + j] = distance;
00337 }
00338 }
00339 }
00340
00341 void EuclideanClustering::computeCentroidsOfClusters(
00342 Vector4fVector& ret,
00343 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00344 std::vector<pcl::PointIndices> cluster_indices)
00345 {
00346 pcl::ExtractIndices<pcl::PointXYZ> extract;
00347 extract.setInputCloud(cloud);
00348 ret.resize(cluster_indices.size());
00349 for (size_t i = 0; i < cluster_indices.size(); i++)
00350 {
00351
00352 pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00353 pcl::PointIndices::Ptr segmented_indices (new pcl::PointIndices);
00354 for (size_t j = 0; j < cluster_indices[i].indices.size(); j++)
00355 {
00356 segmented_indices->indices.push_back(cluster_indices[i].indices[j]);
00357 }
00358 extract.setIndices(segmented_indices);
00359 extract.filter(*segmented_cloud);
00360 Eigen::Vector4f center;
00361 pcl::compute3DCentroid(*segmented_cloud, center);
00362 ret[i] = center;
00363 }
00364 }
00365
00366 }
00367
00368 #include <pluginlib/class_list_macros.h>
00369 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::EuclideanClustering, nodelet::Nodelet);
00370