keypoints_publisher_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Yuki Furuta and JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49