normal_estimation_omp.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 
37 #ifndef JSK_PCL_ROS_NORMAL_ESTIMATION_OMP_H_
38 #define JSK_PCL_ROS_NORMAL_ESTIMATION_OMP_H_
39 
41 #include <sensor_msgs/PointCloud2.h>
42 #include <pcl_ros/FeatureConfig.h>
43 #include <dynamic_reconfigure/server.h>
46 #include <std_msgs/Float32.h>
47 
48 namespace jsk_pcl_ros
49 {
51  {
52  public:
54  typedef pcl_ros::FeatureConfig Config;
55  NormalEstimationOMP(): DiagnosticNodelet("NormalEstimationOMP"), timer_(10) {}
56 
57  protected:
58 
59  virtual void onInit();
60  virtual void subscribe();
61  virtual void unsubscribe();
62  virtual void estimate(
63  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
64  virtual void configCallback(
65  Config& config, uint32_t level);
66 
74  std::string sensor_frame_;
76  int k_;
79 
80  private:
81 
82  };
83 }
84 
85 #endif
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
config
boost::shared_ptr< NormalEstimationOMP > Ptr
DiagnosticNodelet(const std::string &name)
virtual void configCallback(Config &config, uint32_t level)
boost::mutex mutex
global mutex.
jsk_recognition_utils::WallDurationTimer timer_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47