keypoints_publisher_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Yuki Furuta and JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
37 
41 
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>
45 
46 namespace jsk_pcl_ros
47 {
49  {
50  ConnectionBasedNodelet::onInit();
51 
52  input_.reset(new pcl::PointCloud<pcl::PointXYZ>);
53  keypoints_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "nerf_keypoints", 10);
54 
55  onInitPostProcess();
56  }
57 
59  {
60  sub_input_ = pnh_->subscribe("input", 1, &KeypointsPublisher::inputCallback, this);
61  }
62 
64  {
66  }
67 
68  void KeypointsPublisher::inputCallback(const sensor_msgs::PointCloud2::ConstPtr& input)
69  {
71  input_header_ = input->header;
73  }
74 
75  void KeypointsPublisher::extractKeypoints(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
76  {
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);
83 
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;
90 
91  pcl::PointCloud<int> indices;
92  narf.compute(indices);
93 
94  pcl::PointCloud<pcl::PointXYZ> result;
95  for (int i = 0; i < indices.size(); ++i) {
96  result.push_back(cloud->at(indices[i]));
97  }
98  sensor_msgs::PointCloud2 resMsg;
99  pcl::toROSMsg(result, resMsg);
100  resMsg.header = input_header_;
101  keypoints_pub_.publish(resMsg);
102  }
103 
104 }
result
def result
jsk_pcl_ros::KeypointsPublisher::onInit
virtual void onInit()
Definition: keypoints_publisher_nodelet.cpp:80
i
int i
jsk_pcl_ros::KeypointsPublisher::input_header_
std_msgs::Header input_header_
Definition: keypoints_publisher.h:24
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::KeypointsPublisher, nodelet::Nodelet)
ros::Subscriber::shutdown
void shutdown()
time_synchronizer.h
keypoints_publisher.h
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
cloud
cloud
class_list_macros.h
jsk_pcl_ros::KeypointsPublisher::inputCallback
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &input)
Definition: keypoints_publisher_nodelet.cpp:100
jsk_pcl_ros::KeypointsPublisher::sub_input_
ros::Subscriber sub_input_
Definition: keypoints_publisher.h:21
jsk_pcl_ros::KeypointsPublisher::unsubscribe
virtual void unsubscribe()
Definition: keypoints_publisher_nodelet.cpp:95
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::KeypointsPublisher::keypoints_pub_
ros::Publisher keypoints_pub_
Definition: keypoints_publisher.h:22
subscriber.h
jsk_pcl_ros::KeypointsPublisher::subscribe
virtual void subscribe()
Definition: keypoints_publisher_nodelet.cpp:90
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
nodelet::Nodelet
jsk_pcl_ros::KeypointsPublisher::extractKeypoints
virtual void extractKeypoints(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
Definition: keypoints_publisher_nodelet.cpp:107
jsk_pcl_ros::KeypointsPublisher
Definition: keypoints_publisher.h:12
jsk_pcl_ros::KeypointsPublisher::input_
pcl::PointCloud< pcl::PointXYZ >::Ptr input_
Definition: keypoints_publisher.h:23
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
pcl_conversions.h


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45