colorize_segmented_RF_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, yuto_inagaki and JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 #include <jsk_topic_tools/log_utils.h>
00035 #include "jsk_pcl_ros/colorize_segmented_RF.h"
00036 #include <pluginlib/class_list_macros.h>
00037 
00038 namespace jsk_pcl_ros
00039 {
00040   void ColorizeRandomForest::onInit(void)
00041   {
00042     // not implemented yet
00043     PCLNodelet::onInit();
00044     sub_input_ = pnh_->subscribe("input", 1, &ColorizeRandomForest::extract, this);
00045 
00046     pub_ = pnh_->advertise<sensor_msgs::PointCloud2>("cloth_result", 1);
00047     pub2_ = pnh_->advertise<sensor_msgs::PointCloud2>("noncloth_result", 1);
00048 
00049     srand(time(NULL));
00050 
00051     double tmp_radius = 0.03, tmp_pass = 0.03, tmp_pass2 = 0.06;
00052     sum_num_ = 100;
00053     if (!pnh_->getParam("rs", tmp_radius))
00054       {
00055         JSK_ROS_WARN("~rs is not specified, set 1");
00056       }
00057     if (!pnh_->getParam("po", tmp_pass))
00058       {
00059         JSK_ROS_WARN("~po is not specified, set 1");
00060       }
00061     if (!pnh_->getParam("po2", tmp_pass2))
00062       {
00063         JSK_ROS_WARN("~po is not specified, set 1");
00064       }
00065     if (!pnh_->getParam("sum_num", sum_num_))
00066       {
00067         JSK_ROS_WARN("~sum_num is not specified, set 1");
00068       }
00069 
00070     radius_search_ = tmp_radius;
00071     pass_offset_ = tmp_pass;
00072     pass_offset2_ = tmp_pass2;
00073   }
00074 
00075   void ColorizeRandomForest::extract(const sensor_msgs::PointCloud2 pc)
00076   {
00077     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB> ());
00078 
00079     std::vector<int> indices;
00080     pcl::fromROSMsg(pc, *cloud);
00081     cloud->is_dense = false;
00082     pcl::removeNaNFromPointCloud(*cloud, *cloud, indices);
00083 
00084     pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>);
00085     tree->setInputCloud (cloud);
00086     pcl::PassThrough<pcl::PointXYZRGB> pass;
00087     pass.setInputCloud (cloud);
00088     pass.setFilterFieldName (std::string("z"));
00089     pass.setFilterLimits (0.0, 1.5);
00090     pass.filter (*cloud);
00091 
00092     std::vector<pcl::PointIndices> cluster_indices;
00093     pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> ec;
00094     ec.setClusterTolerance (0.025);
00095     ec.setMinClusterSize (200);
00096     ec.setMaxClusterSize (100000);
00097     ec.setSearchMethod (tree);
00098     ec.setInputCloud (cloud);
00099     ec.extract (cluster_indices);
00100 
00101     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloth_cloud_cluster (new pcl::PointCloud<pcl::PointXYZRGB>);
00102     pcl::PointCloud<pcl::PointXYZRGB>::Ptr noncloth_cloud_cluster (new pcl::PointCloud<pcl::PointXYZRGB>);
00103     int cluster_num = 0;
00104     for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
00105       {
00106         JSK_ROS_INFO("Calculate time %d / %ld", cluster_num  , cluster_indices.size());
00107         pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZRGB>);
00108         for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); pit++)
00109           cloud_cluster->points.push_back (cloud->points[*pit]);
00110         cloud_cluster->is_dense = true;
00111         cluster_num ++ ;
00112 
00113         pcl::NormalEstimation<pcl::PointXYZRGB, pcl::PointXYZRGBNormal> ne;
00114         pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB> ());
00115         pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud_normals (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00116         ne.setInputCloud (cloud_cluster);
00117         ne.setSearchMethod (tree);
00118         ne.setRadiusSearch (0.02);
00119         ne.compute (*cloud_normals);
00120 
00121         for (int cloud_index = 0; cloud_index <  cloud_normals->points.size(); cloud_index++){
00122           cloud_normals->points[cloud_index].x = cloud_cluster->points[cloud_index].x;
00123           cloud_normals->points[cloud_index].y = cloud_cluster->points[cloud_index].y;
00124           cloud_normals->points[cloud_index].z = cloud_cluster->points[cloud_index].z;
00125         }
00126 
00127         int result_counter=0, call_counter = 0;
00128         pcl::PointXYZRGBNormal max_pt,min_pt;
00129         pcl::getMinMax3D(*cloud_normals, min_pt, max_pt);
00130 
00131         for (int i = 0 ; i < 30; i++){
00132           double lucky = 0, lucky2 = 0;
00133           std::string axis("x"), other_axis("y");
00134           int rand_xy = rand()%2;
00135           if (rand_xy == 0){
00136             lucky = min_pt.x - pass_offset_ + (max_pt.x - min_pt.x - pass_offset_*2) * 1.0 * rand() / RAND_MAX;
00137             lucky2 = min_pt.y + (max_pt.y - min_pt.y) * 1.0 * rand() / RAND_MAX;
00138           }else {
00139             lucky = min_pt.y - pass_offset_ + (max_pt.y - min_pt.y - pass_offset_*2) * 1.0 * rand() / RAND_MAX;
00140             lucky2 = min_pt.x + (max_pt.x - min_pt.x) * 1.0 * rand() / RAND_MAX;
00141             axis = std::string("y");
00142             other_axis = std::string("x");
00143           }
00144           pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud_normals_pass (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00145           pcl::PassThrough<pcl::PointXYZRGBNormal> pass;
00146           pcl::IndicesPtr indices_x(new std::vector<int>());
00147           pass.setInputCloud (cloud_normals);
00148           pass.setFilterFieldName (axis);
00149           float small = std::min(lucky, lucky + pass_offset_);
00150           float large = std::max(lucky, lucky + pass_offset_);
00151           pass.setFilterLimits (small, large);
00152           pass.filter (*cloud_normals_pass);
00153           pass.setInputCloud (cloud_normals_pass);
00154           pass.setFilterFieldName (other_axis);
00155           float small2 = std::min(lucky2, lucky2 + pass_offset2_);
00156           float large2 = std::max(lucky2, lucky2 + pass_offset2_);
00157           pass.setFilterLimits (small2, large2);
00158           pass.filter (*cloud_normals_pass);
00159 
00160           std::vector<int> tmp_indices;
00161           pcl::removeNaNFromPointCloud(*cloud_normals_pass, *cloud_normals_pass, tmp_indices);
00162 
00163           if(cloud_normals_pass->points.size() == 0)
00164             continue;
00165 
00166           pcl::FPFHEstimationOMP<pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::FPFHSignature33> fpfh;
00167           pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGBNormal>);
00168           pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfhs (new pcl::PointCloud<pcl::FPFHSignature33> ());
00169           fpfh.setNumberOfThreads(8);
00170           fpfh.setInputCloud (cloud_normals_pass);
00171           fpfh.setInputNormals (cloud_normals_pass);
00172           fpfh.setSearchMethod (tree);
00173           fpfh.setRadiusSearch (radius_search_);
00174           fpfh.compute (*fpfhs);
00175 
00176           if((int)fpfhs->points.size() == 0)
00177             continue;
00178 
00179           std::vector<double> result;
00180           int target_id, max_value;
00181           if ((int)fpfhs->points.size() - sum_num_ - 1 < 1){
00182             target_id = 0;
00183             max_value = (int)fpfhs->points.size();
00184           }else{
00185             target_id = rand() % ((int)fpfhs->points.size() - sum_num_ - 1);
00186             max_value = target_id + sum_num_;
00187           }
00188 
00189           bool has_nan = false;
00190           for(int index = 0; index < 33; index++){
00191             float sum_hist_points = 0;
00192             for(int kndex = target_id; kndex < max_value;kndex++)
00193               {
00194                 sum_hist_points+=fpfhs->points[kndex].histogram[index];
00195               }
00196             result.push_back( sum_hist_points/sum_num_ );
00197           }
00198 
00199           for(int x = 0; x < result.size(); x ++){
00200             if(pcl_isnan(result[x]))
00201               has_nan = true;
00202           }
00203           if(has_nan)
00204             break;
00205 
00206           call_counter++;
00207           ros::ServiceClient client = pnh_->serviceClient<ml_classifiers::ClassifyData>("/predict");
00208           ml_classifiers::ClassifyData srv;
00209           ml_classifiers::ClassDataPoint class_data_point;
00210           class_data_point.point = result;
00211           srv.request.data.push_back(class_data_point);
00212           if(client.call(srv))
00213             if (atoi(srv.response.classifications[0].c_str()) == 0)
00214               result_counter += 1;
00215           JSK_ROS_INFO("response result : %s", srv.response.classifications[0].c_str());
00216         }
00217 
00218         if(result_counter >= call_counter / 2){
00219           JSK_ROS_INFO("Cloth %d / %d", result_counter, call_counter);
00220         }
00221         else{
00222           JSK_ROS_INFO("Not Cloth %d / %d", result_counter, call_counter);
00223         }
00224 
00225         for (int i = 0; i < cloud_cluster->points.size(); i++){
00226           if(result_counter >= call_counter / 2){
00227             cloth_cloud_cluster->points.push_back (cloud_cluster->points[i]);
00228           }
00229           else{
00230             noncloth_cloud_cluster->points.push_back (cloud_cluster->points[i]);
00231           }
00232         }
00233       }
00234     sensor_msgs::PointCloud2 cloth_pointcloud2;
00235     pcl::toROSMsg(*cloth_cloud_cluster, cloth_pointcloud2);
00236     cloth_pointcloud2.header = pc.header;
00237     cloth_pointcloud2.is_dense = false;
00238     pub_.publish(cloth_pointcloud2);
00239 
00240     sensor_msgs::PointCloud2 noncloth_pointcloud2;
00241     pcl::toROSMsg(*noncloth_cloud_cluster, noncloth_pointcloud2);
00242     noncloth_pointcloud2.header = pc.header;
00243     noncloth_pointcloud2.is_dense = false;
00244     pub2_.publish(noncloth_pointcloud2);
00245   }
00246 }
00247 
00248 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::ColorizeRandomForest, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47