normal_estimation_integral_image_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and 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/or 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 
38 
39 #include <pcl/features/integral_image_normal.h>
40 
41 
42 namespace jsk_pcl_ros
43 {
45  {
46  ConnectionBasedNodelet::onInit();
47 
48  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49  dynamic_reconfigure::Server<Config>::CallbackType f =
50  boost::bind (&NormalEstimationIntegralImage::configCallback, this, _1, _2);
51  srv_->setCallback (f);
52 
53  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
54  pub_with_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_with_xyz", 1);
55 
56  onInitPostProcess();
57  }
58 
60  {
61  sub_input_ = pnh_->subscribe("input", 1, &NormalEstimationIntegralImage::compute, this);
62  }
63 
65  {
67  }
68 
69  void NormalEstimationIntegralImage::configCallback(Config& config, uint32_t level)
70  {
71  boost::mutex::scoped_lock lock(mutex_);
72  max_depth_change_factor_ = config.max_depth_change_factor;
73  normal_smoothing_size_ = config.normal_smoothing_size;
74  depth_dependent_smoothing_ = config.depth_dependent_smoothing;
75  estimation_method_ = config.estimation_method;
76  border_policy_ignore_ = config.border_policy_ignore;
77  }
78 
79  void NormalEstimationIntegralImage::compute(const sensor_msgs::PointCloud2::ConstPtr& msg)
80  {
81  boost::mutex::scoped_lock lock(mutex_);
82 
83  pcl::PointCloud<pcl::PointXYZRGB>::Ptr input(new pcl::PointCloud<pcl::PointXYZRGB>());
85  pcl::PointCloud<pcl::Normal> output;
86  pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal> ne;
87  if (estimation_method_ == 0) {
88  ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
89  }
90  else if (estimation_method_ == 1) {
91  ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
92  }
93  else if (estimation_method_ == 2) {
94  ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
95  }
96  else {
97  NODELET_FATAL("unknown estimation method: %d", estimation_method_);
98  return;
99  }
100 
102  ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal>::BORDER_POLICY_IGNORE);
103  }
104  else {
105  ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal>::BORDER_POLICY_MIRROR);
106  }
107 
108  ne.setMaxDepthChangeFactor(max_depth_change_factor_);
109  ne.setNormalSmoothingSize(normal_smoothing_size_);
110  ne.setDepthDependentSmoothing(depth_dependent_smoothing_);
111  ne.setInputCloud(input);
112  ne.compute(output);
113  sensor_msgs::PointCloud2 ros_output;
114  pcl::toROSMsg(output, ros_output);
115  pub_.publish(ros_output);
116 
117  // concatenate
118  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr concat(new pcl::PointCloud<pcl::PointXYZRGBNormal>());
119  concat->points.resize(output.points.size());
120  for (size_t i = 0; i < output.points.size(); i++) {
121  pcl::PointXYZRGBNormal point;
122  point.x = input->points[i].x;
123  point.y = input->points[i].y;
124  point.z = input->points[i].z;
125  point.rgb = input->points[i].rgb;
126  point.normal_x = output.points[i].normal_x;
127  point.normal_y = output.points[i].normal_y;
128  point.normal_z = output.points[i].normal_z;
129  point.curvature = output.points[i].curvature;
130  concat->points[i] = point;
131  }
132  concat->header = input->header;
133  sensor_msgs::PointCloud2 ros_output_with_xyz;
134  pcl::toROSMsg(*concat, ros_output_with_xyz);
135  pub_with_xyz_.publish(ros_output_with_xyz);
136  }
137 
138 }
139 
140 
NODELET_FATAL
#define NODELET_FATAL(...)
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
jsk_pcl_ros::NormalEstimationIntegralImage::subscribe
virtual void subscribe()
Definition: normal_estimation_integral_image_nodelet.cpp:91
i
int i
concat
char * concat()
jsk_pcl_ros::NormalEstimationIntegralImage::unsubscribe
virtual void unsubscribe()
Definition: normal_estimation_integral_image_nodelet.cpp:96
jsk_pcl_ros::NormalEstimationIntegralImage::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: normal_estimation_integral_image_nodelet.cpp:101
ros::Subscriber::shutdown
void shutdown()
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_pcl_ros::NormalEstimationIntegralImage::max_depth_change_factor_
double max_depth_change_factor_
Definition: normal_estimation_integral_image.h:125
jsk_pcl_ros::NormalEstimationIntegralImage::depth_dependent_smoothing_
bool depth_dependent_smoothing_
Definition: normal_estimation_integral_image.h:124
class_list_macros.h
jsk_pcl_ros::NormalEstimationIntegralImage::sub_input_
ros::Subscriber sub_input_
Definition: normal_estimation_integral_image.h:119
jsk_pcl_ros
Definition: add_color_from_image.h:51
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::NormalEstimationIntegralImage, nodelet::Nodelet)
jsk_pcl_ros::NormalEstimationIntegralImage::border_policy_ignore_
bool border_policy_ignore_
Definition: normal_estimation_integral_image.h:127
jsk_pcl_ros::NormalEstimationIntegralImage::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: normal_estimation_integral_image.h:128
point
std::chrono::system_clock::time_point point
jsk_pcl_ros::NormalEstimationIntegralImage::mutex_
boost::mutex mutex_
Definition: normal_estimation_integral_image.h:122
jsk_pcl_ros::NormalEstimationIntegralImage::pub_with_xyz_
ros::Publisher pub_with_xyz_
Definition: normal_estimation_integral_image.h:121
jsk_pcl_ros::NormalEstimationIntegralImage::compute
virtual void compute(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: normal_estimation_integral_image_nodelet.cpp:111
jsk_pcl_ros::NormalEstimationIntegralImage::normal_smoothing_size_
double normal_smoothing_size_
Definition: normal_estimation_integral_image.h:126
nodelet::Nodelet
jsk_pcl_ros::NormalEstimationIntegralImage::onInit
virtual void onInit()
Definition: normal_estimation_integral_image_nodelet.cpp:76
normal_estimation_integral_image.h
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::NormalEstimationIntegralImage::estimation_method_
int estimation_method_
Definition: normal_estimation_integral_image.h:123
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
jsk_pcl_ros::NormalEstimationIntegralImage::pub_
ros::Publisher pub_
Definition: normal_estimation_integral_image.h:120
config
config
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::NormalEstimationIntegralImage
Definition: normal_estimation_integral_image.h:81


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:12:12