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 #include "jsk_pcl_ros/keypoints_publisher.h"
00036 #include <pluginlib/class_list_macros.h>
00037 
00038 #include <pcl_conversions/pcl_conversions.h>
00039 #include <message_filters/subscriber.h>
00040 #include <message_filters/time_synchronizer.h>
00041 
00042 #include <pcl/range_image/range_image_planar.h>
00043 #include <pcl/keypoints/narf_keypoint.h>
00044 #include <pcl/features/range_image_border_extractor.h>
00045 
00046 namespace jsk_pcl_ros
00047 {
00048   void KeypointsPublisher::onInit(void)
00049   {
00050     ConnectionBasedNodelet::onInit();
00051     
00052     input_.reset(new pcl::PointCloud<pcl::PointXYZ>);
00053     keypoints_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "nerf_keypoints", 10);
00054     
00055     onInitPostProcess();
00056   }
00057 
00058   void KeypointsPublisher::subscribe()
00059   {
00060     sub_input_ = pnh_->subscribe("input", 1, &KeypointsPublisher::inputCallback, this);
00061   }
00062 
00063   void KeypointsPublisher::unsubscribe()
00064   {
00065     sub_input_.shutdown();
00066   }
00067   
00068   void KeypointsPublisher::inputCallback(const sensor_msgs::PointCloud2::ConstPtr& input)
00069   {
00070     pcl::fromROSMsg(*input, *input_);
00071     input_header_ = input->header;
00072     extractKeypoints(input_);
00073   }
00074 
00075   void KeypointsPublisher::extractKeypoints(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
00076   {
00077     pcl::RangeImagePlanar rip;
00078     pcl::RangeImageBorderExtractor ribe;
00079     rip.createFromPointCloudWithFixedSize(*cloud, cloud->width, cloud->height,
00080                                           319.5, 239.5, 525.0, 525.0, static_cast<Eigen::Affine3f>(Eigen::Translation3f(0.0, 0.0, 0.0)));
00081     rip.setUnseenToMaxRange();
00082     ROS_INFO_STREAM("Built range image " << rip.width << "x" << rip.height);
00083 
00084     pcl::NarfKeypoint narf;
00085     narf.setRangeImageBorderExtractor(&ribe);
00086     narf.setRangeImage(&rip);
00087     narf.getParameters().support_size = 0.1;
00088     narf.getParameters().use_recursive_scale_reduction = true;
00089     narf.getParameters().calculate_sparse_interest_image = true;
00090 
00091     pcl::PointCloud<int> indices;
00092     narf.compute(indices);
00093 
00094     pcl::PointCloud<pcl::PointXYZ> result;
00095     for (int i = 0; i < indices.size(); ++i) {
00096       result.push_back(cloud->at(indices[i]));
00097     }
00098     sensor_msgs::PointCloud2 resMsg;
00099     pcl::toROSMsg(result, resMsg);
00100     resMsg.header = input_header_;
00101     keypoints_pub_.publish(resMsg);
00102   }
00103   
00104 }
00105 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::KeypointsPublisher, nodelet::Nodelet);