39 #include <pcl/features/integral_image_normal.h>
46 ConnectionBasedNodelet::onInit();
48 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
49 dynamic_reconfigure::Server<Config>::CallbackType
f =
51 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);
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;
88 ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
91 ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
94 ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
102 ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal>::BORDER_POLICY_IGNORE);
105 ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal>::BORDER_POLICY_MIRROR);
113 sensor_msgs::PointCloud2 ros_output;
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;
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;
133 sensor_msgs::PointCloud2 ros_output_with_xyz;