LazyNodelet for segmentation/ExtractPolygonalPrismData

This commit is contained in:
Kentaro Wada 2017-08-22 16:28:36 +00:00 committed by Paul Bovbel
parent 76ea38194e
commit ebe25b4b89
2 changed files with 28 additions and 6 deletions

View File

@ -97,9 +97,13 @@ namespace pcl_ros
nf_.add (boost::make_shared<PointIndices> (cloud));
}
/** \brief Nodelet initialization routine. */
/** \brief Nodelet initialization routine. */
void onInit ();
/** \brief LazyNodelet connection routine. */
void subscribe ();
void unsubscribe ();
/** \brief Dynamic reconfigure callback
* \param config the config object
* \param level the dynamic reconfigure level

View File

@ -52,14 +52,24 @@ pcl_ros::ExtractPolygonalPrismData::onInit ()
// Call the super onInit ()
PCLNodelet::onInit ();
sub_hull_filter_.subscribe (*pnh_, "planar_hull", max_queue_size_);
sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
// Enable the dynamic reconfigure service
srv_ = boost::make_shared <dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > (*pnh_);
dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig>::CallbackType f = boost::bind (&ExtractPolygonalPrismData::config_callback, this, _1, _2);
srv_->setCallback (f);
// Advertise the output topics
pub_output_ = advertise<PointIndices> (*pnh_, "output", max_queue_size_);
onInitPostProcess ();
}
//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::ExtractPolygonalPrismData::subscribe ()
{
sub_hull_filter_.subscribe (*pnh_, "planar_hull", max_queue_size_);
sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
// Create the objects here
if (approximate_sync_)
sync_input_hull_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices> > > (max_queue_size_);
@ -88,9 +98,17 @@ pcl_ros::ExtractPolygonalPrismData::onInit ()
sync_input_hull_indices_a_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
else
sync_input_hull_indices_e_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
}
// Advertise the output topics
pub_output_ = pnh_->advertise<PointIndices> ("output", max_queue_size_);
//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::ExtractPolygonalPrismData::unsubscribe ()
{
sub_hull_filter_.unsubscribe ();
sub_input_filter_.unsubscribe ();
if (use_indices_)
sub_indices_filter_.unsubscribe ();
}
//////////////////////////////////////////////////////////////////////////////////////////////