moving_least_squares.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: moving_least_squares.h 36097 2011-02-20 14:18:58Z marton $
35  *
36  */
37 
38 #ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_
39 #define PCL_ROS_MOVING_LEAST_SQUARES_H_
40 
41 #include "pcl_ros/pcl_nodelet.h"
42 
43 // PCL includes
44 #include <pcl/surface/mls.h>
45 #include <pcl/kdtree/kdtree.h> // for KdTree
46 
47 // Dynamic reconfigure
48 #include <dynamic_reconfigure/server.h>
49 #include "pcl_ros/MLSConfig.h"
50 
51 namespace pcl_ros
52 {
54 
61  {
62  typedef pcl::PointXYZ PointIn;
63  typedef pcl::PointNormal NormalOut;
64 
65  typedef pcl::PointCloud<PointIn> PointCloudIn;
68  typedef pcl::PointCloud<NormalOut> NormalCloudOut;
69 
70  typedef pcl::KdTree<PointIn> KdTree;
71  typedef pcl::KdTree<PointIn>::Ptr KdTreePtr;
72 
73  protected:
75  PointCloudInConstPtr surface_;
76 
78  KdTreePtr tree_;
79 
82 
84  //int k_;
85 
88 
91 
94 
95  // ROS nodelet attributes
98 
105 
108 
113  void config_callback (MLSConfig &config, uint32_t level);
114 
116  virtual void onInit ();
117 
119  virtual void subscribe ();
120  virtual void unsubscribe ();
121 
122  private:
127  void input_indices_callback (const PointCloudInConstPtr &cloud,
128  const PointIndicesConstPtr &indices);
129 
130 
131  private:
133  pcl::MovingLeastSquares<PointIn, NormalOut> impl_;
134 
137 
140 
144 
145  public:
146  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
147  };
148 }
149 
150 #endif //#ifndef PCL_ROS_MOVING_LEAST_SQUARES_H_
ros::Subscriber sub_input_
The input PointCloud subscriber.
pcl::PointCloud< PointIn > PointCloudIn
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 &#39;flat&#39; should the neighbor weighting gaussian be (the smaller, the more local the fit)...
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
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
double search_radius_
The nearest neighbors search radius for each point.
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
Definition: pcl_nodelet.h:73
bool use_polynomial_fit_
The number of K nearest neighbors to use for each point.
virtual void onInit()
Nodelet initialization routine.
boost::shared_ptr< PointCloudIn > PointCloudInPtr
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.
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:84
pcl::PointCloud< NormalOut > NormalCloudOut


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Feb 16 2023 03:08:02