feature.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
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 Willow Garage, Inc. 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  * $Id: feature.h 35422 2011-01-24 20:04:44Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_FEATURE_H_
39 #define PCL_ROS_FEATURE_H_
40 
41 // PCL includes
42 #include <pcl/features/feature.h>
43 #include <pcl_msgs/PointIndices.h>
44 
45 #include "pcl_ros/pcl_nodelet.h"
47 
48 // Dynamic reconfigure
49 #include <dynamic_reconfigure/server.h>
50 #include "pcl_ros/FeatureConfig.h"
51 
52 // PCL conversions
54 
55 namespace pcl_ros
56 {
58 
62 
66  class Feature : public PCLNodelet
67  {
68  public:
69  typedef pcl::KdTree<pcl::PointXYZ> KdTree;
70  typedef pcl::KdTree<pcl::PointXYZ>::Ptr KdTreePtr;
71 
72  typedef pcl::PointCloud<pcl::PointXYZ> PointCloudIn;
73  typedef PointCloudIn::Ptr PointCloudInPtr;
74  typedef PointCloudIn::ConstPtr PointCloudInConstPtr;
75 
78 
80  Feature () : /*input_(), indices_(), surface_(), */tree_(), k_(0), search_radius_(0),
82  {};
83 
84  protected:
86  //PointCloudInConstPtr input_;
87 
89  //IndicesConstPtr indices_;
90 
92  //PointCloudInConstPtr surface_;
93 
95  KdTreePtr tree_;
96 
98  int k_;
99 
102 
103  // ROS nodelet attributes
106 
109 
112 
119 
122 
124  virtual bool childInit (ros::NodeHandle &nh) = 0;
125 
127  virtual void emptyPublish (const PointCloudInConstPtr &cloud) = 0;
128 
130  virtual void computePublish (const PointCloudInConstPtr &cloud,
131  const PointCloudInConstPtr &surface,
132  const IndicesPtr &indices) = 0;
133 
138  void config_callback (FeatureConfig &config, uint32_t level);
139 
144 
149  inline void
150  input_callback (const PointCloudInConstPtr &input)
151  {
152  PointIndices indices;
153  indices.header.stamp = pcl_conversions::fromPCL(input->header).stamp;
154  PointCloudIn cloud;
155  cloud.header.stamp = input->header.stamp;
156  nf_pc_.add (cloud.makeShared ());
157  nf_pi_.add (boost::make_shared<PointIndices> (indices));
158  }
159 
160  private:
164 
166  virtual void onInit ();
167 
169  virtual void subscribe ();
170  virtual void unsubscribe ();
171 
177  void input_surface_indices_callback (const PointCloudInConstPtr &cloud,
178  const PointCloudInConstPtr &cloud_surface,
179  const PointIndicesConstPtr &indices);
180 
181  public:
182  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
183  };
184 
189  {
190  public:
191  typedef sensor_msgs::PointCloud2 PointCloud2;
192 
193  typedef pcl::PointCloud<pcl::Normal> PointCloudN;
194  typedef PointCloudN::Ptr PointCloudNPtr;
195  typedef PointCloudN::ConstPtr PointCloudNConstPtr;
196 
197  FeatureFromNormals () : normals_() {};
198 
199  protected:
201  PointCloudNConstPtr normals_;
202 
204  virtual bool childInit (ros::NodeHandle &nh) = 0;
205 
207  virtual void emptyPublish (const PointCloudInConstPtr &cloud) = 0;
208 
210  virtual void computePublish (const PointCloudInConstPtr &cloud,
211  const PointCloudNConstPtr &normals,
212  const PointCloudInConstPtr &surface,
213  const IndicesPtr &indices) = 0;
214 
215  private:
218 
222 
225  const PointCloudInConstPtr &,
226  const IndicesPtr &) {} // This should never be called
227 
229  virtual void onInit ();
230 
232  virtual void subscribe ();
233  virtual void unsubscribe ();
234 
241  void input_normals_surface_indices_callback (const PointCloudInConstPtr &cloud,
242  const PointCloudNConstPtr &cloud_normals,
243  const PointCloudInConstPtr &cloud_surface,
244  const PointIndicesConstPtr &indices);
245 
246  public:
247  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
248  };
249 }
250 
251 #endif //#ifndef PCL_ROS_FEATURE_H_
boost::shared_ptr< const std::vector< int > > IndicesConstPtr
Definition: feature.h:77
virtual void emptyPublish(const PointCloudInConstPtr &cloud)=0
Publish an empty point cloud of the feature output type.
virtual void onInit()
Nodelet initialization routine.
virtual void subscribe()
NodeletLazy connection routine.
PointCloudIn::Ptr PointCloudInPtr
Definition: feature.h:73
pcl::PointCloud< pcl::Normal > PointCloudN
Definition: feature.h:193
bool use_surface_
Set to true if the nodelet needs to listen for incoming point clouds representing the search surface...
Definition: feature.h:111
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_a_
Synchronized input, surface, and point indices.
Definition: feature.h:162
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_e_
Definition: feature.h:163
void config_callback(FeatureConfig &config, uint32_t level)
Dynamic reconfigure callback.
message_filters::PassThrough< PointCloudIn > nf_pc_
Definition: feature.h:143
PointCloudNConstPtr normals_
A pointer to the input dataset that contains the point normals of the XYZ dataset.
Definition: feature.h:197
int k_
The number of K nearest neighbors to use for each point.
Definition: feature.h:98
PointCloudN::ConstPtr PointCloudNConstPtr
Definition: feature.h:195
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
boost::shared_ptr< std::vector< int > > IndicesPtr
Definition: feature.h:76
double search_radius_
The nearest neighbors search radius for each point.
Definition: feature.h:101
pcl::KdTree< pcl::PointXYZ >::Ptr KdTreePtr
Definition: feature.h:70
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudN, PointCloudIn, PointIndices > > > sync_input_normals_surface_indices_e_
Definition: feature.h:221
Feature()
Empty constructor.
Definition: feature.h:80
message_filters::Subscriber< PointCloudN > sub_normals_filter_
The normals PointCloud subscriber filter.
Definition: feature.h:217
void computePublish(const PointCloudInConstPtr &, const PointCloudInConstPtr &, const IndicesPtr &)
Internal method.
Definition: feature.h:224
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
Definition: pcl_nodelet.h:72
pcl_msgs::PointIndices PointIndices
Definition: pcl_nodelet.h:81
boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: feature.h:121
pcl::PointCloud< pcl::PointXYZ > PointCloudIn
Definition: feature.h:72
void input_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
message_filters::PassThrough< PointIndices > nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition: feature.h:142
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
Definition: feature.h:105
sensor_msgs::PointCloud2 PointCloud2
Definition: feature.h:191
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: feature.h:108
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
Definition: feature.h:118
void add(const MConstPtr &msg)
virtual void unsubscribe()
PointCloudIn::ConstPtr PointCloudInConstPtr
Definition: feature.h:74
pcl::KdTree< pcl::PointXYZ > KdTree
Definition: feature.h:69
KdTreePtr tree_
The input point cloud dataset.
Definition: feature.h:82
Feature represents the base feature class. Some generic 3D operations that are applicable to all feat...
Definition: feature.h:66
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointCloudN, PointCloudIn, PointIndices > > > sync_input_normals_surface_indices_a_
Synchronized input, normals, surface, and point indices.
Definition: feature.h:220
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
Compute the feature and publish it. Internal method.
PointCloudN::Ptr PointCloudNPtr
Definition: feature.h:194
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:83
virtual bool childInit(ros::NodeHandle &nh)=0
Child initialization routine. Internal method.
void input_callback(const PointCloudInConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
Definition: feature.h:150


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18