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:
76 
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_
pcl_ros::MovingLeastSquares::KdTreePtr
pcl::KdTree< PointIn >::Ptr KdTreePtr
Definition: moving_least_squares.h:71
pcl_ros::MovingLeastSquares::subscribe
virtual void subscribe()
LazyNodelet connection routine.
Definition: moving_least_squares.cpp:81
ros::Publisher
pcl_ros::PCLNodelet
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition: pcl_nodelet.h:73
boost::shared_ptr
pcl_ros::MovingLeastSquares::srv_
boost::shared_ptr< dynamic_reconfigure::Server< MLSConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: moving_least_squares.h:107
pcl_ros
Definition: boundary.h:46
pcl_ros::MovingLeastSquares::sync_input_indices_e_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
Definition: moving_least_squares.h:142
pcl_ros::MovingLeastSquares::gaussian_parameter_
double gaussian_parameter_
How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit).
Definition: moving_least_squares.h:93
pcl_ros::MovingLeastSquares::NormalOut
pcl::PointNormal NormalOut
Definition: moving_least_squares.h:63
pcl_ros::MovingLeastSquares
MovingLeastSquares represents a nodelet using the MovingLeastSquares implementation....
Definition: moving_least_squares.h:60
pcl_ros::MovingLeastSquares::PointCloudIn
pcl::PointCloud< PointIn > PointCloudIn
Definition: moving_least_squares.h:65
pcl_ros::MovingLeastSquares::sub_input_
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: moving_least_squares.h:136
pcl_ros::MovingLeastSquares::PointCloudInConstPtr
boost::shared_ptr< const PointCloudIn > PointCloudInConstPtr
Definition: moving_least_squares.h:67
pcl_ros::MovingLeastSquares::surface_
PointCloudInConstPtr surface_
An input point cloud describing the surface that is to be used for nearest neighbors estimation.
Definition: moving_least_squares.h:75
pcl_ros::PCLNodelet::PointIndicesConstPtr
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:84
pcl_ros::MovingLeastSquares::polynomial_order_
int polynomial_order_
The order of the polynomial to be fit.
Definition: moving_least_squares.h:90
pcl_nodelet.h
pcl_ros::MovingLeastSquares::sub_surface_filter_
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
Definition: moving_least_squares.h:97
message_filters::Subscriber< PointCloudIn >
pcl_ros::MovingLeastSquares::KdTree
pcl::KdTree< PointIn > KdTree
Definition: moving_least_squares.h:70
pcl_ros::MovingLeastSquares::unsubscribe
virtual void unsubscribe()
Definition: moving_least_squares.cpp:113
pcl_ros::MovingLeastSquares::config_callback
void config_callback(MLSConfig &config, uint32_t level)
Dynamic reconfigure callback.
Definition: moving_least_squares.cpp:192
pcl_ros::MovingLeastSquares::sync_input_indices_a_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointIndices > > > sync_input_indices_a_
Definition: moving_least_squares.h:143
pcl_ros::MovingLeastSquares::pub_normals_
ros::Publisher pub_normals_
The output PointCloud (containing the normals) publisher.
Definition: moving_least_squares.h:139
pcl_ros::MovingLeastSquares::use_polynomial_fit_
bool use_polynomial_fit_
The number of K nearest neighbors to use for each point.
Definition: moving_least_squares.h:87
pcl_ros::MovingLeastSquares::PointIn
pcl::PointXYZ PointIn
Definition: moving_least_squares.h:62
pcl_ros::MovingLeastSquares::impl_
pcl::MovingLeastSquares< PointIn, NormalOut > impl_
The PCL implementation used.
Definition: moving_least_squares.h:133
pcl_ros::MovingLeastSquares::PointCloudInPtr
boost::shared_ptr< PointCloudIn > PointCloudInPtr
Definition: moving_least_squares.h:66
message_filters::sync_policies
pcl_ros::MovingLeastSquares::tree_
KdTreePtr tree_
A pointer to the spatial search object.
Definition: moving_least_squares.h:78
pcl_ros::MovingLeastSquares::search_radius_
double search_radius_
The nearest neighbors search radius for each point.
Definition: moving_least_squares.h:81
pcl_ros::MovingLeastSquares::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: moving_least_squares.cpp:42
pcl_ros::MovingLeastSquares::NormalCloudOut
pcl::PointCloud< NormalOut > NormalCloudOut
Definition: moving_least_squares.h:68
pcl_ros::MovingLeastSquares::spatial_locator_type_
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
Definition: moving_least_squares.h:104
pcl_ros::MovingLeastSquares::input_indices_callback
void input_indices_callback(const PointCloudInConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback.
Definition: moving_least_squares.cpp:126
ros::Subscriber


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Sat Feb 18 2023 03:54:54