Go to the documentation of this file.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 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_recognition_utils/pcl_conversion_util.h"
00038 #include "jsk_pcl_ros_utils/polygon_points_sampler.h"
00039 
00040 namespace jsk_pcl_ros_utils
00041 {
00042   void PolygonPointsSampler::onInit()
00043   {
00044     DiagnosticNodelet::onInit();
00045     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00046     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00047       boost::bind (&PolygonPointsSampler::configCallback, this, _1, _2);
00048     srv_->setCallback (f);
00049 
00050     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00051     pub_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_xyz", 1);
00052 
00053     onInitPostProcess();
00054   }
00055 
00056   void PolygonPointsSampler::subscribe()
00057   {
00058     sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
00059     sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
00060     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00061     sync_->connectInput(sub_polygons_, sub_coefficients_);
00062     sync_->registerCallback(boost::bind(&PolygonPointsSampler::sample, this, _1, _2));
00063   }
00064 
00065   void PolygonPointsSampler::unsubscribe()
00066   {
00067     sub_polygons_.unsubscribe();
00068     sub_coefficients_.unsubscribe();
00069   }
00070 
00071   bool PolygonPointsSampler::isValidMessage(
00072     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00073     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00074   {
00075     if (polygon_msg->polygons.size() == 0) {
00076       NODELET_DEBUG("empty polygons");
00077       return false;
00078     }
00079     if (coefficients_msg->coefficients.size() != polygon_msg->polygons.size()) {
00080       NODELET_ERROR("The size of coefficients and polygons are not same");
00081       return false;
00082     }
00083 
00084     std::string frame_id = polygon_msg->header.frame_id;
00085     for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
00086       if (frame_id != polygon_msg->polygons[i].header.frame_id) {
00087         NODELET_ERROR("Frame id of polygon is not same: %s, %s",
00088                       frame_id.c_str(),
00089                       polygon_msg->polygons[i].header.frame_id.c_str());
00090         return false;
00091       }
00092     }
00093     for (size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
00094       if (frame_id != coefficients_msg->coefficients[i].header.frame_id) {
00095         NODELET_ERROR("Frame id of coefficient is not same: %s, %s",
00096                       frame_id.c_str(),
00097                       coefficients_msg->coefficients[i].header.frame_id.c_str());
00098         return false;
00099       }
00100     }
00101     return true;
00102   }
00103   
00104   void PolygonPointsSampler::sample(
00105     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00106     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00107   {
00108     boost::mutex::scoped_lock lock(mutex_);
00109     vital_checker_->poke();
00110     
00111     if (!isValidMessage(polygon_msg, coefficients_msg)) {
00112       return;
00113     }
00114     
00115     pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00116     pcl::PointCloud<pcl::PointXYZ>::Ptr xyz_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00117     for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
00118       jsk_recognition_utils::Polygon polygon
00119         = jsk_recognition_utils::Polygon::fromROSMsg(polygon_msg->polygons[i].polygon);
00120       pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr one_cloud
00121         = polygon.samplePoints<pcl::PointXYZRGBNormal>(grid_size_);
00122       pcl::PointCloud<pcl::PointXYZ> one_xyz_cloud;
00123       one_xyz_cloud.points.resize(one_cloud->points.size());
00124       for (size_t i = 0; i < one_cloud->points.size(); i++) {
00125         pcl::PointXYZ p;
00126         p.getVector3fMap() = one_cloud->points[i].getVector3fMap();
00127         one_xyz_cloud.points[i] = p;
00128       }
00129       *xyz_cloud = *xyz_cloud + one_xyz_cloud;
00130       *cloud = *cloud + *one_cloud;
00131     }
00132     sensor_msgs::PointCloud2 ros_cloud;
00133     pcl::toROSMsg(*cloud, ros_cloud);
00134     ros_cloud.header = polygon_msg->header;
00135     pub_.publish(ros_cloud);
00136     sensor_msgs::PointCloud2 ros_xyz_cloud;
00137     pcl::toROSMsg(*xyz_cloud, ros_xyz_cloud);
00138     ros_xyz_cloud.header = polygon_msg->header;
00139     pub_xyz_.publish(ros_xyz_cloud);
00140   }
00141 
00142   
00143   void PolygonPointsSampler::configCallback(Config& config, uint32_t level)
00144   {
00145     boost::mutex::scoped_lock lock(mutex_);
00146     grid_size_ = config.grid_size;
00147   }
00148 }
00149 
00150 #include <pluginlib/class_list_macros.h>
00151 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PolygonPointsSampler, nodelet::Nodelet);