shot_omp.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, Ryohei Ueda, 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 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  *
35  */
36 
37 #ifndef PCL_ROS_SHOT_OMP_H_
38 #define PCL_ROS_SHOT_OMP_H_
39 
40 #include <pcl/features/shot_omp.h>
42 
43 namespace pcl_ros
44 {
48  {
49  private:
50  pcl::SHOTEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::SHOT352> impl_;
51 
52  typedef pcl::PointCloud<pcl::SHOT352> PointCloudOut;
53 
55  inline bool
57  {
58  // Create the output publisher
59  pub_output_ = advertise<PointCloudOut> (nh, "output", max_queue_size_);
60  return (true);
61  }
62 
64  void emptyPublish (const PointCloudInConstPtr &cloud);
65 
67  void computePublish (const PointCloudInConstPtr &cloud,
68  const PointCloudNConstPtr &normals,
69  const PointCloudInConstPtr &surface,
70  const IndicesPtr &indices);
71 
72  public:
73  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
74  };
75 }
76 
77 #endif //#ifndef PCL_ROS_SHOT_OMP_H_
78 
SHOTEstimation estimates SHOT descriptor using OpenMP.
Definition: shot_omp.h:47
bool childInit(ros::NodeHandle &nh)
Child initialization routine. Internal method.
Definition: shot_omp.h:56
pcl::IndicesPtr IndicesPtr
Definition: feature.h:75
pcl::SHOTEstimationOMP< pcl::PointXYZ, pcl::Normal, pcl::SHOT352 > impl_
Definition: shot_omp.h:50
void computePublish(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices)
Compute the feature and publish it.
Definition: shot_omp.cpp:49
void emptyPublish(const PointCloudInConstPtr &cloud)
Publish an empty point cloud of the feature output type.
Definition: shot_omp.cpp:41
pcl::PointCloud< pcl::SHOT352 > PointCloudOut
Definition: shot_omp.h:52
int max_queue_size_
The maximum queue size (default: 3).
Definition: pcl_nodelet.h:128
ros::Publisher pub_output_
The output PointCloud publisher.
Definition: pcl_nodelet.h:125


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Feb 16 2023 03:08:02