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/organize_pointcloud.h"
00037 #include <pluginlib/class_list_macros.h>
00038 
00039 #include <pcl/common/centroid.h>
00040 
00041 namespace jsk_pcl_ros
00042 {
00043   void OrganizePointCloud::extract(const sensor_msgs::PointCloud2ConstPtr &input)
00044   {
00045     
00046     ROS_INFO_STREAM("received input clouds, convert range image, resolution: " << angular_resolution << ", width(deg): " << angle_width << ", height(deg):" << angle_height << ", min_points:" << min_points);
00047 
00048     if ( input->width < min_points ) return;
00049 
00050     pcl::PointCloud<pcl::PointXYZ> pointCloud;
00051     pcl::fromROSMsg(*input, pointCloud);
00052 
00053     
00054     float angularResolution = (float) (angular_resolution * (M_PI/180.0f));  
00055     float maxAngleWidth     = (float) (angle_width * (M_PI/180.0f));  
00056     float maxAngleHeight    = (float) (angle_height * (M_PI/180.0f));  
00057     Eigen::Affine3f sensorPose = (Eigen::Affine3f)Eigen::Translation3f(0.0f, 0.0f, 0.0f);
00058     pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
00059     float noiseLevel=0.00;
00060     float minRange = 0.0f;
00061     int borderSize = 1;
00062 
00063     pcl::RangeImage rangeImage;
00064     rangeImage.createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight,
00065                                     sensorPose, coordinate_frame, noiseLevel, minRange, borderSize);
00066     ROS_INFO_STREAM("input image size " << input->width << " x " << input->height << "(=" << input->width * input->height << ")");
00067     ROS_INFO_STREAM("output image size " << rangeImage.width << " x " << rangeImage.height << "(=" << rangeImage.width * rangeImage.height << ")");
00068     ROS_DEBUG_STREAM(rangeImage);
00069 
00070     sensor_msgs::PointCloud2 out;
00071     pcl::toROSMsg(rangeImage, out);
00072     out.header = input->header;
00073     pub_.publish(out);
00074   }
00075 
00076   void OrganizePointCloud::onInit(void)
00077   {
00078     ConnectionBasedNodelet::onInit();
00079     
00080     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00081     pnh_->param<double>("angular_resolution", angular_resolution, 1.0);
00082     pnh_->param<double>("angle_width", angle_width, 120.0);
00083     pnh_->param<double>("angle_height", angle_height, 90.0);
00084     pnh_->param<int>("min_points", min_points, 1000);
00085     onInitPostProcess();
00086   }
00087 
00088   void OrganizePointCloud::subscribe()
00089   {
00090     sub_ = pnh_->subscribe("input", 1, &OrganizePointCloud::extract, this);
00091   }
00092 
00093   void OrganizePointCloud::unsubscribe()
00094   {
00095     sub_.shutdown();
00096   }
00097 }
00098 
00099 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::OrganizePointCloud, nodelet::Nodelet);
00100