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 
44 #include "pcl_ros/pcl_nodelet.h"
46 
47 // Dynamic reconfigure
48 #include <dynamic_reconfigure/server.h>
49 #include "pcl_ros/FeatureConfig.h"
50 
51 // PCL conversions
53 
54 namespace pcl_ros
55 {
57 
61 
65  class Feature : public PCLNodelet
66  {
67  public:
68  typedef pcl::KdTree<pcl::PointXYZ> KdTree;
69  typedef pcl::KdTree<pcl::PointXYZ>::Ptr KdTreePtr;
70 
71  typedef pcl::PointCloud<pcl::PointXYZ> PointCloudIn;
74 
75  typedef pcl::IndicesPtr IndicesPtr;
76  typedef pcl::IndicesConstPtr IndicesConstPtr;
77 
79  Feature () : /*input_(), indices_(), surface_(), */tree_(), k_(0), search_radius_(0),
81  {};
82 
83  protected:
85  //PointCloudInConstPtr input_;
86 
88  //IndicesConstPtr indices_;
89 
91  //PointCloudInConstPtr surface_;
92 
95 
97  int k_;
98 
101 
102  // ROS nodelet attributes
105 
108 
111 
118 
121 
123  virtual bool childInit (ros::NodeHandle &nh) = 0;
124 
126  virtual void emptyPublish (const PointCloudInConstPtr &cloud) = 0;
127 
129  virtual void computePublish (const PointCloudInConstPtr &cloud,
130  const PointCloudInConstPtr &surface,
131  const IndicesPtr &indices) = 0;
132 
137  void config_callback (FeatureConfig &config, uint32_t level);
138 
143 
148  inline void
150  {
151  PointIndices indices;
152  indices.header.stamp = pcl_conversions::fromPCL(input->header).stamp;
153  PointCloudIn cloud;
154  cloud.header.stamp = input->header.stamp;
155  nf_pc_.add (ros_ptr(cloud.makeShared ()));
156  nf_pi_.add (boost::make_shared<PointIndices> (indices));
157  }
158 
159  private:
163 
165  virtual void onInit ();
166 
168  virtual void subscribe ();
169  virtual void unsubscribe ();
170 
177  const PointCloudInConstPtr &cloud_surface,
178  const PointIndicesConstPtr &indices);
179 
180  public:
181  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
182  };
183 
188  {
189  public:
190  typedef sensor_msgs::PointCloud2 PointCloud2;
191 
192  typedef pcl::PointCloud<pcl::Normal> PointCloudN;
195 
197 
198  protected:
201 
203  virtual bool childInit (ros::NodeHandle &nh) = 0;
204 
206  virtual void emptyPublish (const PointCloudInConstPtr &cloud) = 0;
207 
209  virtual void computePublish (const PointCloudInConstPtr &cloud,
210  const PointCloudNConstPtr &normals,
211  const PointCloudInConstPtr &surface,
212  const IndicesPtr &indices) = 0;
213 
214  private:
217 
221 
224  const PointCloudInConstPtr &,
225  const IndicesPtr &) {} // This should never be called
226 
228  virtual void onInit ();
229 
231  virtual void subscribe ();
232  virtual void unsubscribe ();
233 
241  const PointCloudNConstPtr &cloud_normals,
242  const PointCloudInConstPtr &cloud_surface,
243  const PointIndicesConstPtr &indices);
244 
245  public:
246  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
247  };
248 }
249 
250 #endif //#ifndef PCL_ROS_FEATURE_H_
pcl_ros::FeatureFromNormals::PointCloudNPtr
boost::shared_ptr< PointCloudN > PointCloudNPtr
Definition: feature.h:193
pcl_ros::Feature::PointCloudInPtr
boost::shared_ptr< PointCloudIn > PointCloudInPtr
Definition: feature.h:72
pcl_ros::PCLNodelet
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition: pcl_nodelet.h:73
pcl_ros::Feature::spatial_locator_type_
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
Definition: feature.h:117
pcl_ros::Feature::use_surface_
bool use_surface_
Set to true if the nodelet needs to listen for incoming point clouds representing the search surface.
Definition: feature.h:110
pcl_ros::Feature::srv_
boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: feature.h:120
pcl_ros::Feature::KdTree
pcl::KdTree< pcl::PointXYZ > KdTree
Definition: feature.h:68
pass_through.h
boost::shared_ptr
pcl_ros
Definition: boundary.h:46
pcl_ros::Feature::input_surface_indices_callback
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.
Definition: feature.cpp:194
pcl_ros::Feature::emptyPublish
virtual void emptyPublish(const PointCloudInConstPtr &cloud)=0
Publish an empty point cloud of the feature output type.
pcl_ros::FeatureFromNormals::input_normals_surface_indices_callback
void input_normals_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
Definition: feature.cpp:407
pcl_ros::FeatureFromNormals::unsubscribe
virtual void unsubscribe()
Definition: feature.cpp:388
pcl_ros::Feature::sync_input_surface_indices_a_
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:161
pcl_ros::Feature::IndicesConstPtr
pcl::IndicesConstPtr IndicesConstPtr
Definition: feature.h:76
pcl_ros::FeatureFromNormals::normals_
PointCloudNConstPtr normals_
A pointer to the input dataset that contains the point normals of the XYZ dataset.
Definition: feature.h:196
pcl_ros::FeatureFromNormals::computePublish
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
Compute the feature and publish it.
pcl_ros::PCLNodelet::PointIndicesConstPtr
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:84
pcl_ros::FeatureFromNormals::PointCloudNConstPtr
boost::shared_ptr< const PointCloudN > PointCloudNConstPtr
Definition: feature.h:194
pcl_nodelet.h
pcl_ros::Feature::IndicesPtr
pcl::IndicesPtr IndicesPtr
Definition: feature.h:75
pcl_ros::FeatureFromNormals::sync_input_normals_surface_indices_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudN, PointCloudIn, PointIndices > > > sync_input_normals_surface_indices_e_
Definition: feature.h:220
pcl_ros::FeatureFromNormals::computePublish
void computePublish(const PointCloudInConstPtr &, const PointCloudInConstPtr &, const IndicesPtr &)
Internal method.
Definition: feature.h:223
pcl_ros::FeatureFromNormals::emptyPublish
virtual void emptyPublish(const PointCloudInConstPtr &cloud)=0
Publish an empty point cloud of the feature output type.
message_filters::Subscriber< PointCloudIn >
pcl_ros::FeatureFromNormals::sub_normals_filter_
message_filters::Subscriber< PointCloudN > sub_normals_filter_
The normals PointCloud subscriber filter.
Definition: feature.h:216
pcl_ros::Feature::Feature
Feature()
Empty constructor.
Definition: feature.h:79
pcl_ros::Feature
Feature represents the base feature class. Some generic 3D operations that are applicable to all feat...
Definition: feature.h:65
pcl_ros::Feature::sync_input_surface_indices_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_e_
Definition: feature.h:162
pcl_conversions::fromPCL
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
pcl_ros::FeatureFromNormals::PointCloud2
sensor_msgs::PointCloud2 PointCloud2
Definition: feature.h:190
pcl_ros::Feature::PointCloudIn
pcl::PointCloud< pcl::PointXYZ > PointCloudIn
Definition: feature.h:71
pcl_ros::Feature::unsubscribe
virtual void unsubscribe()
Definition: feature.cpp:158
pcl_ros::Feature::k_
int k_
The number of K nearest neighbors to use for each point.
Definition: feature.h:97
pcl_ros::Feature::sub_surface_filter_
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
Definition: feature.h:104
pcl_ros::Feature::KdTreePtr
pcl::KdTree< pcl::PointXYZ >::Ptr KdTreePtr
Definition: feature.h:69
message_filters::PassThrough::add
void add(const EventType &evt)
pcl_ros::FeatureFromNormals::sync_input_normals_surface_indices_a_
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:219
message_filters::sync_policies
message_filters::PassThrough< PointIndices >
pcl_ros::Feature::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: feature.cpp:54
pcl_ros::Feature::subscribe
virtual void subscribe()
NodeletLazy connection routine.
Definition: feature.cpp:99
pcl_ros::Feature::PointCloudInConstPtr
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
Definition: feature.h:73
pcl_ros::Feature::nf_pi_
message_filters::PassThrough< PointIndices > nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
Definition: feature.h:141
pcl_ros::FeatureFromNormals::subscribe
virtual void subscribe()
NodeletLazy connection routine.
Definition: feature.cpp:319
pcl_ros::Feature::tree_
KdTreePtr tree_
The input point cloud dataset.
Definition: feature.h:81
pcl_ros::FeatureFromNormals::FeatureFromNormals
FeatureFromNormals()
Definition: feature.h:196
pcl_ros::Feature::nf_pc_
message_filters::PassThrough< PointCloudIn > nf_pc_
Definition: feature.h:142
pcl_ros::Feature::sub_input_
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: feature.h:107
pcl_ros::FeatureFromNormals::childInit
virtual bool childInit(ros::NodeHandle &nh)=0
Child initialization routine. Internal method.
pcl_ros::Feature::childInit
virtual bool childInit(ros::NodeHandle &nh)=0
Child initialization routine. Internal method.
pcl_ros::Feature::input_callback
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:149
pcl_ros::PCLNodelet::PointIndices
pcl_msgs::PointIndices PointIndices
Definition: pcl_nodelet.h:82
pcl_ros::FeatureFromNormals::PointCloudN
pcl::PointCloud< pcl::Normal > PointCloudN
Definition: feature.h:192
pcl_ros::Feature::search_radius_
double search_radius_
The nearest neighbors search radius for each point.
Definition: feature.h:100
ros::NodeHandle
ros::Subscriber
pcl_ros::FeatureFromNormals::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: feature.cpp:275
pcl_ros::FeatureFromNormals
Definition: feature.h:187
pcl::ros_ptr
boost::shared_ptr< T > ros_ptr(const boost::shared_ptr< T > &p)
Definition: point_cloud.h:354
pcl_ros::Feature::config_callback
void config_callback(FeatureConfig &config, uint32_t level)
Dynamic reconfigure callback.
Definition: feature.cpp:178
pcl_conversions.h
pcl_ros::Feature::computePublish
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
Compute the feature and publish it. Internal method.


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Sat Feb 18 2023 03:54:54