42 #include <pcl/range_image/range_image_planar.h>
43 #include <pcl/keypoints/narf_keypoint.h>
44 #include <pcl/features/range_image_border_extractor.h>
50 ConnectionBasedNodelet::onInit();
52 input_.reset(
new pcl::PointCloud<pcl::PointXYZ>);
53 keypoints_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"nerf_keypoints", 10);
77 pcl::RangeImagePlanar rip;
78 pcl::RangeImageBorderExtractor ribe;
79 rip.createFromPointCloudWithFixedSize(*cloud,
cloud->width,
cloud->height,
80 319.5, 239.5, 525.0, 525.0,
static_cast<Eigen::Affine3f
>(Eigen::Translation3f(0.0, 0.0, 0.0)));
81 rip.setUnseenToMaxRange();
82 ROS_INFO_STREAM(
"Built range image " << rip.width <<
"x" << rip.height);
84 pcl::NarfKeypoint narf;
85 narf.setRangeImageBorderExtractor(&ribe);
86 narf.setRangeImage(&rip);
87 narf.getParameters().support_size = 0.1;
88 narf.getParameters().use_recursive_scale_reduction =
true;
89 narf.getParameters().calculate_sparse_interest_image =
true;
91 pcl::PointCloud<int> indices;
92 narf.compute(indices);
94 pcl::PointCloud<pcl::PointXYZ>
result;
95 for (
int i = 0;
i < indices.size(); ++
i) {
98 sensor_msgs::PointCloud2 resMsg;