00001 // -*- mode: c++ -*- 00002 /********************************************************************* 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2015, JSK Lab 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/o2r other materials provided 00017 * with the distribution. 00018 * * Neither the name of the JSK Lab nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 *********************************************************************/ 00035 00036 00037 #ifndef JSK_PCL_ROS_NORMAL_ESTIMATION_OMP_H_ 00038 #define JSK_PCL_ROS_NORMAL_ESTIMATION_OMP_H_ 00039 00040 #include <jsk_topic_tools/diagnostic_nodelet.h> 00041 #include <sensor_msgs/PointCloud2.h> 00042 #include <pcl_ros/FeatureConfig.h> 00043 #include <dynamic_reconfigure/server.h> 00044 #include <pcl_conversions/pcl_conversions.h> 00045 namespace jsk_pcl_ros 00046 { 00047 class NormalEstimationOMP: public jsk_topic_tools::DiagnosticNodelet 00048 { 00049 public: 00050 typedef boost::shared_ptr<NormalEstimationOMP> Ptr; 00051 typedef pcl_ros::FeatureConfig Config; 00052 NormalEstimationOMP(): DiagnosticNodelet("NormalEstimationOMP") {} 00053 00054 protected: 00055 00056 virtual void onInit(); 00057 virtual void subscribe(); 00058 virtual void unsubscribe(); 00059 virtual void estimate( 00060 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg); 00061 virtual void configCallback( 00062 Config& config, uint32_t level); 00063 00064 boost::mutex mutex_; 00065 ros::Publisher pub_; 00066 ros::Publisher pub_with_xyz_; 00067 ros::Subscriber sub_; 00068 std::string sensor_frame_; 00069 boost::shared_ptr <dynamic_reconfigure::Server<Config> > srv_; 00070 int k_; 00071 double search_radius_; 00072 00073 private: 00074 00075 }; 00076 } 00077 00078 #endif