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/transforms.h"
00040 #include "pcl_ros/segmentation/extract_polygonal_prism_data.h"
00041
00043 void
00044 pcl_ros::ExtractPolygonalPrismData::onInit ()
00045 {
00046
00047 PCLNodelet::onInit ();
00048
00049 sub_hull_filter_.subscribe (*pnh_, "planar_hull", max_queue_size_);
00050 sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
00051
00052
00053 srv_ = boost::make_shared <dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > (*pnh_);
00054 dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig>::CallbackType f = boost::bind (&ExtractPolygonalPrismData::config_callback, this, _1, _2);
00055 srv_->setCallback (f);
00056
00057
00058 if (approximate_sync_)
00059 sync_input_hull_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices> > > (max_queue_size_);
00060 else
00061 sync_input_hull_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices> > > (max_queue_size_);
00062
00063 if (use_indices_)
00064 {
00065 sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
00066 if (approximate_sync_)
00067 sync_input_hull_indices_a_->connectInput (sub_input_filter_, sub_hull_filter_, sub_indices_filter_);
00068 else
00069 sync_input_hull_indices_e_->connectInput (sub_input_filter_, sub_hull_filter_, sub_indices_filter_);
00070 }
00071 else
00072 {
00073 sub_input_filter_.registerCallback (bind (&ExtractPolygonalPrismData::input_callback, this, _1));
00074
00075 if (approximate_sync_)
00076 sync_input_hull_indices_a_->connectInput (sub_input_filter_, sub_hull_filter_, nf_);
00077 else
00078 sync_input_hull_indices_e_->connectInput (sub_input_filter_, sub_hull_filter_, nf_);
00079 }
00080
00081 if (approximate_sync_)
00082 sync_input_hull_indices_a_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
00083 else
00084 sync_input_hull_indices_e_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
00085
00086
00087 pub_output_ = pnh_->advertise<PointIndices> ("output", max_queue_size_);
00088 }
00089
00091 void
00092 pcl_ros::ExtractPolygonalPrismData::config_callback (ExtractPolygonalPrismDataConfig &config, uint32_t level)
00093 {
00094 double height_min, height_max;
00095 impl_.getHeightLimits (height_min, height_max);
00096 if (height_min != config.height_min)
00097 {
00098 height_min = config.height_min;
00099 NODELET_DEBUG ("[%s::config_callback] Setting new minimum height to the planar model to: %f.", getName ().c_str (), height_min);
00100 impl_.setHeightLimits (height_min, height_max);
00101 }
00102 if (height_max != config.height_max)
00103 {
00104 height_max = config.height_max;
00105 NODELET_DEBUG ("[%s::config_callback] Setting new maximum height to the planar model to: %f.", getName ().c_str (), height_max);
00106 impl_.setHeightLimits (height_min, height_max);
00107 }
00108 }
00109
00111 void
00112 pcl_ros::ExtractPolygonalPrismData::input_hull_indices_callback (
00113 const PointCloudConstPtr &cloud,
00114 const PointCloudConstPtr &hull,
00115 const PointIndicesConstPtr &indices)
00116 {
00117
00118 if (pub_output_.getNumSubscribers () <= 0)
00119 return;
00120
00121
00122 pcl::PointIndices inliers;
00123 inliers.header = cloud->header;
00124
00125
00126 if (!isValid (cloud) || !isValid (hull, "planar_hull"))
00127 {
00128 NODELET_ERROR ("[%s::input_hull_indices_callback] Invalid input!", getName ().c_str ());
00129 pub_output_.publish (boost::make_shared<const pcl::PointIndices> (inliers));
00130 return;
00131 }
00132
00133 if (indices && !isValid (indices))
00134 {
00135 NODELET_ERROR ("[%s::input_hull_indices_callback] Invalid indices!", getName ().c_str ());
00136 pub_output_.publish (boost::make_shared<const pcl::PointIndices> (inliers));
00137 return;
00138 }
00139
00141 if (indices)
00142 NODELET_DEBUG ("[%s::input_indices_hull_callback]\n"
00143 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00144 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00145 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
00146 getName ().c_str (),
00147 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00148 hull->width * hull->height, pcl::getFieldsList (*hull).c_str (), hull->header.stamp.toSec (), hull->header.frame_id.c_str (), pnh_->resolveName ("planar_hull").c_str (),
00149 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
00150 else
00151 NODELET_DEBUG ("[%s::input_indices_hull_callback]\n"
00152 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00153 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
00154 getName ().c_str (),
00155 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00156 hull->width * hull->height, pcl::getFieldsList (*hull).c_str (), hull->header.stamp.toSec (), hull->header.frame_id.c_str (), pnh_->resolveName ("planar_hull").c_str ());
00158
00159 if (cloud->header.frame_id != hull->header.frame_id)
00160 {
00161 NODELET_DEBUG ("[%s::input_hull_callback] Planar hull has a different TF frame (%s) than the input point cloud (%s)! Using TF to transform.", getName ().c_str (), hull->header.frame_id.c_str (), cloud->header.frame_id.c_str ());
00162 PointCloud planar_hull;
00163 if (!pcl_ros::transformPointCloud (cloud->header.frame_id, *hull, planar_hull, tf_listener_))
00164 {
00165
00166 pub_output_.publish (boost::make_shared<const pcl::PointIndices> (inliers));
00167 return;
00168 }
00169 impl_.setInputPlanarHull (planar_hull.makeShared ());
00170 }
00171 else
00172 impl_.setInputPlanarHull (hull);
00173
00174 IndicesConstPtr indices_ptr;
00175 if (indices && !indices->header.frame_id.empty ())
00176 indices_ptr = boost::make_shared <std::vector<int> > (indices->indices);
00177
00178 impl_.setInputCloud (cloud);
00179 impl_.setIndices (indices_ptr);
00180
00181
00182 if (!cloud->points.empty ())
00183 impl_.segment (inliers);
00184
00185 inliers.header = cloud->header;
00186 pub_output_.publish (boost::make_shared<const PointIndices> (inliers));
00187 NODELET_DEBUG ("[%s::input_hull_callback] Publishing %zu indices.", getName ().c_str (), inliers.indices.size ());
00188 }
00189
00190 typedef pcl_ros::ExtractPolygonalPrismData ExtractPolygonalPrismData;
00191 PLUGINLIB_DECLARE_CLASS (pcl, ExtractPolygonalPrismData, ExtractPolygonalPrismData, nodelet::Nodelet);
00192