passthrough.cpp
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: passthrough.cpp 36194 2011-02-23 07:49:21Z rusu $
35  *
36  */
37 
40 
42 bool
44 {
45  // Enable the dynamic reconfigure service
46  has_service = true;
47  srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (nh);
48  dynamic_reconfigure::Server<pcl_ros::FilterConfig>::CallbackType f = boost::bind (&PassThrough::config_callback, this, _1, _2);
49  srv_->setCallback (f);
50 
51  return (true);
52 }
53 
55 void
56 pcl_ros::PassThrough::config_callback (pcl_ros::FilterConfig &config, uint32_t /*level*/)
57 {
58  boost::mutex::scoped_lock lock (mutex_);
59 
60  double filter_min, filter_max;
61  impl_.getFilterLimits (filter_min, filter_max);
62 
63  // Check the current values for filter min-max
64  if (filter_min != config.filter_limit_min)
65  {
66  filter_min = config.filter_limit_min;
67  NODELET_DEBUG ("[%s::config_callback] Setting the minimum filtering value a point will be considered from to: %f.", getName ().c_str (), filter_min);
68  // Set the filter min-max if different
69  impl_.setFilterLimits (filter_min, filter_max);
70  }
71  // Check the current values for filter min-max
72  if (filter_max != config.filter_limit_max)
73  {
74  filter_max = config.filter_limit_max;
75  NODELET_DEBUG ("[%s::config_callback] Setting the maximum filtering value a point will be considered from to: %f.", getName ().c_str (), filter_max);
76  // Set the filter min-max if different
77  impl_.setFilterLimits (filter_min, filter_max);
78  }
79 
80  // Check the current value for the filter field
81  //std::string filter_field = impl_.getFilterFieldName ();
82  if (impl_.getFilterFieldName () != config.filter_field_name)
83  {
84  // Set the filter field if different
85  impl_.setFilterFieldName (config.filter_field_name);
86  NODELET_DEBUG ("[%s::config_callback] Setting the filter field name to: %s.", getName ().c_str (), config.filter_field_name.c_str ());
87  }
88 
89  // Check the current value for keep_organized
90  if (impl_.getKeepOrganized () != config.keep_organized)
91  {
92  NODELET_DEBUG ("[%s::config_callback] Setting the filter keep_organized value to: %s.", getName ().c_str (), config.keep_organized ? "true" : "false");
93  // Call the virtual method in the child
94  impl_.setKeepOrganized (config.keep_organized);
95  }
96 
97  // Check the current value for the negative flag
98 #if PCL_VERSION_COMPARE(<, 1, 10, 0)
99  if (impl_.getFilterLimitsNegative () != config.filter_limit_negative)
100 #else
101  if (impl_.getNegative () != config.filter_limit_negative)
102 #endif
103  {
104  NODELET_DEBUG ("[%s::config_callback] Setting the filter negative flag to: %s.", getName ().c_str (), config.filter_limit_negative ? "true" : "false");
105  // Call the virtual method in the child
106 #if PCL_VERSION_COMPARE(<, 1, 10, 0)
107  impl_.setFilterLimitsNegative (config.filter_limit_negative);
108 #else
109  impl_.setNegative (config.filter_limit_negative);
110 #endif
111  }
112 
113  // The following parameters are updated automatically for all PCL_ROS Nodelet Filters as they are inexistent in PCL
114  if (tf_input_frame_ != config.input_frame)
115  {
116  tf_input_frame_ = config.input_frame;
117  NODELET_DEBUG ("[%s::config_callback] Setting the input TF frame to: %s.", getName ().c_str (), tf_input_frame_.c_str ());
118  }
119  if (tf_output_frame_ != config.output_frame)
120  {
121  tf_output_frame_ = config.output_frame;
122  NODELET_DEBUG ("[%s::config_callback] Setting the output TF frame to: %s.", getName ().c_str (), tf_output_frame_.c_str ());
123  }
124 }
125 
128 
pcl_ros::PassThrough
PassThrough uses the base Filter class methods to pass through all data that satisfies the user given...
Definition: passthrough.h:51
pcl_ros::PassThrough::child_init
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Definition: passthrough.cpp:43
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
PassThrough
pcl_ros::PassThrough PassThrough
Definition: passthrough.cpp:126
f
f
passthrough.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
nodelet::Nodelet
class_list_macros.hpp
pcl_ros::PassThrough::config_callback
void config_callback(pcl_ros::FilterConfig &config, uint32_t level)
Dynamic reconfigure service callback.
Definition: passthrough.cpp:56
pcl_ros::PassThrough::srv_
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::FilterConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: passthrough.h:55
ros::NodeHandle
NODELET_DEBUG
#define NODELET_DEBUG(...)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40