include
jsk_pcl_ros
moving_least_square_smoothing.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/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
36
#ifndef JSK_PCL_ROS_MOVING_LEAST_SQUARE_SMOOTHING_H_
37
#define JSK_PCL_ROS_MOVING_LEAST_SQUARE_SMOOTHING_H_
38
39
// ros
40
#include <
ros/ros.h
>
41
#include <
ros/names.h
>
42
#include <sensor_msgs/PointCloud2.h>
43
#include <
tf/transform_broadcaster.h
>
44
#include <jsk_pcl_ros/MovingLeastSquareSmoothingConfig.h>
45
46
// pcl
47
#include <
pcl_ros/pcl_nodelet.h
>
48
#include <pcl/point_types.h>
49
#include <pcl/common/centroid.h>
50
#include <pcl/surface/mls.h>
51
#include <dynamic_reconfigure/server.h>
52
#include <pcl/filters/filter.h>
53
#include <jsk_topic_tools/diagnostic_nodelet.h>
54
55
namespace
jsk_pcl_ros
56
{
57
class
MovingLeastSquareSmoothing:
public
jsk_topic_tools::DiagnosticNodelet
58
{
59
public
:
60
typedef
MovingLeastSquareSmoothingConfig
Config
;
61
MovingLeastSquareSmoothing
(): DiagnosticNodelet(
"MovingLesatSquareSmoothing"
){};
62
protected
:
63
virtual
void
onInit
();
64
virtual
void
subscribe
();
65
virtual
void
unsubscribe
();
66
virtual
void
smooth
(
const
sensor_msgs::PointCloud2ConstPtr &
input
);
67
virtual
void
configCallback
(
Config
&config, uint32_t level);
68
69
ros::Subscriber
sub_input_
;
70
ros::Publisher
pub_
;
71
bool
gauss_param_set_
;
72
bool
calc_normal_
;
73
double
search_radius_
;
74
bool
use_polynomial_fit_
;
75
int
polynomial_order_
;
76
boost::mutex
mutex_
;
77
boost::shared_ptr <dynamic_reconfigure::Server<Config>
>
srv_
;
78
79
private
:
80
};
81
}
82
83
#endif
ros::Publisher
jsk_pcl_ros::MovingLeastSquareSmoothing::sub_input_
ros::Subscriber sub_input_
Definition:
moving_least_square_smoothing.h:133
boost::shared_ptr
jsk_pcl_ros::MovingLeastSquareSmoothing::mutex_
boost::mutex mutex_
Definition:
moving_least_square_smoothing.h:140
ros.h
jsk_pcl_ros::MovingLeastSquareSmoothing::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition:
moving_least_square_smoothing.h:141
jsk_pcl_ros::MovingLeastSquareSmoothing::subscribe
virtual void subscribe()
Definition:
moving_least_square_smoothing_nodelet.cpp:78
jsk_pcl_ros::MovingLeastSquareSmoothing::polynomial_order_
int polynomial_order_
Definition:
moving_least_square_smoothing.h:139
transform_broadcaster.h
jsk_pcl_ros::MovingLeastSquareSmoothing::calc_normal_
bool calc_normal_
Definition:
moving_least_square_smoothing.h:136
pcl_nodelet.h
jsk_pcl_ros::MovingLeastSquareSmoothing::MovingLeastSquareSmoothing
MovingLeastSquareSmoothing()
Definition:
moving_least_square_smoothing.h:125
jsk_pcl_ros
Definition:
add_color_from_image.h:51
jsk_pcl_ros::MovingLeastSquareSmoothing::onInit
virtual void onInit()
Definition:
moving_least_square_smoothing_nodelet.cpp:98
jsk_pcl_ros::MovingLeastSquareSmoothing::gauss_param_set_
bool gauss_param_set_
Definition:
moving_least_square_smoothing.h:135
jsk_pcl_ros::MovingLeastSquareSmoothing::smooth
virtual void smooth(const sensor_msgs::PointCloud2ConstPtr &input)
Definition:
moving_least_square_smoothing_nodelet.cpp:46
jsk_pcl_ros::MovingLeastSquareSmoothing::pub_
ros::Publisher pub_
Definition:
moving_least_square_smoothing.h:134
names.h
jsk_pcl_ros::MovingLeastSquareSmoothing::use_polynomial_fit_
bool use_polynomial_fit_
Definition:
moving_least_square_smoothing.h:138
jsk_pcl_ros::MovingLeastSquareSmoothing::unsubscribe
virtual void unsubscribe()
Definition:
moving_least_square_smoothing_nodelet.cpp:83
mutex
boost::mutex mutex
global mutex.
Definition:
depth_camera_error_visualization.cpp:86
depth_error_calibration.input
input
Definition:
depth_error_calibration.py:43
jsk_pcl_ros::MovingLeastSquareSmoothing::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition:
moving_least_square_smoothing_nodelet.cpp:88
jsk_pcl_ros::MovingLeastSquareSmoothing::search_radius_
double search_radius_
Definition:
moving_least_square_smoothing.h:137
ros::Subscriber
jsk_pcl_ros::MovingLeastSquareSmoothing::Config
MovingLeastSquareSmoothingConfig Config
Definition:
moving_least_square_smoothing.h:124
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45