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/filters/project_inliers.h"
00040
00042 void
00043 pcl_ros::ProjectInliers::onInit ()
00044 {
00045
00046
00047 PCLNodelet::onInit ();
00048
00049
00050
00051 int model_type;
00052 if (!pnh_->getParam ("model_type", model_type))
00053 {
00054 NODELET_ERROR ("[%s::onInit] Need a 'model_type' parameter to be set before continuing!", getName ().c_str ());
00055 return;
00056 }
00057
00058
00059 bool copy_all_data = false;
00060
00061
00062 bool copy_all_fields = true;
00063
00064 pnh_->getParam ("copy_all_data", copy_all_data);
00065 pnh_->getParam ("copy_all_fields", copy_all_fields);
00066
00067 pub_output_ = pnh_->advertise<PointCloud2> ("output", max_queue_size_);
00068
00069
00070 sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
00071
00072
00073
00074
00075
00076
00077 sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
00078
00079 sub_model_.subscribe (*pnh_, "model", max_queue_size_);
00080
00081 if (approximate_sync_)
00082 {
00083 sync_input_indices_model_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<PointCloud2, PointIndices, ModelCoefficients> > > (max_queue_size_);
00084 sync_input_indices_model_a_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_);
00085 sync_input_indices_model_a_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3));
00086 }
00087 else
00088 {
00089 sync_input_indices_model_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<PointCloud2, PointIndices, ModelCoefficients> > > (max_queue_size_);
00090 sync_input_indices_model_e_->connectInput (sub_input_filter_, sub_indices_filter_, sub_model_);
00091 sync_input_indices_model_e_->registerCallback (bind (&ProjectInliers::input_indices_model_callback, this, _1, _2, _3));
00092 }
00093
00094 NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
00095 " - model_type : %d\n"
00096 " - copy_all_data : %s\n"
00097 " - copy_all_fields : %s",
00098 getName ().c_str (),
00099 model_type, (copy_all_data) ? "true" : "false", (copy_all_fields) ? "true" : "false");
00100
00101
00102 impl_.setModelType (model_type);
00103 impl_.setCopyAllFields (copy_all_fields);
00104 impl_.setCopyAllData (copy_all_data);
00105 }
00106
00108 void
00109 pcl_ros::ProjectInliers::input_indices_model_callback (const PointCloud2::ConstPtr &cloud,
00110 const PointIndicesConstPtr &indices,
00111 const ModelCoefficientsConstPtr &model)
00112 {
00113 if (pub_output_.getNumSubscribers () <= 0)
00114 return;
00115
00116 if (!isValid (model) || !isValid (indices) || !isValid (cloud))
00117 {
00118 NODELET_ERROR ("[%s::input_indices_model_callback] Invalid input!", getName ().c_str ());
00119 return;
00120 }
00121
00122 NODELET_DEBUG ("[%s::input_indices_model_callback]\n"
00123 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00124 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.\n"
00125 " - ModelCoefficients with %zu values, stamp %f, and frame %s on topic %s received.",
00126 getName ().c_str (),
00127 cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00128 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("inliers").c_str (),
00129 model->values.size (), model->header.stamp.toSec (), model->header.frame_id.c_str (), pnh_->resolveName ("model").c_str ());
00130
00131 tf_input_orig_frame_ = cloud->header.frame_id;
00132
00133 IndicesConstPtr vindices;
00134 if (indices)
00135 vindices = boost::make_shared <std::vector<int> > (indices->indices);
00136
00137 model_ = model;
00138 computePublish (cloud, vindices);
00139 }
00140
00141 typedef pcl_ros::ProjectInliers ProjectInliers;
00142 PLUGINLIB_DECLARE_CLASS (pcl, ProjectInliers, ProjectInliers, nodelet::Nodelet);
00143