00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <pluginlib/class_list_macros.h>
00039 #include "pcl_ros/surface/moving_least_squares.h"
00040 #include <pcl/io/io.h>
00041 #include <pcl/kdtree/tree_types.h>
00043 void
00044 pcl_ros::MovingLeastSquares::onInit ()
00045 {
00046 PCLNodelet::onInit ();
00047
00048
00049 pub_output_ = pnh_->advertise<PointCloudIn> ("output", max_queue_size_);
00050 pub_normals_ = pnh_->advertise<NormalCloudOut> ("normals", max_queue_size_);
00051
00052
00053 if (!pnh_->getParam ("search_radius", search_radius_))
00054 {
00055
00056 NODELET_ERROR ("[%s::onInit] Need a 'search_radius' parameter to be set before continuing!", getName ().c_str ());
00057 return;
00058 }
00059 if (!pnh_->getParam ("spatial_locator", spatial_locator_type_))
00060 {
00061 NODELET_ERROR ("[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!", getName ().c_str ());
00062 return;
00063 }
00064
00065
00066 srv_ = boost::make_shared<dynamic_reconfigure::Server<MLSConfig> > (*pnh_);
00067 dynamic_reconfigure::Server<MLSConfig>::CallbackType f = boost::bind (&MovingLeastSquares::config_callback, this, _1, _2 );
00068 srv_->setCallback (f);
00069
00070
00071 pnh_->getParam ("use_indices", use_indices_);
00072
00073
00074 if (use_indices_)
00075 {
00076
00077 sub_input_filter_.subscribe (*pnh_, "input", 1);
00078
00079 sub_indices_filter_.subscribe (*pnh_, "indices", 1);
00080
00081 if (approximate_sync_)
00082 {
00083 sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<PointCloudIn, PointIndices> > >(max_queue_size_);
00084
00085 sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
00086 sync_input_indices_a_->registerCallback (bind (&MovingLeastSquares::input_indices_callback, this, _1, _2));
00087 }
00088 else
00089 {
00090 sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<PointCloudIn, PointIndices> > >(max_queue_size_);
00091
00092 sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
00093 sync_input_indices_e_->registerCallback (bind (&MovingLeastSquares::input_indices_callback, this, _1, _2));
00094 }
00095 }
00096 else
00097
00098 sub_input_ = pnh_->subscribe<PointCloudIn> ("input", 1, bind (&MovingLeastSquares::input_indices_callback, this, _1, PointIndicesConstPtr ()));
00099
00100
00101 NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
00102 " - use_indices : %s",
00103 getName ().c_str (),
00104 (use_indices_) ? "true" : "false");
00105 }
00106
00108 void
00109 pcl_ros::MovingLeastSquares::input_indices_callback (const PointCloudInConstPtr &cloud,
00110 const PointIndicesConstPtr &indices)
00111 {
00112
00113 if (pub_output_.getNumSubscribers () <= 0 && pub_normals_.getNumSubscribers () <= 0)
00114 return;
00115
00116
00117 PointCloudIn output;
00118
00119
00120 NormalCloudOut::Ptr normals (new NormalCloudOut ());
00121
00122
00123 if (!isValid (cloud))
00124 {
00125 NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
00126 output.header = cloud->header;
00127 pub_output_.publish (output.makeShared ());
00128 return;
00129 }
00130
00131 if (indices && !isValid (indices, "indices"))
00132 {
00133 NODELET_ERROR ("[%s::input_indices_callback] Invalid indices!", getName ().c_str ());
00134 output.header = cloud->header;
00135 pub_output_.publish (output.makeShared ());
00136 return;
00137 }
00138
00140 if (indices)
00141 NODELET_DEBUG ("[%s::input_indices_model_callback]\n"
00142 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00143 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
00144 getName ().c_str (),
00145 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName ("input").c_str (),
00146 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName ("indices").c_str ());
00147 else
00148 NODELET_DEBUG ("[%s::input_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", getName ().c_str (), cloud->width * cloud->height, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName ("input").c_str ());
00150
00151
00152 impl_.setInputCloud (cloud);
00153 impl_.setOutputNormals (normals);
00154
00155 IndicesPtr indices_ptr;
00156 if (indices)
00157 indices_ptr.reset (new std::vector<int> (indices->indices));
00158
00159 impl_.setIndices (indices_ptr);
00160
00161
00162 initTree (spatial_locator_type_, tree_, 0);
00163 impl_.setSearchMethod (tree_);
00164
00165
00166 impl_.reconstruct (output);
00167
00168
00169
00170 output.header = cloud->header;
00171 pub_output_.publish (output.makeShared ());
00172 normals->header = cloud->header;
00173 pub_normals_.publish (normals);
00174 }
00175
00177 void
00178 pcl_ros::MovingLeastSquares::config_callback (MLSConfig &config, uint32_t level)
00179 {
00180
00181
00182
00183
00184
00185
00186 if (search_radius_ != config.search_radius)
00187 {
00188 search_radius_ = config.search_radius;
00189 NODELET_DEBUG ("[config_callback] Setting the search radius: %f.", search_radius_);
00190 impl_.setSearchRadius (search_radius_);
00191 }
00192 if (spatial_locator_type_ != config.spatial_locator)
00193 {
00194 spatial_locator_type_ = config.spatial_locator;
00195 NODELET_DEBUG ("[config_callback] Setting the spatial locator to type: %d.", spatial_locator_type_);
00196 }
00197 if (use_polynomial_fit_ != config.use_polynomial_fit)
00198 {
00199 use_polynomial_fit_ = config.use_polynomial_fit;
00200 NODELET_DEBUG ("[config_callback] Setting the use_polynomial_fit flag to: %d.", use_polynomial_fit_);
00201 impl_.setPolynomialFit (use_polynomial_fit_);
00202 }
00203 if (polynomial_order_ != config.polynomial_order)
00204 {
00205 polynomial_order_ = config.polynomial_order;
00206 NODELET_DEBUG ("[config_callback] Setting the polynomial order to: %d.", polynomial_order_);
00207 impl_.setPolynomialOrder (polynomial_order_);
00208 }
00209 if (gaussian_parameter_ != config.gaussian_parameter)
00210 {
00211 gaussian_parameter_ = config.gaussian_parameter;
00212 NODELET_DEBUG ("[config_callback] Setting the gaussian parameter to: %f.", gaussian_parameter_);
00213 impl_.setSqrGaussParam (gaussian_parameter_ * gaussian_parameter_);
00214 }
00215 }
00216
00217 typedef pcl_ros::MovingLeastSquares MovingLeastSquares;
00218 PLUGINLIB_DECLARE_CLASS (pcl, MovingLeastSquares, MovingLeastSquares, nodelet::Nodelet);