Go to the documentation of this file.
38 #ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_
39 #define PCL_ROS_MOVING_LEAST_SQUARES_H_
44 #include <pcl/surface/mls.h>
45 #include <pcl/kdtree/kdtree.h>
48 #include <dynamic_reconfigure/server.h>
49 #include "pcl_ros/MLSConfig.h"
133 pcl::MovingLeastSquares<PointIn, NormalOut>
impl_;
146 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
150 #endif //#ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_
pcl::KdTree< PointIn >::Ptr KdTreePtr
virtual void subscribe()
LazyNodelet connection routine.
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
boost::shared_ptr< dynamic_reconfigure::Server< MLSConfig > > srv_
Pointer to a dynamic reconfigure service.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
double gaussian_parameter_
How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit).
pcl::PointNormal NormalOut
MovingLeastSquares represents a nodelet using the MovingLeastSquares implementation....
pcl::PointCloud< PointIn > PointCloudIn
ros::Subscriber sub_input_
The input PointCloud subscriber.
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
PointCloudInConstPtr surface_
An input point cloud describing the surface that is to be used for nearest neighbors estimation.
PointIndices::ConstPtr PointIndicesConstPtr
int polynomial_order_
The order of the polynomial to be fit.
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
pcl::KdTree< PointIn > KdTree
virtual void unsubscribe()
void config_callback(MLSConfig &config, uint32_t level)
Dynamic reconfigure callback.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointIndices > > > sync_input_indices_a_
ros::Publisher pub_normals_
The output PointCloud (containing the normals) publisher.
bool use_polynomial_fit_
The number of K nearest neighbors to use for each point.
pcl::MovingLeastSquares< PointIn, NormalOut > impl_
The PCL implementation used.
boost::shared_ptr< PointCloudIn > PointCloudInPtr
KdTreePtr tree_
A pointer to the spatial search object.
double search_radius_
The nearest neighbors search radius for each point.
virtual void onInit()
Nodelet initialization routine.
pcl::PointCloud< NormalOut > NormalCloudOut
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
void input_indices_callback(const PointCloudInConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback.
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40