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(){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)
122  {
123  string_map_t::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  value = std::string(it->second);
135  return true;
136  }
137 
142  bool getParam(const std::string& name, bool& value)
143  {
144  string_map_t::iterator it = params_.find(name);
145  if (it == params_.end())
146  {
147  return false;
148  }
149 
150  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeBoolean)
151  {
152  return false;
153  }
154 
155  value = (bool)(it->second);
156  return true;
157  }
158 
163  bool getParam(const std::string&name, double& value)
164  {
165  string_map_t::iterator it = params_.find(name);
166  if (it == params_.end())
167  {
168  return false;
169  }
170 
171  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeDouble && it->second.getType() != XmlRpc::XmlRpcValue::TypeInt)
172  {
173  return false;
174  }
175 
176  value = it->second.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(it->second) : (double)(it->second);
177  return true;
178  }
179 
184  bool getParam(const std::string&name, int& value)
185  {
186  string_map_t::iterator it = params_.find(name);
187  if (it == params_.end())
188  {
189  return false;
190  }
191 
192  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeInt)
193  {
194  return false;
195  }
196 
197  value = it->second;
198  return true;
199  }
200 
205  bool getParam(const std::string&name, unsigned int& value)
206  {
207  int signed_value;
208  if (!getParam(name, signed_value))
209  return false;
210  if (signed_value < 0)
211  return false;
212  value = signed_value;
213  return true;
214  };
215 
220  bool getParam(const std::string&name, std::vector<double>& value)
221  {
222  string_map_t::iterator it = params_.find(name);
223  if (it == params_.end())
224  {
225  return false;
226  }
227 
228  value.clear();
229 
230  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeArray)
231  {
232  return false;
233  }
234 
235  XmlRpc::XmlRpcValue double_array = it->second;
236 
237  for (int i = 0; i < double_array.size(); ++i){
238  if(double_array[i].getType() != XmlRpc::XmlRpcValue::TypeDouble && double_array[i].getType() != XmlRpc::XmlRpcValue::TypeInt)
239  {
240  return false;
241  }
242 
243  double double_value = double_array[i].getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(double_array[i]) : (double)(double_array[i]);
244  value.push_back(double_value);
245  }
246 
247  return true;
248  }
249 
254  bool getParam(const std::string&name, std::vector<std::string>& value)
255  {
256  string_map_t::iterator it = params_.find(name);
257  if (it == params_.end())
258  {
259  return false;
260  }
261 
262  value.clear();
263 
264  if(it->second.getType() != XmlRpc::XmlRpcValue::TypeArray)
265  {
266  return false;
267  }
268 
269  XmlRpc::XmlRpcValue string_array = it->second;
270 
271  for (unsigned int i = 0; i < string_array.size(); ++i){
272  if(string_array[i].getType() != XmlRpc::XmlRpcValue::TypeString)
273  {
274  return false;
275  }
276 
277  value.push_back(string_array[i]);
278  }
279 
280  return true;
281  }
282 
287  bool getParam(const std::string& name, XmlRpc::XmlRpcValue& value)
288  {
289  string_map_t::iterator it = params_.find(name);
290  if (it == params_.end())
291  {
292  return false;
293  }
294 
295  value = it->second;
296  return true;
297  }
298 
300  std::string filter_name_;
302  std::string filter_type_;
305 
307  string_map_t params_;
308 
309 private:
314  {
315  if(!config.hasMember("name"))
316  {
317  ROS_ERROR("Filter didn't have name defined, other strings are not allowed");
318  return false;
319  }
320 
321  std::string name = config["name"];
322 
323  if(!config.hasMember("type"))
324  {
325  ROS_ERROR("Filter %s didn't have type defined, other strings are not allowed", name.c_str());
326  return false;
327  }
328 
329  std::string type = config["type"];
330 
331  filter_name_ = name;
332  filter_type_ = type;
333  ROS_DEBUG("Configuring Filter of Type: %s with name %s", type.c_str(), name.c_str());
334  return true;
335  }
336 
337 protected:
339  {
341  {
342  ROS_ERROR("A filter configuration must be a map with fields name, type, and params");
343  return false;
344  }
345 
346  if (!setNameAndType(config))
347  {
348  return false;
349  }
350 
351  //check to see if we have parameters in our list
352  if(config.hasMember("params"))
353  {
354  //get the params map
355  XmlRpc::XmlRpcValue params = config["params"];
356 
358  {
359  ROS_ERROR("params must be a map");
360  return false;
361  }
362  else{
363  //Load params into map
364  for(XmlRpc::XmlRpcValue::iterator it = params.begin(); it != params.end(); ++it)
365  {
366  ROS_DEBUG("Loading param %s\n", it->first.c_str());
367  params_[it->first] = it->second;
368  }
369  }
370  }
371 
372  return true;
373  }
374 };
375 
376 
377 template <typename T>
379 {
380 public:
381  MultiChannelFilterBase():number_of_channels_(0){};
382 
388  bool configure(unsigned int number_of_channels, const std::string& param_name, ros::NodeHandle node_handle = ros::NodeHandle())
389  {
390  XmlRpc::XmlRpcValue config;
391  if (!node_handle.getParam(param_name, config))
392  {
393  ROS_ERROR("Could not find parameter %s on the server, are you sure that it was pushed up correctly?", param_name.c_str());
394  return false;
395  }
396  return configure(number_of_channels, config);
397 
398  }
399 
400 
405  bool configure(unsigned int number_of_channels, XmlRpc::XmlRpcValue& config)
406  {
407  ROS_DEBUG("FilterBase being configured with XmlRpc xml: %s type: %d", config.toXml().c_str(), config.getType());
408  if (configured_)
409  {
410  ROS_WARN("Filter %s of type %s already being reconfigured", filter_name_.c_str(), filter_type_.c_str());
411  };
412  configured_ = false;
413  number_of_channels_ = number_of_channels;
414  ROS_DEBUG("MultiChannelFilterBase configured with %d channels", number_of_channels_);
415  bool retval = true;
416 
417  retval = retval && FilterBase<T>::loadConfiguration(config);
418  retval = retval && configure();
419  configured_ = retval;
420  return retval;
421  };
422 
423 
426  {
427  ROS_ERROR("MultiChannelFilterBase configure should be called with a number of channels argument, assuming 1");
428  return configure(1, config);
429  }
430 
431  virtual bool configure()=0;
432 
433 
439  virtual bool update(const std::vector<T>& data_in, std::vector<T>& data_out)=0;
440 
441  virtual bool update(const T& data_in, T& data_out)
442  {
443  ROS_ERROR("THIS IS A MULTI FILTER DON'T CALL SINGLE FORM OF UPDATE");
444  return false;
445  };
446 
447 
448 protected:
452 
454  unsigned int number_of_channels_;
455 
456 
457 };
458 
459 }
460 #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
ValueStruct::iterator iterator
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:300
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:388
int size() const
std::map< std::string, XmlRpc::XmlRpcValue > string_map_t
Definition: filter_base.h:44
FilterBase()
Default constructor used by Filter Factories.
Definition: filter_base.h:55
bool configured_
Whether the filter has been configured.
Definition: filter_base.h:304
const std::string & getName()
Get the name of the filter as a string.
Definition: filter_base.h:106
Type const & getType() const
#define ROS_WARN(...)
bool getParam(const std::string &name, bool &value)
Get a filter parameter as a boolean.
Definition: filter_base.h:142
bool getParam(const std::string &name, unsigned int &value)
Get a filter parameter as an unsigned int.
Definition: filter_base.h:205
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 getParam(const std::string &name, std::string &value)
Get a filter parameter as a string.
Definition: filter_base.h:121
bool configure(XmlRpc::XmlRpcValue &config)
The public method to configure a filter from XML.
Definition: filter_base.h:80
std::string toXml() 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:405
bool loadConfiguration(XmlRpc::XmlRpcValue &config)
Definition: filter_base.h:338
string_map_t params_
Storage of the parsed xml parameters.
Definition: filter_base.h:307
unsigned int number_of_channels_
How many parallel inputs for which the filter is to be configured.
Definition: filter_base.h:454
bool getParam(const std::string &name, XmlRpc::XmlRpcValue &value)
Get a filter parameter as a XmlRpcValue.
Definition: filter_base.h:287
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:441
bool getParam(const std::string &name, std::vector< std::string > &value)
Get a filter parameter as a std::vector<string>
Definition: filter_base.h:254
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 hasMember(const std::string &name) const
bool getParam(const std::string &name, std::vector< double > &value)
Get a filter parameter as a std::vector<double>
Definition: filter_base.h:220
bool getParam(const std::string &name, int &value)
Get a filter parameter as a int.
Definition: filter_base.h:184
std::string filter_type_
The type of the filter (Used by FilterChain for Factory construction)
Definition: filter_base.h:302
bool getParam(const std::string &name, double &value)
Get a filter parameter as a double.
Definition: filter_base.h:163
bool setNameAndType(XmlRpc::XmlRpcValue &config)
Set the name and type of the filter from the parameter server.
Definition: filter_base.h:313
bool configure(XmlRpc::XmlRpcValue &config)
A method to hide the base class method and warn if improperly called.
Definition: filter_base.h:425
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


filters
Author(s):
autogenerated on Sat Jun 8 2019 04:37:52