38 #ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_ 39 #define PCL_ROS_MOVING_LEAST_SQUARES_H_ 44 #include <pcl/surface/mls.h> 47 #include <dynamic_reconfigure/server.h> 48 #include "pcl_ros/MLSConfig.h" 132 pcl::MovingLeastSquares<PointIn, NormalOut>
impl_;
145 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
149 #endif //#ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_ ros::Subscriber sub_input_
The input PointCloud subscriber.
pcl::PointCloud< PointIn > PointCloudIn
PointCloudIn::Ptr PointCloudInPtr
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
int polynomial_order_
The order of the polynomial to be fit.
KdTreePtr tree_
A pointer to the spatial search object.
double gaussian_parameter_
How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit)...
pcl::PointNormal NormalOut
void config_callback(MLSConfig &config, uint32_t level)
Dynamic reconfigure callback.
pcl::MovingLeastSquares< PointIn, NormalOut > impl_
The PCL implementation used.
void input_indices_callback(const PointCloudInConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback.
pcl::KdTree< PointIn > KdTree
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
virtual void subscribe()
LazyNodelet connection routine.
pcl::KdTree< PointIn >::Ptr KdTreePtr
double search_radius_
The nearest neighbors search radius for each point.
PointCloudIn::ConstPtr PointCloudInConstPtr
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
bool use_polynomial_fit_
The number of K nearest neighbors to use for each point.
virtual void onInit()
Nodelet initialization routine.
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.
PointCloudInConstPtr surface_
An input point cloud describing the surface that is to be used for nearest neighbors estimation...
boost::shared_ptr< dynamic_reconfigure::Server< MLSConfig > > srv_
Pointer to a dynamic reconfigure service.
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.
virtual void unsubscribe()
PointIndices::ConstPtr PointIndicesConstPtr
pcl::PointCloud< NormalOut > NormalCloudOut