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_pcl_ros/normal_estimation_omp.h"
00038 #include <pcl/point_types.h>
00039 #include <pcl/features/normal_3d_omp.h>
00040 
00041 namespace jsk_pcl_ros
00042 {
00043   void NormalEstimationOMP::onInit()
00044   {
00045     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00046     DiagnosticNodelet::onInit();
00047     pnh_->param("number_of_threads", num_of_threads_, 0);
00048     NODELET_DEBUG_STREAM("num_of_threads: " << num_of_threads_);
00049     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00051       boost::bind (&NormalEstimationOMP::configCallback, this, _1, _2);
00052     srv_->setCallback (f);
00053     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00054     pub_with_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_with_xyz", 1);
00055     pub_latest_time_ = advertise<std_msgs::Float32>(
00056       *pnh_, "output/latest_time", 1);
00057     pub_average_time_ = advertise<std_msgs::Float32>(
00058       *pnh_, "output/average_time", 1);
00059     onInitPostProcess();
00060   }
00061 
00062   void NormalEstimationOMP::subscribe()
00063   {
00064     sub_ = pnh_->subscribe("input", 1, &NormalEstimationOMP::estimate, this);
00065   }
00066 
00067   void NormalEstimationOMP::unsubscribe()
00068   {
00069     sub_.shutdown();
00070   }
00071 
00072   void NormalEstimationOMP::configCallback(
00073     Config& config, uint32_t level)
00074   {
00075     boost::mutex::scoped_lock lock(mutex_);
00076     k_ = config.k_search;
00077     search_radius_ = config.radius_search;
00078   }
00079 
00080   void NormalEstimationOMP::estimate(
00081     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00082   {
00083     boost::mutex::scoped_lock lock(mutex_);
00084     vital_checker_->poke();
00085     {
00086       jsk_recognition_utils::ScopedWallDurationReporter r
00087         = timer_.reporter(pub_latest_time_, pub_average_time_);
00088       pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00089         cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00090       pcl::fromROSMsg(*cloud_msg, *cloud);
00091       pcl::NormalEstimationOMP<pcl::PointXYZRGB, pcl::Normal> impl(num_of_threads_);
00092       impl.setInputCloud(cloud);
00093       pcl::search::KdTree<pcl::PointXYZRGB>::Ptr
00094         tree (new pcl::search::KdTree<pcl::PointXYZRGB> ());
00095       impl.setSearchMethod (tree);
00096       impl.setKSearch(k_);
00097       impl.setRadiusSearch(search_radius_);
00098       pcl::PointCloud<pcl::Normal>::Ptr
00099         normal_cloud(new pcl::PointCloud<pcl::Normal>);
00100       impl.compute(*normal_cloud);
00101 
00102       sensor_msgs::PointCloud2 ros_normal_cloud;
00103       pcl::toROSMsg(*normal_cloud, ros_normal_cloud);
00104       ros_normal_cloud.header = cloud_msg->header;
00105       pub_.publish(ros_normal_cloud);
00106 
00107       pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
00108         normal_xyz(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00109       normal_xyz->points.resize(cloud->points.size());
00110       for (size_t i = 0; i < normal_xyz->points.size(); i++) {
00111         pcl::PointXYZRGBNormal p;
00112         p.x = cloud->points[i].x;
00113         p.y = cloud->points[i].y;
00114         p.z = cloud->points[i].z;
00115         p.rgb = cloud->points[i].rgb;
00116         p.normal_x = normal_cloud->points[i].normal_x;
00117         p.normal_y = normal_cloud->points[i].normal_y;
00118         p.normal_z = normal_cloud->points[i].normal_z;
00119         normal_xyz->points[i] = p;
00120       }
00121 
00122       sensor_msgs::PointCloud2 ros_normal_xyz_cloud;
00123       pcl::toROSMsg(*normal_xyz, ros_normal_xyz_cloud);
00124       ros_normal_xyz_cloud.header = cloud_msg->header;
00125       pub_with_xyz_.publish(ros_normal_xyz_cloud);
00126     }
00127   }
00128 }
00129 
00130 #include <pluginlib/class_list_macros.h>
00131 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::NormalEstimationOMP, nodelet::Nodelet);