filter_base.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef FILTERS_FILTER_BASE_H_
31 #define FILTERS_FILTER_BASE_H_
32 
33 #include <typeinfo>
34 #include "ros/assert.h"
35 #include "ros/console.h"
36 #include "ros/ros.h"
37 
38 #include "boost/scoped_ptr.hpp"
39 #include <boost/algorithm/string.hpp>
40 
41 namespace filters
42 {
43 
44 typedef std::map<std::string, XmlRpc::XmlRpcValue> string_map_t;
45 
49 template<typename T>
51 {
52 public:
55  FilterBase():configured_(false){};
56 
59  virtual ~FilterBase(){};
60 
65  bool configure(const std::string& param_name, ros::NodeHandle node_handle = ros::NodeHandle())
66  {
67  XmlRpc::XmlRpcValue config;
68  if (!node_handle.getParam(param_name, config))
69  {
70  ROS_ERROR("Could not find parameter %s on the server, are you sure that it was pushed up correctly?", param_name.c_str());
71  return false;
72  }
73  return configure(config);
74 
75  }
76 
81  {
82  if (configured_)
83  {
84  ROS_WARN("Filter %s of type %s already being reconfigured", filter_name_.c_str(), filter_type_.c_str());
85  };
86  configured_ = false;
87  bool retval = true;
88 
89  retval = retval && loadConfiguration(config);
90  retval = retval && configure();
91  configured_ = retval;
92  return retval;
93  }
94 
100  virtual bool update(const T& data_in, T& data_out)=0;
101 
103  std::string getType() {return filter_type_;};
104 
106  inline const std::string& getName() const {return filter_name_;};
107 
108 
109 protected:
110 
114  virtual bool configure()=0;
115 
116 
121  bool getParam(const std::string& name, std::string& value) const
122  {
123  string_map_t::const_iterator it = params_.find(name);
124  if (it == params_.end())
125  {
126  return false;
127  }
128 
129  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeString)
130  {
131  return false;
132  }
133 
134  auto tmp = it->second;
135  value = std::string(tmp);
136  return true;
137  }
138 
143  bool getParam(const std::string& name, bool& value) const
144  {
145  string_map_t::const_iterator it = params_.find(name);
146  if (it == params_.end())
147  {
148  return false;
149  }
150 
151  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeBoolean)
152  {
153  return false;
154  }
155 
156  auto tmp = it->second;
157  value = (bool)(tmp);
158  return true;
159  }
160 
165  bool getParam(const std::string&name, double& value) const
166  {
167  string_map_t::const_iterator it = params_.find(name);
168  if (it == params_.end())
169  {
170  return false;
171  }
172 
173  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeDouble && it->second.getType() != XmlRpc::XmlRpcValue::TypeInt)
174  {
175  return false;
176  }
177 
178  auto tmp = it->second;
179  value = it->second.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(tmp) : (double)(tmp);
180  return true;
181  }
182 
187  bool getParam(const std::string&name, int& value) const
188  {
189  string_map_t::const_iterator it = params_.find(name);
190  if (it == params_.end())
191  {
192  return false;
193  }
194 
195  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeInt)
196  {
197  return false;
198  }
199 
200  auto tmp = it->second;
201  value = tmp;
202  return true;
203  }
204 
209  bool getParam(const std::string&name, unsigned int& value) const
210  {
211  int signed_value;
212  if (!getParam(name, signed_value))
213  return false;
214  if (signed_value < 0)
215  return false;
216  value = signed_value;
217  return true;
218  };
219 
224  bool getParam(const std::string&name, std::vector<double>& value) const
225  {
226  string_map_t::const_iterator it = params_.find(name);
227  if (it == params_.end())
228  {
229  return false;
230  }
231 
232  value.clear();
233 
234  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeArray)
235  {
236  return false;
237  }
238 
239  XmlRpc::XmlRpcValue double_array = it->second;
240 
241  for (int i = 0; i < double_array.size(); ++i){
242  if(double_array[i].getType() != XmlRpc::XmlRpcValue::TypeDouble && double_array[i].getType() != XmlRpc::XmlRpcValue::TypeInt)
243  {
244  return false;
245  }
246 
247  double double_value = double_array[i].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(double_array[i]) : (double)(double_array[i]);
248  value.push_back(double_value);
249  }
250 
251  return true;
252  }
253 
258  bool getParam(const std::string&name, std::vector<std::string>& value) const
259  {
260  string_map_t::const_iterator it = params_.find(name);
261  if (it == params_.end())
262  {
263  return false;
264  }
265 
266  value.clear();
267 
268  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeArray)
269  {
270  return false;
271  }
272 
273  XmlRpc::XmlRpcValue string_array = it->second;
274 
275  for (unsigned int i = 0; i < string_array.size(); ++i){
276  if(string_array[i].getType() != XmlRpc::XmlRpcValue::TypeString)
277  {
278  return false;
279  }
280 
281  value.push_back(string_array[i]);
282  }
283 
284  return true;
285  }
286 
291  bool getParam(const std::string& name, XmlRpc::XmlRpcValue& value) const
292  {
293  string_map_t::const_iterator it = params_.find(name);
294  if (it == params_.end())
295  {
296  return false;
297  }
298 
299  auto tmp = it->second;
300  value = tmp;
301  return true;
302  }
303 
305  std::string filter_name_;
307  std::string filter_type_;
310 
312  string_map_t params_;
313 
314 private:
319  {
320  if(!config.hasMember("name"))
321  {
322  ROS_ERROR("Filter didn't have name defined, other strings are not allowed");
323  return false;
324  }
325 
326  std::string name = config["name"];
327 
328  if(!config.hasMember("type"))
329  {
330  ROS_ERROR("Filter %s didn't have type defined, other strings are not allowed", name.c_str());
331  return false;
332  }
333 
334  std::string type = config["type"];
335 
336  filter_name_ = name;
337  filter_type_ = type;
338  ROS_DEBUG("Configuring Filter of Type: %s with name %s", type.c_str(), name.c_str());
339  return true;
340  }
341 
342 protected:
344  {
346  {
347  ROS_ERROR("A filter configuration must be a map with fields name, type, and params");
348  return false;
349  }
350 
351  if (!setNameAndType(config))
352  {
353  return false;
354  }
355 
356  //check to see if we have parameters in our list
357  if(config.hasMember("params"))
358  {
359  //get the params map
360  XmlRpc::XmlRpcValue params = config["params"];
361 
363  {
364  ROS_ERROR("params must be a map");
365  return false;
366  }
367  else{
368  //Load params into map
369  for(XmlRpc::XmlRpcValue::iterator it = params.begin(); it != params.end(); ++it)
370  {
371  ROS_DEBUG("Loading param %s\n", it->first.c_str());
372  params_[it->first] = it->second;
373  }
374  }
375  }
376 
377  return true;
378  }
379 };
380 
381 
382 template <typename T>
384 {
385 public:
386  MultiChannelFilterBase():number_of_channels_(0){};
387 
393  bool configure(unsigned int number_of_channels, const std::string& param_name, ros::NodeHandle node_handle = ros::NodeHandle())
394  {
395  XmlRpc::XmlRpcValue config;
396  if (!node_handle.getParam(param_name, config))
397  {
398  ROS_ERROR("Could not find parameter %s on the server, are you sure that it was pushed up correctly?", param_name.c_str());
399  return false;
400  }
401  return configure(number_of_channels, config);
402 
403  }
404 
405 
410  bool configure(unsigned int number_of_channels, XmlRpc::XmlRpcValue& config)
411  {
412  ROS_DEBUG("FilterBase being configured with XmlRpc xml: %s type: %d", config.toXml().c_str(), config.getType());
413  if (configured_)
414  {
415  ROS_WARN("Filter %s of type %s already being reconfigured", filter_name_.c_str(), filter_type_.c_str());
416  };
417  configured_ = false;
418  number_of_channels_ = number_of_channels;
419  ROS_DEBUG("MultiChannelFilterBase configured with %d channels", number_of_channels_);
420  bool retval = true;
421 
422  retval = retval && FilterBase<T>::loadConfiguration(config);
423  retval = retval && configure();
424  configured_ = retval;
425  return retval;
426  };
427 
428 
431  {
432  ROS_ERROR("MultiChannelFilterBase configure should be called with a number of channels argument, assuming 1");
433  return configure(1, config);
434  }
435 
436  virtual bool configure()=0;
437 
438 
444  virtual bool update(const std::vector<T>& data_in, std::vector<T>& data_out)=0;
445 
446  virtual bool update(const T& data_in, T& data_out)
447  {
448  ROS_ERROR("THIS IS A MULTI FILTER DON'T CALL SINGLE FORM OF UPDATE");
449  return false;
450  };
451 
452 
453 protected:
457 
459  unsigned int number_of_channels_;
460 
461 
462 };
463 
464 }
465 #endif //#ifndef FILTERS_FILTER_BASE_H_
bool configure(const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
Definition: filter_base.h:65
bool getParam(const std::string &name, std::vector< double > &value) const
Get a filter parameter as a std::vector<double>
Definition: filter_base.h:224
ValueStruct::iterator iterator
bool getParam(const std::string &name, std::vector< std::string > &value) const
Get a filter parameter as a std::vector<string>
Definition: filter_base.h:258
A Base filter class to provide a standard interface for all filters.
Definition: filter_base.h:50
std::string filter_name_
The name of the filter.
Definition: filter_base.h:305
bool configure(unsigned int number_of_channels, const std::string &param_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
Definition: filter_base.h:393
std::map< std::string, XmlRpc::XmlRpcValue > string_map_t
Definition: filter_base.h:44
const std::string & getName() const
Get the name of the filter as a string.
Definition: filter_base.h:106
FilterBase()
Default constructor used by Filter Factories.
Definition: filter_base.h:55
bool configured_
Whether the filter has been configured.
Definition: filter_base.h:309
bool getParam(const std::string &name, bool &value) const
Get a filter parameter as a boolean.
Definition: filter_base.h:143
#define ROS_WARN(...)
virtual bool update(const T &data_in, T &data_out)=0
Update the filter and return the data seperately This is an inefficient way to do this and can be ove...
bool configure(XmlRpc::XmlRpcValue &config)
The public method to configure a filter from XML.
Definition: filter_base.h:80
Type const & getType() const
std::string getType()
Get the type of the filter as a string.
Definition: filter_base.h:103
bool configure(unsigned int number_of_channels, XmlRpc::XmlRpcValue &config)
The public method to configure a filter from XML.
Definition: filter_base.h:410
bool loadConfiguration(XmlRpc::XmlRpcValue &config)
Definition: filter_base.h:343
string_map_t params_
Storage of the parsed xml parameters.
Definition: filter_base.h:312
unsigned int number_of_channels_
How many parallel inputs for which the filter is to be configured.
Definition: filter_base.h:459
bool getParam(const std::string &name, std::string &value) const
Get a filter parameter as a string.
Definition: filter_base.h:121
virtual bool update(const T &data_in, T &data_out)
Update the filter and return the data seperately This is an inefficient way to do this and can be ove...
Definition: filter_base.h:446
virtual bool configure()=0
Pure virtual function for the sub class to configure the filter This function must be implemented in ...
virtual ~FilterBase()
Virtual Destructor.
Definition: filter_base.h:59
bool getParam(const std::string &name, int &value) const
Get a filter parameter as a int.
Definition: filter_base.h:187
std::string toXml() const
std::string filter_type_
The type of the filter (Used by FilterChain for Factory construction)
Definition: filter_base.h:307
bool getParam(const std::string &name, double &value) const
Get a filter parameter as a double.
Definition: filter_base.h:165
bool getParam(const std::string &name, XmlRpc::XmlRpcValue &value) const
Get a filter parameter as a XmlRpcValue.
Definition: filter_base.h:291
bool setNameAndType(XmlRpc::XmlRpcValue &config)
Set the name and type of the filter from the parameter server.
Definition: filter_base.h:318
bool configure(XmlRpc::XmlRpcValue &config)
A method to hide the base class method and warn if improperly called.
Definition: filter_base.h:430
bool getParam(const std::string &name, unsigned int &value) const
Get a filter parameter as an unsigned int.
Definition: filter_base.h:209
#define ROS_ERROR(...)
bool hasMember(const std::string &name) const
#define ROS_DEBUG(...)


filters
Author(s):
autogenerated on Wed May 11 2022 02:40:46