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
00037
00038 #include <pluginlib/class_list_macros.h>
00039 #include "pcl_ros/segmentation/sac_segmentation.h"
00040
00042 void
00043 pcl_ros::SACSegmentation::onInit ()
00044 {
00045
00046 PCLNodelet::onInit ();
00047
00048
00049 if (use_indices_)
00050 {
00051
00052 sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
00053 sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
00054
00055
00056
00057
00058
00059 if (latched_indices_)
00060 {
00061
00062 sub_indices_filter_.registerCallback (bind (&SACSegmentation::indices_callback, this, _1));
00063
00064 sub_input_filter_.registerCallback (bind (&SACSegmentation::input_callback, this, _1));
00065
00066
00067
00068 sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointIndices> > > (max_queue_size_);
00069 sync_input_indices_e_->connectInput (sub_input_filter_, nf_pi_);
00070 sync_input_indices_e_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, _1, _2));
00071 }
00072
00073 else
00074 {
00075 if (approximate_sync_)
00076 {
00077 sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointIndices> > > (max_queue_size_);
00078 sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
00079 sync_input_indices_a_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, _1, _2));
00080 }
00081 else
00082 {
00083 sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointIndices> > > (max_queue_size_);
00084 sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
00085 sync_input_indices_e_->registerCallback (bind (&SACSegmentation::input_indices_callback, this, _1, _2));
00086 }
00087 }
00088 }
00089 else
00090
00091 sub_input_ = pnh_->subscribe<PointCloud> ("input", max_queue_size_, bind (&SACSegmentation::input_indices_callback, this, _1, PointIndicesConstPtr ()));
00092
00093
00094 pub_indices_ = pnh_->advertise<PointIndices> ("inliers", max_queue_size_);
00095 pub_model_ = pnh_->advertise<ModelCoefficients> ("model", max_queue_size_);
00096
00097
00098 int model_type;
00099 if (!pnh_->getParam ("model_type", model_type))
00100 {
00101 NODELET_ERROR ("[onInit] Need a 'model_type' parameter to be set before continuing!");
00102 return;
00103 }
00104 double threshold;
00105 if (!pnh_->getParam ("distance_threshold", threshold))
00106 {
00107 NODELET_ERROR ("[onInit] Need a 'distance_threshold' parameter to be set before continuing!");
00108 return;
00109 }
00110
00111
00112 int method_type = 0;
00113 pnh_->getParam ("method_type", method_type);
00114
00115 XmlRpc::XmlRpcValue axis_param;
00116 pnh_->getParam ("axis", axis_param);
00117 Eigen::Vector3f axis = Eigen::Vector3f::Zero ();
00118
00119 switch (axis_param.getType ())
00120 {
00121 case XmlRpc::XmlRpcValue::TypeArray:
00122 {
00123 if (axis_param.size () != 3)
00124 {
00125 NODELET_ERROR ("[%s::onInit] Parameter 'axis' given but with a different number of values (%d) than required (3)!", getName ().c_str (), axis_param.size ());
00126 return;
00127 }
00128 for (int i = 0; i < 3; ++i)
00129 {
00130 if (axis_param[i].getType () != XmlRpc::XmlRpcValue::TypeDouble)
00131 {
00132 NODELET_ERROR ("[%s::onInit] Need floating point values for 'axis' parameter.", getName ().c_str ());
00133 return;
00134 }
00135 double value = axis_param[i]; axis[i] = value;
00136 }
00137 break;
00138 }
00139 default:
00140 {
00141 break;
00142 }
00143 }
00144
00145
00146 srand (time (0));
00147
00148
00149 srv_ = boost::make_shared<dynamic_reconfigure::Server<SACSegmentationConfig> >(*pnh_);
00150 dynamic_reconfigure::Server<SACSegmentationConfig>::CallbackType f = boost::bind (&SACSegmentation::config_callback, this, _1, _2);
00151 srv_->setCallback (f);
00152
00153 NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
00154 " - model_type : %d\n"
00155 " - method_type : %d\n"
00156 " - model_threshold : %f\n"
00157 " - axis : [%f, %f, %f]\n",
00158 getName ().c_str (), model_type, method_type, threshold,
00159 axis[0], axis[1], axis[2]);
00160
00161
00162 impl_.setModelType (model_type);
00163 impl_.setMethodType (method_type);
00164 impl_.setAxis (axis);
00165 }
00166
00168 void
00169 pcl_ros::SACSegmentation::config_callback (SACSegmentationConfig &config, uint32_t level)
00170 {
00171 boost::mutex::scoped_lock lock (mutex_);
00172
00173 if (impl_.getDistanceThreshold () != config.distance_threshold)
00174 {
00175
00176 impl_.setDistanceThreshold (config.distance_threshold);
00177 NODELET_DEBUG ("[%s::config_callback] Setting new distance to model threshold to: %f.", getName ().c_str (), config.distance_threshold);
00178 }
00179
00180 if (impl_.getEpsAngle () != config.eps_angle)
00181 {
00182 impl_.setEpsAngle (config.eps_angle);
00183 NODELET_DEBUG ("[%s::config_callback] Setting new epsilon angle to model threshold to: %f (%f degrees).", getName ().c_str (), config.eps_angle, config.eps_angle * 180.0 / M_PI);
00184 }
00185
00186
00187 if (min_inliers_ != config.min_inliers)
00188 {
00189 min_inliers_ = config.min_inliers;
00190 NODELET_DEBUG ("[%s::config_callback] Setting new minimum number of inliers to: %d.", getName ().c_str (), min_inliers_);
00191 }
00192
00193 if (impl_.getMaxIterations () != config.max_iterations)
00194 {
00195
00196 impl_.setMaxIterations (config.max_iterations);
00197 NODELET_DEBUG ("[%s::config_callback] Setting new maximum number of iterations to: %d.", getName ().c_str (), config.max_iterations);
00198 }
00199 if (impl_.getProbability () != config.probability)
00200 {
00201
00202 impl_.setProbability (config.probability);
00203 NODELET_DEBUG ("[%s::config_callback] Setting new probability to: %f.", getName ().c_str (), config.probability);
00204 }
00205 if (impl_.getOptimizeCoefficients () != config.optimize_coefficients)
00206 {
00207 impl_.setOptimizeCoefficients (config.optimize_coefficients);
00208 NODELET_DEBUG ("[%s::config_callback] Setting coefficient optimization to: %s.", getName ().c_str (), (config.optimize_coefficients) ? "true" : "false");
00209 }
00210
00211 double radius_min, radius_max;
00212 impl_.getRadiusLimits (radius_min, radius_max);
00213 if (radius_min != config.radius_min)
00214 {
00215 radius_min = config.radius_min;
00216 NODELET_DEBUG ("[config_callback] Setting minimum allowable model radius to: %f.", radius_min);
00217 impl_.setRadiusLimits (radius_min, radius_max);
00218 }
00219 if (radius_max != config.radius_max)
00220 {
00221 radius_max = config.radius_max;
00222 NODELET_DEBUG ("[config_callback] Setting maximum allowable model radius to: %f.", radius_max);
00223 impl_.setRadiusLimits (radius_min, radius_max);
00224 }
00225
00226 if (tf_input_frame_ != config.input_frame)
00227 {
00228 tf_input_frame_ = config.input_frame;
00229 NODELET_DEBUG ("[config_callback] Setting the input TF frame to: %s.", tf_input_frame_.c_str ());
00230 NODELET_WARN ("input_frame TF not implemented yet!");
00231 }
00232 if (tf_output_frame_ != config.output_frame)
00233 {
00234 tf_output_frame_ = config.output_frame;
00235 NODELET_DEBUG ("[config_callback] Setting the output TF frame to: %s.", tf_output_frame_.c_str ());
00236 NODELET_WARN ("output_frame TF not implemented yet!");
00237 }
00238 }
00239
00241 void
00242 pcl_ros::SACSegmentation::input_indices_callback (const PointCloudConstPtr &cloud,
00243 const PointIndicesConstPtr &indices)
00244 {
00245 boost::mutex::scoped_lock lock (mutex_);
00246
00247
00248 if (pub_indices_.getNumSubscribers () <= 0 && pub_model_.getNumSubscribers () <= 0)
00249 return;
00250
00251 PointIndices inliers;
00252 ModelCoefficients model;
00253
00254 inliers.header = model.header = cloud->header;
00255
00256
00257 if (!isValid (cloud))
00258 {
00259 NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
00260 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00261 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00262 return;
00263 }
00264
00265 if (indices && !isValid (indices))
00266 {
00267 NODELET_ERROR ("[%s::input_indices_callback] Invalid indices!", getName ().c_str ());
00268 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00269 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00270 return;
00271 }
00272
00274 if (indices && !indices->header.frame_id.empty ())
00275 NODELET_DEBUG ("[%s::input_indices_callback]\n"
00276 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00277 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
00278 getName ().c_str (),
00279 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00280 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
00281 else
00282 NODELET_DEBUG ("[%s::input_indices_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.",
00283 getName ().c_str (), cloud->width * cloud->height, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ());
00285
00286
00287 tf_input_orig_frame_ = cloud->header.frame_id;
00288 PointCloudConstPtr cloud_tf;
00289
00290
00291
00292
00293
00294
00295
00296
00297
00298
00299
00300 cloud_tf = cloud;
00301
00302 IndicesConstPtr indices_ptr;
00303 if (indices && !indices->header.frame_id.empty ())
00304 indices_ptr = boost::make_shared <std::vector<int> > (indices->indices);
00305
00306 impl_.setInputCloud (cloud_tf);
00307 impl_.setIndices (indices_ptr);
00308
00309
00310 if (!cloud->points.empty ())
00311 impl_.segment (inliers, model);
00312
00313
00314
00315
00316 if ((int)inliers.indices.size () <= min_inliers_)
00317 {
00318 inliers.indices.clear ();
00319 model.values.clear ();
00320 }
00321
00322
00323 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00324 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00325 NODELET_DEBUG ("[%s::input_indices_callback] Published PointIndices with %zu values on topic %s, and ModelCoefficients with %zu values on topic %s",
00326 getName ().c_str (), inliers.indices.size (), pnh_->resolveName ("inliers").c_str (),
00327 model.values.size (), pnh_->resolveName ("model").c_str ());
00328
00329 if (inliers.indices.empty ())
00330 NODELET_WARN ("[%s::input_indices_callback] No inliers found!", getName ().c_str ());
00331 }
00332
00334 void
00335 pcl_ros::SACSegmentationFromNormals::onInit ()
00336 {
00337
00338 PCLNodelet::onInit ();
00339
00340
00341 srv_ = boost::make_shared <dynamic_reconfigure::Server<SACSegmentationFromNormalsConfig> > (*pnh_);
00342 dynamic_reconfigure::Server<SACSegmentationFromNormalsConfig>::CallbackType f = boost::bind (&SACSegmentationFromNormals::config_callback, this, _1, _2);
00343 srv_->setCallback (f);
00344
00345
00346 sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
00347 sub_normals_filter_.subscribe (*pnh_, "normals", max_queue_size_);
00348
00349
00350 sub_axis_ = pnh_->subscribe ("axis", 1, &SACSegmentationFromNormals::axis_callback, this);
00351
00352 if (approximate_sync_)
00353 sync_input_normals_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloudN, PointIndices> > > (max_queue_size_);
00354 else
00355 sync_input_normals_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloudN, PointIndices> > > (max_queue_size_);
00356
00357
00358 if (use_indices_)
00359 {
00360
00361 sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
00362
00363 if (approximate_sync_)
00364 sync_input_normals_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, sub_indices_filter_);
00365 else
00366 sync_input_normals_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, sub_indices_filter_);
00367 }
00368 else
00369 {
00370
00371 sub_input_filter_.registerCallback (bind (&SACSegmentationFromNormals::input_callback, this, _1));
00372
00373 if (approximate_sync_)
00374 sync_input_normals_indices_a_->connectInput (sub_input_filter_, sub_normals_filter_, nf_);
00375 else
00376 sync_input_normals_indices_e_->connectInput (sub_input_filter_, sub_normals_filter_, nf_);
00377 }
00378
00379 if (approximate_sync_)
00380 sync_input_normals_indices_a_->registerCallback (bind (&SACSegmentationFromNormals::input_normals_indices_callback, this, _1, _2, _3));
00381 else
00382 sync_input_normals_indices_e_->registerCallback (bind (&SACSegmentationFromNormals::input_normals_indices_callback, this, _1, _2, _3));
00383
00384
00385 pub_indices_ = pnh_->advertise<PointIndices> ("inliers", max_queue_size_);
00386 pub_model_ = pnh_->advertise<ModelCoefficients> ("model", max_queue_size_);
00387
00388
00389 int model_type;
00390 if (!pnh_->getParam ("model_type", model_type))
00391 {
00392 NODELET_ERROR ("[%s::onInit] Need a 'model_type' parameter to be set before continuing!", getName ().c_str ());
00393 return;
00394 }
00395 double threshold;
00396 if (!pnh_->getParam ("distance_threshold", threshold))
00397 {
00398 NODELET_ERROR ("[%s::onInit] Need a 'distance_threshold' parameter to be set before continuing!", getName ().c_str ());
00399 return;
00400 }
00401
00402
00403 int method_type = 0;
00404 pnh_->getParam ("method_type", method_type);
00405
00406 XmlRpc::XmlRpcValue axis_param;
00407 pnh_->getParam ("axis", axis_param);
00408 Eigen::Vector3f axis = Eigen::Vector3f::Zero ();
00409
00410 switch (axis_param.getType ())
00411 {
00412 case XmlRpc::XmlRpcValue::TypeArray:
00413 {
00414 if (axis_param.size () != 3)
00415 {
00416 NODELET_ERROR ("[%s::onInit] Parameter 'axis' given but with a different number of values (%d) than required (3)!", getName ().c_str (), axis_param.size ());
00417 return;
00418 }
00419 for (int i = 0; i < 3; ++i)
00420 {
00421 if (axis_param[i].getType () != XmlRpc::XmlRpcValue::TypeDouble)
00422 {
00423 NODELET_ERROR ("[%s::onInit] Need floating point values for 'axis' parameter.", getName ().c_str ());
00424 return;
00425 }
00426 double value = axis_param[i]; axis[i] = value;
00427 }
00428 break;
00429 }
00430 default:
00431 {
00432 break;
00433 }
00434 }
00435
00436
00437 srand (time (0));
00438
00439 NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
00440 " - model_type : %d\n"
00441 " - method_type : %d\n"
00442 " - model_threshold : %f\n"
00443 " - axis : [%f, %f, %f]\n",
00444 getName ().c_str (), model_type, method_type, threshold,
00445 axis[0], axis[1], axis[2]);
00446
00447
00448 impl_.setModelType (model_type);
00449 impl_.setMethodType (method_type);
00450 impl_.setAxis (axis);
00451 }
00452
00454 void
00455 pcl_ros::SACSegmentationFromNormals::axis_callback (const pcl::ModelCoefficientsConstPtr &model)
00456 {
00457 boost::mutex::scoped_lock lock (mutex_);
00458
00459 if (model->values.size () < 3)
00460 {
00461 NODELET_ERROR ("[%s::axis_callback] Invalid axis direction / model coefficients with %zu values sent on %s!", getName ().c_str (), model->values.size (), pnh_->resolveName ("axis").c_str ());
00462 return;
00463 }
00464 NODELET_DEBUG ("[%s::axis_callback] Received axis direction: %f %f %f", getName ().c_str (), model->values[0], model->values[1], model->values[2]);
00465
00466 Eigen::Vector3f axis (model->values[0], model->values[1], model->values[2]);
00467 impl_.setAxis (axis);
00468 }
00469
00471 void
00472 pcl_ros::SACSegmentationFromNormals::config_callback (SACSegmentationFromNormalsConfig &config, uint32_t level)
00473 {
00474 boost::mutex::scoped_lock lock (mutex_);
00475
00476 if (impl_.getDistanceThreshold () != config.distance_threshold)
00477 {
00478 impl_.setDistanceThreshold (config.distance_threshold);
00479 NODELET_DEBUG ("[%s::config_callback] Setting distance to model threshold to: %f.", getName ().c_str (), config.distance_threshold);
00480 }
00481
00482 if (impl_.getEpsAngle () != config.eps_angle)
00483 {
00484 impl_.setEpsAngle (config.eps_angle);
00485 NODELET_DEBUG ("[%s::config_callback] Setting new epsilon angle to model threshold to: %f (%f degrees).", getName ().c_str (), config.eps_angle, config.eps_angle * 180.0 / M_PI);
00486 }
00487
00488 if (impl_.getMaxIterations () != config.max_iterations)
00489 {
00490 impl_.setMaxIterations (config.max_iterations);
00491 NODELET_DEBUG ("[%s::config_callback] Setting new maximum number of iterations to: %d.", getName ().c_str (), config.max_iterations);
00492 }
00493
00494
00495 if (min_inliers_ != config.min_inliers)
00496 {
00497 min_inliers_ = config.min_inliers;
00498 NODELET_DEBUG ("[%s::config_callback] Setting new minimum number of inliers to: %d.", getName ().c_str (), min_inliers_);
00499 }
00500
00501
00502 if (impl_.getProbability () != config.probability)
00503 {
00504 impl_.setProbability (config.probability);
00505 NODELET_DEBUG ("[%s::config_callback] Setting new probability to: %f.", getName ().c_str (), config.probability);
00506 }
00507
00508 if (impl_.getOptimizeCoefficients () != config.optimize_coefficients)
00509 {
00510 impl_.setOptimizeCoefficients (config.optimize_coefficients);
00511 NODELET_DEBUG ("[%s::config_callback] Setting coefficient optimization to: %s.", getName ().c_str (), (config.optimize_coefficients) ? "true" : "false");
00512 }
00513
00514 if (impl_.getNormalDistanceWeight () != config.normal_distance_weight)
00515 {
00516 impl_.setNormalDistanceWeight (config.normal_distance_weight);
00517 NODELET_DEBUG ("[%s::config_callback] Setting new distance weight to: %f.", getName ().c_str (), config.normal_distance_weight);
00518 }
00519
00520 double radius_min, radius_max;
00521 impl_.getRadiusLimits (radius_min, radius_max);
00522 if (radius_min != config.radius_min)
00523 {
00524 radius_min = config.radius_min;
00525 NODELET_DEBUG ("[%s::config_callback] Setting minimum allowable model radius to: %f.", getName ().c_str (), radius_min);
00526 impl_.setRadiusLimits (radius_min, radius_max);
00527 }
00528 if (radius_max != config.radius_max)
00529 {
00530 radius_max = config.radius_max;
00531 NODELET_DEBUG ("[%s::config_callback] Setting maximum allowable model radius to: %f.", getName ().c_str (), radius_max);
00532 impl_.setRadiusLimits (radius_min, radius_max);
00533 }
00534 }
00535
00537 void
00538 pcl_ros::SACSegmentationFromNormals::input_normals_indices_callback (
00539 const PointCloudConstPtr &cloud,
00540 const PointCloudNConstPtr &cloud_normals,
00541 const PointIndicesConstPtr &indices
00542 )
00543 {
00544 boost::mutex::scoped_lock lock (mutex_);
00545
00546
00547 if (pub_indices_.getNumSubscribers () <= 0 && pub_model_.getNumSubscribers () <= 0)
00548 return;
00549
00550 PointIndices inliers;
00551 ModelCoefficients model;
00552
00553 inliers.header = model.header = cloud->header;
00554
00555 if (impl_.getModelType () < 0)
00556 {
00557 NODELET_ERROR ("[%s::input_normals_indices_callback] Model type not set!", getName ().c_str ());
00558 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00559 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00560 return;
00561 }
00562
00563 if (!isValid (cloud))
00564 {
00565 NODELET_ERROR ("[%s::input_normals_indices_callback] Invalid input!", getName ().c_str ());
00566 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00567 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00568 return;
00569 }
00570
00571 if (indices && !isValid (indices))
00572 {
00573 NODELET_ERROR ("[%s::input_normals_indices_callback] Invalid indices!", getName ().c_str ());
00574 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00575 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00576 return;
00577 }
00578
00580 if (indices && !indices->header.frame_id.empty ())
00581 NODELET_DEBUG ("[%s::input_normals_indices_callback]\n"
00582 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00583 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00584 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
00585 getName ().c_str (),
00586 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00587 cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (),
00588 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
00589 else
00590 NODELET_DEBUG ("[%s::input_normals_indices_callback]\n"
00591 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00592 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
00593 getName ().c_str (),
00594 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00595 cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ());
00597
00598
00599
00600 int cloud_nr_points = cloud->width * cloud->height;
00601 int cloud_normals_nr_points = cloud_normals->width * cloud_normals->height;
00602 if (cloud_nr_points != cloud_normals_nr_points)
00603 {
00604 NODELET_ERROR ("[%s::input_normals_indices_callback] Number of points in the input dataset (%d) differs from the number of points in the normals (%d)!", getName ().c_str (), cloud_nr_points, cloud_normals_nr_points);
00605 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00606 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00607 return;
00608 }
00609
00610 impl_.setInputCloud (cloud);
00611 impl_.setInputNormals (cloud_normals);
00612
00613 IndicesConstPtr indices_ptr;
00614 if (indices && !indices->header.frame_id.empty ())
00615 indices_ptr = boost::make_shared <std::vector<int> > (indices->indices);
00616
00617 impl_.setIndices (indices_ptr);
00618
00619
00620 if (!cloud->points.empty ())
00621 impl_.segment (inliers, model);
00622
00623
00624 if ((int)inliers.indices.size () <= min_inliers_)
00625 {
00626 inliers.indices.clear ();
00627 model.values.clear ();
00628 }
00629
00630
00631 pub_indices_.publish (boost::make_shared<const PointIndices> (inliers));
00632 pub_model_.publish (boost::make_shared<const ModelCoefficients> (model));
00633 NODELET_DEBUG ("[%s::input_normals_callback] Published PointIndices with %zu values on topic %s, and ModelCoefficients with %zu values on topic %s",
00634 getName ().c_str (), inliers.indices.size (), pnh_->resolveName ("inliers").c_str (),
00635 model.values.size (), pnh_->resolveName ("model").c_str ());
00636 if (inliers.indices.empty ())
00637 NODELET_WARN ("[%s::input_indices_callback] No inliers found!", getName ().c_str ());
00638 }
00639
00640 typedef pcl_ros::SACSegmentation SACSegmentation;
00641 typedef pcl_ros::SACSegmentationFromNormals SACSegmentationFromNormals;
00642 PLUGINLIB_DECLARE_CLASS (pcl, SACSegmentation, SACSegmentation, nodelet::Nodelet);
00643 PLUGINLIB_DECLARE_CLASS (pcl, SACSegmentationFromNormals, SACSegmentationFromNormals, nodelet::Nodelet);
00644