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 #include "jsk_pcl_ros/normal_estimation_integral_image.h"
00037 #include <pluginlib/class_list_macros.h>
00038
00039 #include <pcl/features/integral_image_normal.h>
00040
00041
00042 namespace jsk_pcl_ros
00043 {
00044 void NormalEstimationIntegralImage::onInit()
00045 {
00046 ConnectionBasedNodelet::onInit();
00047
00048 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00049 dynamic_reconfigure::Server<Config>::CallbackType f =
00050 boost::bind (&NormalEstimationIntegralImage::configCallback, this, _1, _2);
00051 srv_->setCallback (f);
00052
00053 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00054 pub_with_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_with_xyz", 1);
00055
00056 onInitPostProcess();
00057 }
00058
00059 void NormalEstimationIntegralImage::subscribe()
00060 {
00061 sub_input_ = pnh_->subscribe("input", 1, &NormalEstimationIntegralImage::compute, this);
00062 }
00063
00064 void NormalEstimationIntegralImage::unsubscribe()
00065 {
00066 sub_input_.shutdown();
00067 }
00068
00069 void NormalEstimationIntegralImage::configCallback(Config& config, uint32_t level)
00070 {
00071 boost::mutex::scoped_lock lock(mutex_);
00072 max_depth_change_factor_ = config.max_depth_change_factor;
00073 normal_smoothing_size_ = config.normal_smoothing_size;
00074 depth_dependent_smoothing_ = config.depth_dependent_smoothing;
00075 estimation_method_ = config.estimation_method;
00076 border_policy_ignore_ = config.border_policy_ignore;
00077 }
00078
00079 void NormalEstimationIntegralImage::compute(const sensor_msgs::PointCloud2::ConstPtr& msg)
00080 {
00081 boost::mutex::scoped_lock lock(mutex_);
00082
00083 pcl::PointCloud<pcl::PointXYZRGB>::Ptr input(new pcl::PointCloud<pcl::PointXYZRGB>());
00084 pcl::fromROSMsg(*msg, *input);
00085 pcl::PointCloud<pcl::Normal> output;
00086 pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal> ne;
00087 if (estimation_method_ == 0) {
00088 ne.setNormalEstimationMethod (ne.AVERAGE_3D_GRADIENT);
00089 }
00090 else if (estimation_method_ == 1) {
00091 ne.setNormalEstimationMethod (ne.COVARIANCE_MATRIX);
00092 }
00093 else if (estimation_method_ == 2) {
00094 ne.setNormalEstimationMethod (ne.AVERAGE_DEPTH_CHANGE);
00095 }
00096 else {
00097 NODELET_FATAL("unknown estimation method: %d", estimation_method_);
00098 return;
00099 }
00100
00101 if (border_policy_ignore_) {
00102 ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal>::BORDER_POLICY_IGNORE);
00103 }
00104 else {
00105 ne.setBorderPolicy(pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::Normal>::BORDER_POLICY_MIRROR);
00106 }
00107
00108 ne.setMaxDepthChangeFactor(max_depth_change_factor_);
00109 ne.setNormalSmoothingSize(normal_smoothing_size_);
00110 ne.setDepthDependentSmoothing(depth_dependent_smoothing_);
00111 ne.setInputCloud(input);
00112 ne.compute(output);
00113 sensor_msgs::PointCloud2 ros_output;
00114 pcl::toROSMsg(output, ros_output);
00115 pub_.publish(ros_output);
00116
00117
00118 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr concat(new pcl::PointCloud<pcl::PointXYZRGBNormal>());
00119 concat->points.resize(output.points.size());
00120 for (size_t i = 0; i < output.points.size(); i++) {
00121 pcl::PointXYZRGBNormal point;
00122 point.x = input->points[i].x;
00123 point.y = input->points[i].y;
00124 point.z = input->points[i].z;
00125 point.rgb = input->points[i].rgb;
00126 point.normal_x = output.points[i].normal_x;
00127 point.normal_y = output.points[i].normal_y;
00128 point.normal_z = output.points[i].normal_z;
00129 point.curvature = output.points[i].curvature;
00130 concat->points[i] = point;
00131 }
00132 concat->header = input->header;
00133 sensor_msgs::PointCloud2 ros_output_with_xyz;
00134 pcl::toROSMsg(*concat, ros_output_with_xyz);
00135 pub_with_xyz_.publish(ros_output_with_xyz);
00136 }
00137
00138 }
00139
00140
00141 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::NormalEstimationIntegralImage,
00142 nodelet::Nodelet);