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 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00048 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00049 boost::bind (&NormalEstimationOMP::configCallback, this, _1, _2);
00050 srv_->setCallback (f);
00051 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00052 pub_with_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_with_xyz", 1);
00053 }
00054
00055 void NormalEstimationOMP::subscribe()
00056 {
00057 sub_ = pnh_->subscribe("input", 1, &NormalEstimationOMP::estimate, this);
00058 }
00059
00060 void NormalEstimationOMP::unsubscribe()
00061 {
00062 sub_.shutdown();
00063 }
00064
00065 void NormalEstimationOMP::configCallback(
00066 Config& config, uint32_t level)
00067 {
00068 boost::mutex::scoped_lock lock(mutex_);
00069 k_ = config.k_search;
00070 search_radius_ = config.radius_search;
00071 }
00072
00073 void NormalEstimationOMP::estimate(
00074 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00075 {
00076 boost::mutex::scoped_lock lock(mutex_);
00077 vital_checker_->poke();
00078 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00079 cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00080 pcl::fromROSMsg(*cloud_msg, *cloud);
00081 pcl::NormalEstimationOMP<pcl::PointXYZRGB, pcl::Normal> impl;
00082 impl.setInputCloud(cloud);
00083 pcl::search::KdTree<pcl::PointXYZRGB>::Ptr
00084 tree (new pcl::search::KdTree<pcl::PointXYZRGB> ());
00085 impl.setSearchMethod (tree);
00086 impl.setKSearch(k_);
00087 impl.setRadiusSearch(search_radius_);
00088 pcl::PointCloud<pcl::Normal>::Ptr
00089 normal_cloud(new pcl::PointCloud<pcl::Normal>);
00090 impl.compute(*normal_cloud);
00091
00092 sensor_msgs::PointCloud2 ros_normal_cloud;
00093 pcl::toROSMsg(*normal_cloud, ros_normal_cloud);
00094 ros_normal_cloud.header = cloud_msg->header;
00095 pub_.publish(ros_normal_cloud);
00096
00097 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
00098 normal_xyz(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00099 normal_xyz->points.resize(cloud->points.size());
00100 for (size_t i = 0; i < normal_xyz->points.size(); i++) {
00101 pcl::PointXYZRGBNormal p;
00102 p.x = cloud->points[i].x;
00103 p.y = cloud->points[i].y;
00104 p.z = cloud->points[i].z;
00105 p.normal_x = normal_cloud->points[i].normal_x;
00106 p.normal_y = normal_cloud->points[i].normal_y;
00107 p.normal_z = normal_cloud->points[i].normal_z;
00108 normal_xyz->points[i] = p;
00109 }
00110
00111 sensor_msgs::PointCloud2 ros_normal_xyz_cloud;
00112 pcl::toROSMsg(*normal_xyz, ros_normal_xyz_cloud);
00113 ros_normal_xyz_cloud.header = cloud_msg->header;
00114 pub_with_xyz_.publish(ros_normal_xyz_cloud);
00115 }
00116 }
00117
00118 #include <pluginlib/class_list_macros.h>
00119 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::NormalEstimationOMP, nodelet::Nodelet);