filter_chain.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_CHAIN_H_
31 #define FILTERS_FILTER_CHAIN_H_
32 
33 #include "ros/ros.h"
34 #include "filters/filter_base.h"
35 #include <pluginlib/class_loader.h>
36 #include <sstream>
37 #include <vector>
38 #include "boost/shared_ptr.hpp"
39 
40 namespace filters
41 {
42 
46 template <typename T>
48 {
49 private:
51 public:
53  FilterChain(std::string data_type): loader_("filters", std::string("filters::FilterBase<") + data_type + std::string(">")), configured_(false)
54  {
55  std::string lib_string = "";
56  std::vector<std::string> libs = loader_.getDeclaredClasses();
57  for (unsigned int i = 0 ; i < libs.size(); i ++)
58  {
59  lib_string = lib_string + std::string(", ") + libs[i];
60  }
61  ROS_DEBUG("In FilterChain ClassLoader found the following libs: %s", lib_string.c_str());
62  };
63 
65  {
66  clear();
67 
68  };
69 
74  bool configure(std::string param_name, ros::NodeHandle node = ros::NodeHandle())
75  {
76  XmlRpc::XmlRpcValue config;
77  if(node.getParam(param_name + "/filter_chain", config))
78  {
79  std::string resolved_name = node.resolveName(param_name).c_str();
80  ROS_WARN("Filter chains no longer check implicit nested 'filter_chain' parameter. This node is configured to look directly at '%s'. Please move your chain description from '%s/filter_chain' to '%s'", resolved_name.c_str(), resolved_name.c_str(), resolved_name.c_str());
81  }
82  else if(!node.getParam(param_name, config))
83  {
84  ROS_DEBUG("Could not load the filter chain configuration from parameter %s, are you sure it was pushed to the parameter server? Assuming that you meant to leave it empty.", param_name.c_str());
85  configured_ = true;
86  return true;
87  }
88  return this->configure(config, node.getNamespace());
89  }
90 
92  bool update(const T& data_in, T& data_out)
93  {
94  unsigned int list_size = reference_pointers_.size();
95  bool result;
96  if (list_size == 0)
97  {
98  data_out = data_in;
99  result = true;
100  }
101  else if (list_size == 1)
102  result = reference_pointers_[0]->update(data_in, data_out);
103  else if (list_size == 2)
104  {
105  result = reference_pointers_[0]->update(data_in, buffer0_);
106  if (result == false) {return false; };//don't keep processing on failure
107  result = result && reference_pointers_[1]->update(buffer0_, data_out);
108  }
109  else
110  {
111  result = reference_pointers_[0]->update(data_in, buffer0_); //first copy in
112  for (unsigned int i = 1; i < reference_pointers_.size() - 1; i++) // all but first and last (never called if size=2)
113  {
114  if (i %2 == 1)
115  result = result && reference_pointers_[i]->update(buffer0_, buffer1_);
116  else
117  result = result && reference_pointers_[i]->update(buffer1_, buffer0_);
118 
119  if (result == false) {return false; }; //don't keep processing on failure
120  }
121  if (list_size % 2 == 1) // odd number last deposit was in buffer1
122  result = result && reference_pointers_.back()->update(buffer1_, data_out);
123  else
124  result = result && reference_pointers_.back()->update(buffer0_, data_out);
125  }
126  return result;
127 
128  };
130  bool clear()
131  {
132  configured_ = false;
133  reference_pointers_.clear();
134  return true;
135  };
136 
137 
138 
139 
142  bool configure(XmlRpc::XmlRpcValue& config, const std::string& filter_ns)
143  {
144  /*************************** Parse the XmlRpcValue ***********************************/
145  //Verify proper naming and structure
146  if (config.getType() != XmlRpc::XmlRpcValue::TypeArray)
147  {
148  ROS_ERROR("%s: The filter chain specification must be a list. but is of of XmlRpcType %d", filter_ns.c_str(), config.getType());
149  ROS_ERROR("The xml passed in is formatted as follows:\n %s", config.toXml().c_str());
150 
151  return false;
152  }
153 
154  //Iterate over all filter in filters (may be just one)
155  for (int i = 0; i < config.size(); ++i)
156  {
157  if(config[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
158  {
159  ROS_ERROR("%s: Filters must be specified as maps, but they are XmlRpcType:%d", filter_ns.c_str(), config[i].getType());
160  return false;
161  }
162  else if (!config[i].hasMember("type"))
163  {
164  ROS_ERROR("%s: Could not add a filter because no type was given", filter_ns.c_str());
165  return false;
166  }
167  else if (!config[i].hasMember("name"))
168  {
169  ROS_ERROR("%s: Could not add a filter because no name was given", filter_ns.c_str());
170  return false;
171  }
172  else
173  {
174  //Check for name collisions within the list itself.
175  for (int j = i + 1; j < config.size(); ++j)
176  {
177  if(config[j].getType() != XmlRpc::XmlRpcValue::TypeStruct)
178  {
179  ROS_ERROR("%s: Filters must be specified as maps, but they are XmlRpcType:%d", filter_ns.c_str(), config[j].getType());
180  return false;
181  }
182 
183  if(!config[j].hasMember("name")
184  ||config[i]["name"].getType() != XmlRpc::XmlRpcValue::TypeString
185  || config[j]["name"].getType() != XmlRpc::XmlRpcValue::TypeString)
186  {
187  ROS_ERROR("%s: Filters names must be strings, but they are XmlRpcTypes:%d and %d", filter_ns.c_str(), config[i].getType(), config[j].getType());
188  return false;
189  }
190 
191  std::string namei = config[i]["name"];
192  std::string namej = config[j]["name"];
193  if (namei == namej)
194  {
195  ROS_ERROR("%s: A self_filter with the name %s already exists", filter_ns.c_str(), namei.c_str());
196  return false;
197  }
198  }
199 
200 
201  //CHeck for backwards compatible declarations
202  if (std::string(config[i]["type"]).find("/") == std::string::npos)
203  {
204  ROS_WARN("Deprecation Warning: No '/' detected in FilterType, Please update to 1.2 plugin syntax. ");
205  std::vector<std::string> libs = loader_.getDeclaredClasses();
206  for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
207  {
208  size_t position = it->find(std::string(config[i]["type"]));
209  if (position != std::string::npos)
210  {
211  ROS_WARN("Replaced %s with %s", std::string(config[i]["type"]).c_str(), it->c_str());
212  config[i]["type"] = *it;
213  }
214  }
215  }
216  //Make sure the filter chain has a valid type
217  std::vector<std::string> libs = loader_.getDeclaredClasses();
218  bool found = false;
219  for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
220  {
221  if (*it == std::string(config[i]["type"]))
222  {
223  found = true;
224  break;
225  }
226  }
227  if (!found)
228  {
229  ROS_ERROR("Couldn't find filter of type %s", std::string(config[i]["type"]).c_str());
230  return false;
231  }
232 
233  }
234  }
235 
236 
237  bool result = true;
238 
239 
240  for (int i = 0; i < config.size(); ++i)
241  {
242  boost::shared_ptr<filters::FilterBase<T> > p(loader_.createInstance(config[i]["type"]));
243  if (p.get() == NULL)
244  return false;
245  result = result && p.get()->configure(config[i]);
246  reference_pointers_.push_back(p);
247  std::string type = config[i]["type"];
248  std::string name = config[i]["name"];
249  ROS_DEBUG("%s: Configured %s:%s filter at %p\n", filter_ns.c_str(), type.c_str(),
250  name.c_str(), p.get());
251  }
252 
253  if (result == true)
254  {
255  configured_ = true;
256  }
257  return result;
258  };
259 
260 private:
261 
262  std::vector<boost::shared_ptr<filters::FilterBase<T> > > reference_pointers_;
263 
266  bool configured_;
267 
268 };
269 
273 template <typename T>
275 {
276 private:
278 public:
280  MultiChannelFilterChain(std::string data_type): loader_("filters", std::string("filters::MultiChannelFilterBase<") + data_type + std::string(">")), configured_(false)
281  {
282  std::string lib_string = "";
283  std::vector<std::string> libs = loader_.getDeclaredClasses();
284  for (unsigned int i = 0 ; i < libs.size(); i ++)
285  {
286  lib_string = lib_string + std::string(", ") + libs[i];
287  }
288  ROS_DEBUG("In MultiChannelFilterChain ClassLoader found the following libs: %s", lib_string.c_str());
289  };
290 
295  bool configure(unsigned int size, std::string param_name, ros::NodeHandle node = ros::NodeHandle())
296  {
297  XmlRpc::XmlRpcValue config;
298  if(node.getParam(param_name + "/filter_chain", config))
299  {
300  std::string resolved_name = node.resolveName(param_name).c_str();
301  ROS_WARN("Filter chains no longer check implicit nested 'filter_chain' parameter. This node is configured to look directly at '%s'. Please move your chain description from '%s/filter_chain' to '%s'", resolved_name.c_str(), resolved_name.c_str(), resolved_name.c_str());
302  }
303  else if(!node.getParam(param_name, config))
304  {
305  ROS_ERROR("Could not load the configuration for %s, are you sure it was pushed to the parameter server? Assuming that you meant to leave it blank.", param_name.c_str());
306  /********************** Do the allocation *********************/
307  buffer0_.resize(size);
308  buffer1_.resize(size);
309  configured_ = true;
310  return false;
311  }
312  return this->configure(size, config);
313  }
314 
316  bool update(const std::vector<T>& data_in, std::vector<T>& data_out)
317  {
318  unsigned int list_size = reference_pointers_.size();
319  bool result;
320  if (list_size == 0)
321  {
322  data_out = data_in;
323  result = true;
324  }
325  else if (list_size == 1)
326  result = reference_pointers_[0]->update(data_in, data_out);
327  else if (list_size == 2)
328  {
329  result = reference_pointers_[0]->update(data_in, buffer0_);
330  if (result == false) {return false; };//don't keep processing on failure
331  result = result && reference_pointers_[1]->update(buffer0_, data_out);
332  }
333  else
334  {
335  result = reference_pointers_[0]->update(data_in, buffer0_); //first copy in
336  for (unsigned int i = 1; i < reference_pointers_.size() - 1; i++) // all but first and last (never if size = 2)
337  {
338  if (i %2 == 1)
339  result = result && reference_pointers_[i]->update(buffer0_, buffer1_);
340  else
341  result = result && reference_pointers_[i]->update(buffer1_, buffer0_);
342 
343  if (result == false) {return false; }; //don't keep processing on failure
344  }
345  if (list_size % 2 == 1) // odd number last deposit was in buffer1
346  result = result && reference_pointers_.back()->update(buffer1_, data_out);
347  else
348  result = result && reference_pointers_.back()->update(buffer0_, data_out);
349  }
350  return result;
351 
352  };
353 
354 
356  {
357  clear();
358 
359  };
360 
362  bool clear()
363  {
364  configured_ = false;
365  reference_pointers_.clear();
366  buffer0_.clear();
367  buffer1_.clear();
368  return true;
369  };
370 
371 
372 
376  bool configure(unsigned int size, XmlRpc::XmlRpcValue& config)
377  {
378  /*************************** Parse the XmlRpcValue ***********************************/
379  //Verify proper naming and structure
380  if (config.getType() != XmlRpc::XmlRpcValue::TypeArray)
381  {
382  ROS_ERROR("The filter chain specification must be a list. but is of of XmlRpcType %d", config.getType());
383  ROS_ERROR("The xml passed in is formatted as follows:\n %s", config.toXml().c_str());
384 
385  return false;
386  }
387 
388  //Iterate over all filter in filters (may be just one)
389  for (int i = 0; i < config.size(); ++i)
390  {
391  if(config[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
392  {
393  ROS_ERROR("Filters must be specified as maps, but they are XmlRpcType:%d", config[i].getType());
394  return false;
395  }
396  else if (!config[i].hasMember("type"))
397  {
398  ROS_ERROR("Could not add a filter because no type was given");
399  return false;
400  }
401  else if (!config[i].hasMember("name"))
402  {
403  ROS_ERROR("Could not add a filter because no name was given");
404  return false;
405  }
406  else
407  {
408  //Check for name collisions within the list itself.
409  for (int j = i + 1; j < config.size(); ++j)
410  {
411  if(config[j].getType() != XmlRpc::XmlRpcValue::TypeStruct)
412  {
413  ROS_ERROR("Filters must be specified as maps");
414  return false;
415  }
416 
417  if(!config[j].hasMember("name")
418  ||config[i]["name"].getType() != XmlRpc::XmlRpcValue::TypeString
419  || config[j]["name"].getType() != XmlRpc::XmlRpcValue::TypeString)
420  {
421  ROS_ERROR("Filters names must be strings");
422  return false;
423  }
424 
425  std::string namei = config[i]["name"];
426  std::string namej = config[j]["name"];
427  if (namei == namej)
428  {
429  std::string name = config[i]["name"];
430  ROS_ERROR("A self_filter with the name %s already exists", name.c_str());
431  return false;
432  }
433  }
434  //CHeck for backwards compatible declarations
435  if (std::string(config[i]["type"]).find("/") == std::string::npos)
436  {
437  ROS_WARN("Deprecation Warning: No '/' detected in FilterType, Please update to 1.2 plugin syntax. ");
438  std::vector<std::string> libs = loader_.getDeclaredClasses();
439  for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
440  {
441  size_t position = it->find(std::string(config[i]["type"]));
442  if (position != std::string::npos)
443  {
444  ROS_WARN("Replaced %s with %s", std::string(config[i]["type"]).c_str(), it->c_str());
445  config[i]["type"] = *it;
446  }
447  }
448  }
449  //Make sure the filter chain has a valid type
450  std::vector<std::string> libs = loader_.getDeclaredClasses();
451  bool found = false;
452  for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
453  {
454  if (*it == std::string(config[i]["type"]))
455  {
456  found = true;
457  break;
458  }
459  }
460  if (!found)
461  {
462  ROS_ERROR("Couldn't find filter of type %s", std::string(config[i]["type"]).c_str());
463  return false;
464  }
465 
466 
467  }
468  }
469 
470  /********************** Do the allocation *********************/
471  buffer0_.resize(size);
472  buffer1_.resize(size);
473 
474  bool result = true;
475 
476 
477  for (int i = 0; i < config.size(); ++i)
478  {
479  boost::shared_ptr<filters::MultiChannelFilterBase<T> > p(loader_.createInstance(config[i]["type"]));
480  if (p.get() == NULL)
481  return false;
482  result = result && p.get()->configure(size, config[i]);
483  reference_pointers_.push_back(p);
484  std::string type = config[i]["type"];
485  std::string name = config[i]["name"];
486  ROS_DEBUG("Configured %s:%s filter at %p\n", type.c_str(),
487  name.c_str(), p.get());
488  }
489 
490  if (result == true)
491  {
492  configured_ = true;
493  }
494  return result;
495  };
496 
497 private:
498 
499  std::vector<boost::shared_ptr<filters::MultiChannelFilterBase<T> > > reference_pointers_;
500 
501  std::vector<T> buffer0_;
502  std::vector<T> buffer1_;
503  bool configured_;
504 
505 };
506 
507 };
508 
509 #endif //#ifndef FILTERS_FILTER_CHAIN_H_
T buffer0_
! A temporary intermediate buffer
Definition: filter_chain.h:264
bool clear()
Clear all filters from this chain.
Definition: filter_chain.h:362
A class which will construct and sequentially call Filters according to xml This is the primary way i...
Definition: filter_chain.h:274
bool configured_
! whether the system is configured
Definition: filter_chain.h:503
pluginlib::ClassLoader< filters::MultiChannelFilterBase< T > > loader_
Definition: filter_chain.h:277
int size() const
FilterChain(std::string data_type)
Create the filter chain object.
Definition: filter_chain.h:53
std::vector< T > buffer0_
! A temporary intermediate buffer
Definition: filter_chain.h:501
T buffer1_
! A temporary intermediate buffer
Definition: filter_chain.h:265
bool update(const std::vector< T > &data_in, std::vector< T > &data_out)
process data through each of the filters added sequentially
Definition: filter_chain.h:316
Type const & getType() const
#define ROS_WARN(...)
std::string toXml() const
std::vector< std::string > getDeclaredClasses()
MultiChannelFilterChain(std::string data_type)
Create the filter chain object.
Definition: filter_chain.h:280
A class which will construct and sequentially call Filters according to xml This is the primary way i...
Definition: filter_chain.h:47
bool clear()
Clear all filters from this chain.
Definition: filter_chain.h:130
std::vector< boost::shared_ptr< filters::FilterBase< T > > > reference_pointers_
! A vector of pointers to currently constructed filters
Definition: filter_chain.h:258
bool configure(unsigned int size, XmlRpc::XmlRpcValue &config)
Configure the filter chain This will call configure on all filters which have been added as well as a...
Definition: filter_chain.h:376
std::vector< boost::shared_ptr< filters::MultiChannelFilterBase< T > > > reference_pointers_
! A vector of pointers to currently constructed filters
Definition: filter_chain.h:495
bool update(const T &data_in, T &data_out)
process data through each of the filters added sequentially
Definition: filter_chain.h:92
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
Configure the filter chain from a configuration stored on the parameter server.
Definition: filter_chain.h:74
bool configure(XmlRpc::XmlRpcValue &config, const std::string &filter_ns)
Configure the filter chain This will call configure on all filters which have been added...
Definition: filter_chain.h:142
std::vector< T > buffer1_
! A temporary intermediate buffer
Definition: filter_chain.h:502
bool configured_
! whether the system is configured
Definition: filter_chain.h:266
bool configure(unsigned int size, std::string param_name, ros::NodeHandle node=ros::NodeHandle())
Configure the filter chain from a configuration stored on the parameter server.
Definition: filter_chain.h:295
#define ROS_ERROR(...)
pluginlib::ClassLoader< filters::FilterBase< T > > loader_
Definition: filter_chain.h:50
#define ROS_DEBUG(...)


filters
Author(s):
autogenerated on Mon Jun 10 2019 13:15:08