Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Private Attributes
pcl_ros::MovingLeastSquares Class Reference

MovingLeastSquares represents a nodelet using the MovingLeastSquares implementation. The type of the output is the same as the input, it only smooths the XYZ coordinates according to the parameters. Normals are estimated at each point as well and published on a separate topic. More...

#include <moving_least_squares.h>

Inheritance diagram for pcl_ros::MovingLeastSquares:
Inheritance graph
[legend]

List of all members.

Protected Member Functions

void config_callback (MLSConfig &config, uint32_t level)
 Dynamic reconfigure callback.

Protected Attributes

double gaussian_parameter_
 How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit).
int polynomial_order_
 The order of the polynomial to be fit.
double search_radius_
 The nearest neighbors search radius for each point.
int spatial_locator_type_
 Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index.
boost::shared_ptr
< dynamic_reconfigure::Server
< MLSConfig > > 
srv_
 Pointer to a dynamic reconfigure service.
message_filters::Subscriber
< PointCloudIn
sub_surface_filter_
 The surface PointCloud subscriber filter.
PointCloudInConstPtr surface_
 An input point cloud describing the surface that is to be used for nearest neighbors estimation.
KdTreePtr tree_
 A pointer to the spatial search object.
bool use_polynomial_fit_
 The number of K nearest neighbors to use for each point.

Private Types

typedef pcl::KdTree< PointInKdTree
typedef pcl::KdTree< PointIn >::Ptr KdTreePtr
typedef pcl::PointCloud
< NormalOut
NormalCloudOut
typedef pcl::PointNormal NormalOut
typedef pcl::PointCloud< PointInPointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef pcl::PointXYZ PointIn

Private Member Functions

void input_indices_callback (const PointCloudInConstPtr &cloud, const PointIndicesConstPtr &indices)
 Input point cloud callback.
virtual void onInit ()
 Nodelet initialization routine.

Private Attributes

pcl::MovingLeastSquares
< PointIn, NormalOut
impl_
 The PCL implementation used.
ros::Publisher pub_normals_
 The output PointCloud (containing the normals) publisher.
ros::Subscriber sub_input_
 The input PointCloud subscriber.
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ApproximateTime
< PointCloudIn, PointIndices > > > 
sync_input_indices_a_
boost::shared_ptr
< message_filters::Synchronizer
< sync_policies::ExactTime
< PointCloudIn, PointIndices > > > 
sync_input_indices_e_
 Synchronized input, and indices.

Detailed Description

MovingLeastSquares represents a nodelet using the MovingLeastSquares implementation. The type of the output is the same as the input, it only smooths the XYZ coordinates according to the parameters. Normals are estimated at each point as well and published on a separate topic.

Author:
Radu Bogdan Rusu, Zoltan-Csaba Marton

Definition at line 59 of file moving_least_squares.h.


Member Typedef Documentation

typedef pcl::KdTree<PointIn> pcl_ros::MovingLeastSquares::KdTree [private]

Definition at line 69 of file moving_least_squares.h.

typedef pcl::KdTree<PointIn>::Ptr pcl_ros::MovingLeastSquares::KdTreePtr [private]

Definition at line 70 of file moving_least_squares.h.

Definition at line 67 of file moving_least_squares.h.

typedef pcl::PointNormal pcl_ros::MovingLeastSquares::NormalOut [private]

Definition at line 62 of file moving_least_squares.h.

Definition at line 64 of file moving_least_squares.h.

typedef PointCloudIn::ConstPtr pcl_ros::MovingLeastSquares::PointCloudInConstPtr [private]

Definition at line 66 of file moving_least_squares.h.

typedef PointCloudIn::Ptr pcl_ros::MovingLeastSquares::PointCloudInPtr [private]

Definition at line 65 of file moving_least_squares.h.

typedef pcl::PointXYZ pcl_ros::MovingLeastSquares::PointIn [private]

Definition at line 61 of file moving_least_squares.h.


Member Function Documentation

void pcl_ros::MovingLeastSquares::config_callback ( MLSConfig &  config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
configthe config object
levelthe dynamic reconfigure level

Definition at line 174 of file moving_least_squares.cpp.

Input point cloud callback.

Parameters:
cloudthe pointer to the input point cloud
indicesthe pointer to the input point cloud indices

DEBUG

Definition at line 108 of file moving_least_squares.cpp.

void pcl_ros::MovingLeastSquares::onInit ( ) [private, virtual]

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 43 of file moving_least_squares.cpp.


Member Data Documentation

How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit).

Definition at line 92 of file moving_least_squares.h.

The PCL implementation used.

Definition at line 128 of file moving_least_squares.h.

The order of the polynomial to be fit.

Definition at line 89 of file moving_least_squares.h.

The output PointCloud (containing the normals) publisher.

Definition at line 134 of file moving_least_squares.h.

The nearest neighbors search radius for each point.

Definition at line 80 of file moving_least_squares.h.

Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index.

Definition at line 103 of file moving_least_squares.h.

boost::shared_ptr<dynamic_reconfigure::Server<MLSConfig> > pcl_ros::MovingLeastSquares::srv_ [protected]

Pointer to a dynamic reconfigure service.

Definition at line 106 of file moving_least_squares.h.

The input PointCloud subscriber.

Definition at line 131 of file moving_least_squares.h.

The surface PointCloud subscriber filter.

Definition at line 96 of file moving_least_squares.h.

An input point cloud describing the surface that is to be used for nearest neighbors estimation.

Definition at line 74 of file moving_least_squares.h.

Definition at line 138 of file moving_least_squares.h.

Synchronized input, and indices.

Definition at line 137 of file moving_least_squares.h.

A pointer to the spatial search object.

Definition at line 77 of file moving_least_squares.h.

The number of K nearest neighbors to use for each point.

Whether to use a polynomial fit.

Definition at line 86 of file moving_least_squares.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Aug 26 2015 15:25:31