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);
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);
111 ne.setInputCloud(input);
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;
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;
132 concat->header = input->header;
133 sensor_msgs::PointCloud2 ros_output_with_xyz;
virtual void compute(const sensor_msgs::PointCloud2::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
double normal_smoothing_size_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::NormalEstimationIntegralImage, nodelet::Nodelet)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
void output(int index, double value)
jsk_pcl_ros::NormalEstimationIntegralImageConfig Config
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
virtual void unsubscribe()
double max_depth_change_factor_
ros::Subscriber sub_input_
bool border_policy_ignore_
#define NODELET_FATAL(...)
bool depth_dependent_smoothing_
ros::Publisher pub_with_xyz_
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_