filter.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: filter.cpp 35876 2011-02-09 01:04:36Z rusu $
00035  *
00036  */
00037 
00038 #include <pcl/io/io.h>
00039 #include "pcl_ros/transforms.h"
00040 #include "pcl_ros/filters/filter.h"
00041 
00042 /*//#include <pcl/filters/pixel_grid.h>
00043 //#include <pcl/filters/filter_dimension.h>
00044 */
00045 
00046 /*//typedef pcl::PixelGrid PixelGrid;
00047 //typedef pcl::FilterDimension FilterDimension;
00048 */
00049 
00050 // Include the implementations instead of compiling them separately to speed up compile time
00051 //#include "extract_indices.cpp"
00052 //#include "passthrough.cpp"
00053 //#include "project_inliers.cpp"
00054 //#include "radius_outlier_removal.cpp"
00055 //#include "statistical_outlier_removal.cpp"
00056 //#include "voxel_grid.cpp"
00057 
00058 /*//PLUGINLIB_EXPORT_CLASS(PixelGrid,nodelet::Nodelet);
00059 //PLUGINLIB_EXPORT_CLASS(FilterDimension,nodelet::Nodelet);
00060 */
00061 
00063 void
00064 pcl_ros::Filter::computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
00065 {
00066   PointCloud2 output;
00067   // Call the virtual method in the child
00068   filter (input, indices, output);
00069 
00070   PointCloud2::Ptr cloud_tf (new PointCloud2 (output));   // set the output by default
00071   // Check whether the user has given a different output TF frame
00072   if (!tf_output_frame_.empty () && output.header.frame_id != tf_output_frame_)
00073   {
00074     NODELET_DEBUG ("[%s::computePublish] Transforming output dataset from %s to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_output_frame_.c_str ());
00075     // Convert the cloud into the different frame
00076     PointCloud2 cloud_transformed;
00077     if (!pcl_ros::transformPointCloud (tf_output_frame_, output, cloud_transformed, tf_listener_))
00078     {
00079       NODELET_ERROR ("[%s::computePublish] Error converting output dataset from %s to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_output_frame_.c_str ());
00080       return;
00081     }
00082     cloud_tf.reset (new PointCloud2 (cloud_transformed));
00083   }
00084   if (tf_output_frame_.empty () && output.header.frame_id != tf_input_orig_frame_)
00085   // no tf_output_frame given, transform the dataset to its original frame
00086   {
00087     NODELET_DEBUG ("[%s::computePublish] Transforming output dataset from %s back to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_input_orig_frame_.c_str ());
00088     // Convert the cloud into the different frame
00089     PointCloud2 cloud_transformed;
00090     if (!pcl_ros::transformPointCloud (tf_input_orig_frame_, output, cloud_transformed, tf_listener_))
00091     {
00092       NODELET_ERROR ("[%s::computePublish] Error converting output dataset from %s back to %s.", getName ().c_str (), output.header.frame_id.c_str (), tf_input_orig_frame_.c_str ());
00093       return;
00094     }
00095     cloud_tf.reset (new PointCloud2 (cloud_transformed));
00096   }
00097 
00098   // Copy timestamp to keep it
00099   cloud_tf->header.stamp = input->header.stamp;
00100   
00101   // Publish a boost shared ptr
00102   pub_output_.publish (cloud_tf);
00103 }
00104 
00106 void
00107 pcl_ros::Filter::onInit ()
00108 {
00109   // Call the super onInit ()
00110   PCLNodelet::onInit ();
00111 
00112   // Call the child's local init
00113   bool has_service = false;
00114   if (!child_init (*pnh_, has_service))
00115   {
00116     NODELET_ERROR ("[%s::onInit] Initialization failed.", getName ().c_str ());
00117     return;
00118   }
00119 
00120   pub_output_ = pnh_->advertise<PointCloud2> ("output", max_queue_size_);
00121 
00122   // Enable the dynamic reconfigure service
00123   if (!has_service)
00124   {
00125     srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (*pnh_);
00126     dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f =  boost::bind (&Filter::config_callback, this, _1, _2);
00127     srv_->setCallback (f);
00128   }
00129 
00130   // If we're supposed to look for PointIndices (indices)
00131   if (use_indices_)
00132   {
00133     // Subscribe to the input using a filter
00134     sub_input_filter_.subscribe (*pnh_, "input", max_queue_size_);
00135     sub_indices_filter_.subscribe (*pnh_, "indices", max_queue_size_);
00136 
00137     if (approximate_sync_)
00138     {
00139       sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
00140       sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
00141       sync_input_indices_a_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
00142     }
00143     else
00144     {
00145       sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud2, pcl_msgs::PointIndices> > >(max_queue_size_);
00146       sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
00147       sync_input_indices_e_->registerCallback (bind (&Filter::input_indices_callback, this, _1, _2));
00148     }
00149   }
00150   else
00151     // Subscribe in an old fashion to input only (no filters)
00152     sub_input_ = pnh_->subscribe<sensor_msgs::PointCloud2> ("input", max_queue_size_,  bind (&Filter::input_indices_callback, this, _1, pcl_msgs::PointIndicesConstPtr ()));
00153 
00154   NODELET_DEBUG ("[%s::onInit] Nodelet successfully created.", getName ().c_str ());
00155 }
00156 
00158 void
00159 pcl_ros::Filter::config_callback (pcl_ros::FilterConfig &config, uint32_t level)
00160 {
00161   // The following parameters are updated automatically for all PCL_ROS Nodelet Filters as they are inexistent in PCL
00162   if (tf_input_frame_ != config.input_frame)
00163   {
00164     tf_input_frame_ = config.input_frame;
00165     NODELET_DEBUG ("[%s::config_callback] Setting the input TF frame to: %s.", getName ().c_str (), tf_input_frame_.c_str ());
00166   }
00167   if (tf_output_frame_ != config.output_frame)
00168   {
00169     tf_output_frame_ = config.output_frame;
00170     NODELET_DEBUG ("[%s::config_callback] Setting the output TF frame to: %s.", getName ().c_str (), tf_output_frame_.c_str ());
00171   }
00172 }
00173 
00175 void
00176 pcl_ros::Filter::input_indices_callback (const PointCloud2::ConstPtr &cloud, const PointIndicesConstPtr &indices)
00177 {
00178   // No subscribers, no work
00179   if (pub_output_.getNumSubscribers () <= 0)
00180     return;
00181 
00182   // If cloud is given, check if it's valid
00183   if (!isValid (cloud))
00184   {
00185     NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
00186     return;
00187   }
00188   // If indices are given, check if they are valid
00189   if (indices && !isValid (indices))
00190   {
00191     NODELET_ERROR ("[%s::input_indices_callback] Invalid indices!", getName ().c_str ());
00192     return;
00193   }
00194 
00196   if (indices)
00197     NODELET_DEBUG ("[%s::input_indices_callback]\n"
00198                    "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
00199                    "                                 - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
00200                    getName ().c_str (), 
00201                    cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
00202                    indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
00203   else
00204     NODELET_DEBUG ("[%s::input_indices_callback] PointCloud with %d data points and frame %s on topic %s received.", getName ().c_str (), cloud->width * cloud->height, cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ());
00206 
00207   // Check whether the user has given a different input TF frame
00208   tf_input_orig_frame_ = cloud->header.frame_id;
00209   PointCloud2::ConstPtr cloud_tf;
00210   if (!tf_input_frame_.empty () && cloud->header.frame_id != tf_input_frame_)
00211   {
00212     NODELET_DEBUG ("[%s::input_indices_callback] Transforming input dataset from %s to %s.", getName ().c_str (), cloud->header.frame_id.c_str (), tf_input_frame_.c_str ());
00213     // Save the original frame ID
00214     // Convert the cloud into the different frame
00215     PointCloud2 cloud_transformed;
00216     if (!pcl_ros::transformPointCloud (tf_input_frame_, *cloud, cloud_transformed, tf_listener_))
00217     {
00218       NODELET_ERROR ("[%s::input_indices_callback] Error converting input dataset from %s to %s.", getName ().c_str (), cloud->header.frame_id.c_str (), tf_input_frame_.c_str ());
00219       return;
00220     }
00221     cloud_tf = boost::make_shared<PointCloud2> (cloud_transformed);
00222   }
00223   else
00224     cloud_tf = cloud;
00225 
00226   // Need setInputCloud () here because we have to extract x/y/z
00227   IndicesPtr vindices;
00228   if (indices)
00229     vindices.reset (new std::vector<int> (indices->indices));
00230 
00231   computePublish (cloud_tf, vindices);
00232 }
00233 


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Aug 26 2015 15:25:31