39 #include <pcl/common/centroid.h> 
   50     pcl::PointCloud<pcl::PointXYZ> pointCloud;
 
   55     float maxAngleWidth     = (float) (
angle_width * (M_PI/180.0
f));  
 
   56     float maxAngleHeight    = (float) (
angle_height * (M_PI/180.0
f));  
 
   57     Eigen::Affine3f sensorPose = (Eigen::Affine3f)Eigen::Translation3f(0.0
f, 0.0
f, 0.0
f);
 
   58     pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
 
   59     float noiseLevel=0.00;
 
   60     float minRange = 0.0f;
 
   63     pcl::RangeImage rangeImage;
 
   64     rangeImage.createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight,
 
   65                                     sensorPose, coordinate_frame, noiseLevel, minRange, borderSize);
 
   67     ROS_INFO_STREAM(
"output image size " << rangeImage.width << 
" x " << rangeImage.height << 
"(=" << rangeImage.width * rangeImage.height << 
")");
 
   70     sensor_msgs::PointCloud2 out;
 
   72     out.header = 
input->header;
 
   78     ConnectionBasedNodelet::onInit();
 
   80     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, 
"output", 1);
 
   82     pnh_->param<
double>(
"angle_width", 
angle_width, 120.0);
 
   84     pnh_->param<
int>(
"min_points", 
min_points, 1000);