Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::MovingLeastSquareSmoothing Class Reference

#include <moving_least_square_smoothing.h>

Inheritance diagram for jsk_pcl_ros::MovingLeastSquareSmoothing:
Inheritance graph
[legend]

Public Types

typedef MovingLeastSquareSmoothingConfig Config
 

Public Member Functions

 MovingLeastSquareSmoothing ()
 

Protected Member Functions

virtual void configCallback (Config &config, uint32_t level)
 
virtual void onInit ()
 
virtual void smooth (const sensor_msgs::PointCloud2ConstPtr &input)
 
virtual void subscribe ()
 
virtual void unsubscribe ()
 

Protected Attributes

bool calc_normal_
 
bool gauss_param_set_
 
boost::mutex mutex_
 
int polynomial_order_
 
ros::Publisher pub_
 
double search_radius_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
ros::Subscriber sub_input_
 
bool use_polynomial_fit_
 

Detailed Description

Definition at line 89 of file moving_least_square_smoothing.h.

Member Typedef Documentation

◆ Config

typedef MovingLeastSquareSmoothingConfig jsk_pcl_ros::MovingLeastSquareSmoothing::Config

Definition at line 124 of file moving_least_square_smoothing.h.

Constructor & Destructor Documentation

◆ MovingLeastSquareSmoothing()

jsk_pcl_ros::MovingLeastSquareSmoothing::MovingLeastSquareSmoothing ( )
inline

Definition at line 125 of file moving_least_square_smoothing.h.

Member Function Documentation

◆ configCallback()

void jsk_pcl_ros::MovingLeastSquareSmoothing::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 88 of file moving_least_square_smoothing_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::MovingLeastSquareSmoothing::onInit ( )
protectedvirtual

Definition at line 98 of file moving_least_square_smoothing_nodelet.cpp.

◆ smooth()

void jsk_pcl_ros::MovingLeastSquareSmoothing::smooth ( const sensor_msgs::PointCloud2ConstPtr &  input)
protectedvirtual

Definition at line 46 of file moving_least_square_smoothing_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::MovingLeastSquareSmoothing::subscribe ( )
protectedvirtual

Definition at line 78 of file moving_least_square_smoothing_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::MovingLeastSquareSmoothing::unsubscribe ( )
protectedvirtual

Definition at line 83 of file moving_least_square_smoothing_nodelet.cpp.

Member Data Documentation

◆ calc_normal_

bool jsk_pcl_ros::MovingLeastSquareSmoothing::calc_normal_
protected

Definition at line 136 of file moving_least_square_smoothing.h.

◆ gauss_param_set_

bool jsk_pcl_ros::MovingLeastSquareSmoothing::gauss_param_set_
protected

Definition at line 135 of file moving_least_square_smoothing.h.

◆ mutex_

boost::mutex jsk_pcl_ros::MovingLeastSquareSmoothing::mutex_
protected

Definition at line 140 of file moving_least_square_smoothing.h.

◆ polynomial_order_

int jsk_pcl_ros::MovingLeastSquareSmoothing::polynomial_order_
protected

Definition at line 139 of file moving_least_square_smoothing.h.

◆ pub_

ros::Publisher jsk_pcl_ros::MovingLeastSquareSmoothing::pub_
protected

Definition at line 134 of file moving_least_square_smoothing.h.

◆ search_radius_

double jsk_pcl_ros::MovingLeastSquareSmoothing::search_radius_
protected

Definition at line 137 of file moving_least_square_smoothing.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::MovingLeastSquareSmoothing::srv_
protected

Definition at line 141 of file moving_least_square_smoothing.h.

◆ sub_input_

ros::Subscriber jsk_pcl_ros::MovingLeastSquareSmoothing::sub_input_
protected

Definition at line 133 of file moving_least_square_smoothing.h.

◆ use_polynomial_fit_

bool jsk_pcl_ros::MovingLeastSquareSmoothing::use_polynomial_fit_
protected

Definition at line 138 of file moving_least_square_smoothing.h.


The documentation for this class was generated from the following files:


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