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>
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< PointIn > | KdTree |
typedef pcl::KdTree< PointIn >::Ptr | KdTreePtr |
typedef pcl::PointCloud < NormalOut > | NormalCloudOut |
typedef pcl::Normal | NormalOut |
typedef pcl::PointCloud< PointIn > | PointCloudIn |
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. |
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.
Definition at line 57 of file moving_least_squares.h.
typedef pcl::KdTree<PointIn> pcl_ros::MovingLeastSquares::KdTree [private] |
Definition at line 58 of file moving_least_squares.h.
typedef pcl::KdTree<PointIn>::Ptr pcl_ros::MovingLeastSquares::KdTreePtr [private] |
Definition at line 59 of file moving_least_squares.h.
typedef pcl::PointCloud<NormalOut> pcl_ros::MovingLeastSquares::NormalCloudOut [private] |
Definition at line 56 of file moving_least_squares.h.
typedef pcl::Normal pcl_ros::MovingLeastSquares::NormalOut [private] |
Definition at line 51 of file moving_least_squares.h.
typedef pcl::PointCloud<PointIn> pcl_ros::MovingLeastSquares::PointCloudIn [private] |
Definition at line 53 of file moving_least_squares.h.
typedef PointCloudIn::ConstPtr pcl_ros::MovingLeastSquares::PointCloudInConstPtr [private] |
Definition at line 55 of file moving_least_squares.h.
typedef PointCloudIn::Ptr pcl_ros::MovingLeastSquares::PointCloudInPtr [private] |
Definition at line 54 of file moving_least_squares.h.
typedef pcl::PointXYZ pcl_ros::MovingLeastSquares::PointIn [private] |
Definition at line 50 of file moving_least_squares.h.
void pcl_ros::MovingLeastSquares::config_callback | ( | MLSConfig & | config, | |
uint32_t | level | |||
) | [protected] |
Dynamic reconfigure callback.
config | the config object | |
level | the dynamic reconfigure level |
Definition at line 177 of file moving_least_squares.cpp.
void pcl_ros::MovingLeastSquares::input_indices_callback | ( | const PointCloudInConstPtr & | cloud, | |
const PointIndicesConstPtr & | indices | |||
) | [private] |
Input point cloud callback.
cloud | the pointer to the input point cloud | |
indices | the 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.
double pcl_ros::MovingLeastSquares::gaussian_parameter_ [protected] |
How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit).
Definition at line 81 of file moving_least_squares.h.
The PCL implementation used.
Definition at line 117 of file moving_least_squares.h.
int pcl_ros::MovingLeastSquares::polynomial_order_ [protected] |
The order of the polynomial to be fit.
Definition at line 78 of file moving_least_squares.h.
ros::Publisher pcl_ros::MovingLeastSquares::pub_normals_ [private] |
The output PointCloud (containing the normals) publisher.
Definition at line 123 of file moving_least_squares.h.
double pcl_ros::MovingLeastSquares::search_radius_ [protected] |
The nearest neighbors search radius for each point.
Definition at line 69 of file moving_least_squares.h.
int pcl_ros::MovingLeastSquares::spatial_locator_type_ [protected] |
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 92 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 95 of file moving_least_squares.h.
ros::Subscriber pcl_ros::MovingLeastSquares::sub_input_ [private] |
The input PointCloud subscriber.
Definition at line 120 of file moving_least_squares.h.
message_filters::Subscriber<PointCloudIn> pcl_ros::MovingLeastSquares::sub_surface_filter_ [protected] |
The surface PointCloud subscriber filter.
Definition at line 85 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 63 of file moving_least_squares.h.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointIndices> > > pcl_ros::MovingLeastSquares::sync_input_indices_a_ [private] |
Definition at line 127 of file moving_least_squares.h.
boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointIndices> > > pcl_ros::MovingLeastSquares::sync_input_indices_e_ [private] |
Synchronized input, and indices.
Definition at line 126 of file moving_least_squares.h.
KdTreePtr pcl_ros::MovingLeastSquares::tree_ [protected] |
A pointer to the spatial search object.
Definition at line 66 of file moving_least_squares.h.
bool pcl_ros::MovingLeastSquares::use_polynomial_fit_ [protected] |
The number of K nearest neighbors to use for each point.
Whether to use a polynomial fit.
Definition at line 75 of file moving_least_squares.h.