Go to the documentation of this file.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/passthrough.h"
00040 
00042 bool
00043 pcl_ros::PassThrough::child_init (ros::NodeHandle &nh, bool &has_service)
00044 {
00045   
00046   has_service = true;
00047   srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (nh);
00048   dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&PassThrough::config_callback, this, _1, _2);
00049   srv_->setCallback (f);
00050 
00051   return (true);
00052 }
00053 
00055 void
00056 pcl_ros::PassThrough::config_callback (pcl_ros::FilterConfig &config, uint32_t level)
00057 {
00058   boost::mutex::scoped_lock lock (mutex_);
00059 
00060   double filter_min, filter_max;
00061   impl_.getFilterLimits (filter_min, filter_max);
00062 
00063   
00064   if (filter_min != config.filter_limit_min)
00065   {
00066     filter_min = config.filter_limit_min;
00067     NODELET_DEBUG ("[%s::config_callback] Setting the minimum filtering value a point will be considered from to: %f.", getName ().c_str (), filter_min);
00068     
00069     impl_.setFilterLimits (filter_min, filter_max);
00070   }
00071   
00072   if (filter_max != config.filter_limit_max)
00073   {
00074     filter_max = config.filter_limit_max;
00075     NODELET_DEBUG ("[%s::config_callback] Setting the maximum filtering value a point will be considered from to: %f.", getName ().c_str (), filter_max);
00076     
00077     impl_.setFilterLimits (filter_min, filter_max);
00078   }
00079 
00080   
00081   
00082   if (impl_.getFilterFieldName () != config.filter_field_name)
00083   {
00084     
00085     impl_.setFilterFieldName (config.filter_field_name);
00086     NODELET_DEBUG ("[%s::config_callback] Setting the filter field name to: %s.", getName ().c_str (), config.filter_field_name.c_str ());
00087   }
00088 
00089   
00090   if (impl_.getKeepOrganized () != config.keep_organized)
00091   {
00092     NODELET_DEBUG ("[%s::config_callback] Setting the filter keep_organized value to: %s.", getName ().c_str (), config.keep_organized ? "true" : "false");
00093     
00094     impl_.setKeepOrganized (config.keep_organized);
00095   }
00096 
00097   
00098   if (impl_.getFilterLimitsNegative () != config.filter_limit_negative)
00099   {
00100     NODELET_DEBUG ("[%s::config_callback] Setting the filter negative flag to: %s.", getName ().c_str (), config.filter_limit_negative ? "true" : "false");
00101     
00102     impl_.setFilterLimitsNegative (config.filter_limit_negative);
00103   }
00104 
00105   
00106   if (tf_input_frame_ != config.input_frame)
00107   {
00108     tf_input_frame_ = config.input_frame;
00109     NODELET_DEBUG ("[%s::config_callback] Setting the input TF frame to: %s.", getName ().c_str (), tf_input_frame_.c_str ());
00110   }
00111   if (tf_output_frame_ != config.output_frame)
00112   {
00113     tf_output_frame_ = config.output_frame;
00114     NODELET_DEBUG ("[%s::config_callback] Setting the output TF frame to: %s.", getName ().c_str (), tf_output_frame_.c_str ());
00115   }
00116 }
00117 
00118 typedef pcl_ros::PassThrough PassThrough;
00119 PLUGINLIB_EXPORT_CLASS(PassThrough,nodelet::Nodelet);
00120