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 }
00056
00057 void KeypointsPublisher::subscribe()
00058 {
00059 sub_input_ = pnh_->subscribe("input", 1, &KeypointsPublisher::inputCallback, this);
00060 }
00061
00062 void KeypointsPublisher::unsubscribe()
00063 {
00064 sub_input_.shutdown();
00065 }
00066
00067 void KeypointsPublisher::inputCallback(const sensor_msgs::PointCloud2::ConstPtr& input)
00068 {
00069 pcl::fromROSMsg(*input, *input_);
00070 input_header_ = input->header;
00071 extractKeypoints(input_);
00072 }
00073
00074 void KeypointsPublisher::extractKeypoints(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
00075 {
00076 pcl::RangeImagePlanar rip;
00077 pcl::RangeImageBorderExtractor ribe;
00078 rip.createFromPointCloudWithFixedSize(*cloud, cloud->width, cloud->height,
00079 319.5, 239.5, 525.0, 525.0, static_cast<Eigen::Affine3f>(Eigen::Translation3f(0.0, 0.0, 0.0)));
00080 rip.setUnseenToMaxRange();
00081 JSK_ROS_INFO_STREAM("Built range image " << rip.width << "x" << rip.height);
00082
00083 pcl::NarfKeypoint narf;
00084 narf.setRangeImageBorderExtractor(&ribe);
00085 narf.setRangeImage(&rip);
00086 narf.getParameters().support_size = 0.1;
00087 narf.getParameters().use_recursive_scale_reduction = true;
00088 narf.getParameters().calculate_sparse_interest_image = true;
00089
00090 pcl::PointCloud<int> indices;
00091 narf.compute(indices);
00092
00093 pcl::PointCloud<pcl::PointXYZ> result;
00094 for (int i = 0; i < indices.size(); ++i) {
00095 result.push_back(cloud->at(indices[i]));
00096 }
00097 sensor_msgs::PointCloud2 resMsg;
00098 pcl::toROSMsg(result, resMsg);
00099 resMsg.header = input_header_;
00100 keypoints_pub_.publish(resMsg);
00101 }
00102
00103 }
00104 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::KeypointsPublisher, nodelet::Nodelet);