00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2015, Ryohei Ueda, JSK Lab 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of JSK Lab. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * 00035 */ 00036 00037 #ifndef PCL_ROS_SHOT_OMP_H_ 00038 #define PCL_ROS_SHOT_OMP_H_ 00039 00040 #include <pcl/features/shot_omp.h> 00041 #include "pcl_ros/features/shot.h" 00042 00043 namespace pcl_ros 00044 { 00047 class SHOTEstimationOMP : public FeatureFromNormals 00048 { 00049 private: 00050 pcl::SHOTEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::SHOT352> impl_; 00051 00052 typedef pcl::PointCloud<pcl::SHOT352> PointCloudOut; 00053 00055 inline bool 00056 childInit (ros::NodeHandle &nh) 00057 { 00058 // Create the output publisher 00059 pub_output_ = nh.advertise<PointCloudOut> ("output", max_queue_size_); 00060 return (true); 00061 } 00062 00064 void emptyPublish (const PointCloudInConstPtr &cloud); 00065 00067 void computePublish (const PointCloudInConstPtr &cloud, 00068 const PointCloudNConstPtr &normals, 00069 const PointCloudInConstPtr &surface, 00070 const IndicesPtr &indices); 00071 00072 public: 00073 EIGEN_MAKE_ALIGNED_OPERATOR_NEW 00074 }; 00075 } 00076 00077 #endif //#ifndef PCL_ROS_SHOT_OMP_H_ 00078