normal_estimation_integral_image.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and 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/or 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 #ifndef JSK_PCL_ROS_NORMAL_ESTIMATION_INTEGRAL_IMAGE_H_
36 #define JSK_PCL_ROS_NORMAL_ESTIMATION_INTEGRAL_IMAGE_H_
37 
38 #include <ros/ros.h>
39 #include <ros/names.h>
40 #include <sensor_msgs/PointCloud2.h>
41 
42 #include <pcl_ros/pcl_nodelet.h>
43 #include <dynamic_reconfigure/server.h>
44 #include "jsk_pcl_ros/NormalEstimationIntegralImageConfig.h"
45 #include <jsk_topic_tools/connection_based_nodelet.h>
46 
47 namespace jsk_pcl_ros
48 {
49  class NormalEstimationIntegralImage:
50  public jsk_topic_tools::ConnectionBasedNodelet
51  {
52  public:
53  typedef jsk_pcl_ros::NormalEstimationIntegralImageConfig Config;
54  protected:
65  virtual void configCallback (Config& config, uint32_t level);
66  virtual void compute(const sensor_msgs::PointCloud2::ConstPtr& msg);
67  virtual void subscribe();
68  virtual void unsubscribe();
69  private:
70  virtual void onInit();
71  };
72 }
73 
74 #endif
ros::Publisher
jsk_pcl_ros::NormalEstimationIntegralImage::subscribe
virtual void subscribe()
Definition: normal_estimation_integral_image_nodelet.cpp:91
boost::shared_ptr
ros.h
jsk_pcl_ros::NormalEstimationIntegralImage::unsubscribe
virtual void unsubscribe()
Definition: normal_estimation_integral_image_nodelet.cpp:96
jsk_pcl_ros::NormalEstimationIntegralImage::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: normal_estimation_integral_image_nodelet.cpp:101
jsk_pcl_ros::NormalEstimationIntegralImage::max_depth_change_factor_
double max_depth_change_factor_
Definition: normal_estimation_integral_image.h:125
jsk_pcl_ros::NormalEstimationIntegralImage::depth_dependent_smoothing_
bool depth_dependent_smoothing_
Definition: normal_estimation_integral_image.h:124
pcl_nodelet.h
jsk_pcl_ros::NormalEstimationIntegralImage::sub_input_
ros::Subscriber sub_input_
Definition: normal_estimation_integral_image.h:119
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::NormalEstimationIntegralImage::border_policy_ignore_
bool border_policy_ignore_
Definition: normal_estimation_integral_image.h:127
jsk_pcl_ros::NormalEstimationIntegralImage::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: normal_estimation_integral_image.h:128
jsk_pcl_ros::NormalEstimationIntegralImage::mutex_
boost::mutex mutex_
Definition: normal_estimation_integral_image.h:122
jsk_pcl_ros::NormalEstimationIntegralImage::pub_with_xyz_
ros::Publisher pub_with_xyz_
Definition: normal_estimation_integral_image.h:121
jsk_pcl_ros::NormalEstimationIntegralImage::compute
virtual void compute(const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: normal_estimation_integral_image_nodelet.cpp:111
jsk_pcl_ros::NormalEstimationIntegralImage::normal_smoothing_size_
double normal_smoothing_size_
Definition: normal_estimation_integral_image.h:126
names.h
jsk_pcl_ros::NormalEstimationIntegralImage::onInit
virtual void onInit()
Definition: normal_estimation_integral_image_nodelet.cpp:76
jsk_pcl_ros::NormalEstimationIntegralImage::estimation_method_
int estimation_method_
Definition: normal_estimation_integral_image.h:123
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::NormalEstimationIntegralImage::pub_
ros::Publisher pub_
Definition: normal_estimation_integral_image.h:120
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
jsk_pcl_ros::NormalEstimationIntegralImage::Config
jsk_pcl_ros::NormalEstimationIntegralImageConfig Config
Definition: normal_estimation_integral_image.h:117
ros::Subscriber


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45