normal_estimation_omp_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <pcl/point_types.h>
39 #include <pcl/features/normal_3d_omp.h>
40 
41 namespace jsk_pcl_ros
42 {
44  {
45  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
46  DiagnosticNodelet::onInit();
47  pnh_->param("number_of_threads", num_of_threads_, 0);
48  NODELET_DEBUG_STREAM("num_of_threads: " << num_of_threads_);
49  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50  typename dynamic_reconfigure::Server<Config>::CallbackType f =
51  boost::bind (&NormalEstimationOMP::configCallback, this, _1, _2);
52  srv_->setCallback (f);
53  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
54  pub_with_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_with_xyz", 1);
55  pub_latest_time_ = advertise<std_msgs::Float32>(
56  *pnh_, "output/latest_time", 1);
57  pub_average_time_ = advertise<std_msgs::Float32>(
58  *pnh_, "output/average_time", 1);
60  }
61 
63  {
64  sub_ = pnh_->subscribe("input", 1, &NormalEstimationOMP::estimate, this);
65  }
66 
68  {
69  sub_.shutdown();
70  }
71 
73  Config& config, uint32_t level)
74  {
75  boost::mutex::scoped_lock lock(mutex_);
76  k_ = config.k_search;
77  search_radius_ = config.radius_search;
78  }
79 
81  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
82  {
83  boost::mutex::scoped_lock lock(mutex_);
84  vital_checker_->poke();
85  {
88  pcl::PointCloud<pcl::PointXYZRGB>::Ptr
89  cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
90  pcl::fromROSMsg(*cloud_msg, *cloud);
91  pcl::NormalEstimationOMP<pcl::PointXYZRGB, pcl::Normal> impl(num_of_threads_);
92  impl.setInputCloud(cloud);
93  pcl::search::KdTree<pcl::PointXYZRGB>::Ptr
94  tree (new pcl::search::KdTree<pcl::PointXYZRGB> ());
95  impl.setSearchMethod (tree);
96  impl.setKSearch(k_);
97  impl.setRadiusSearch(search_radius_);
98  pcl::PointCloud<pcl::Normal>::Ptr
99  normal_cloud(new pcl::PointCloud<pcl::Normal>);
100  impl.compute(*normal_cloud);
101 
102  sensor_msgs::PointCloud2 ros_normal_cloud;
103  pcl::toROSMsg(*normal_cloud, ros_normal_cloud);
104  ros_normal_cloud.header = cloud_msg->header;
105  pub_.publish(ros_normal_cloud);
106 
107  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
108  normal_xyz(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
109  normal_xyz->points.resize(cloud->points.size());
110  for (size_t i = 0; i < normal_xyz->points.size(); i++) {
111  pcl::PointXYZRGBNormal p;
112  p.x = cloud->points[i].x;
113  p.y = cloud->points[i].y;
114  p.z = cloud->points[i].z;
115  p.rgb = cloud->points[i].rgb;
116  p.normal_x = normal_cloud->points[i].normal_x;
117  p.normal_y = normal_cloud->points[i].normal_y;
118  p.normal_z = normal_cloud->points[i].normal_z;
119  normal_xyz->points[i] = p;
120  }
121 
122  sensor_msgs::PointCloud2 ros_normal_xyz_cloud;
123  pcl::toROSMsg(*normal_xyz, ros_normal_xyz_cloud);
124  ros_normal_xyz_cloud.header = cloud_msg->header;
125  pub_with_xyz_.publish(ros_normal_xyz_cloud);
126  }
127  }
128 }
129 
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void publish(const boost::shared_ptr< M > &message) const
virtual ScopedWallDurationReporter reporter()
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void configCallback(Config &config, uint32_t level)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::NormalEstimationOMP, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
#define NODELET_DEBUG_STREAM(...)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
p
jsk_recognition_utils::WallDurationTimer timer_
cloud


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47