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 <memory>
37 #include <sstream>
38 #include <vector>
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  if (std::string(config[i]["type"]).find("/") == std::string::npos)
202  {
203  ROS_ERROR("Bad filter type %s. Filter type must be of form <package_name>/<filter_name>", std::string(config[i]["type"]).c_str());
204  return false;
205  }
206  //Make sure the filter chain has a valid type
207  std::vector<std::string> libs = loader_.getDeclaredClasses();
208  bool found = false;
209  for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
210  {
211  if (*it == std::string(config[i]["type"]))
212  {
213  found = true;
214  break;
215  }
216  }
217  if (!found)
218  {
219  ROS_ERROR("Couldn't find filter of type %s", std::string(config[i]["type"]).c_str());
220  return false;
221  }
222 
223  }
224  }
225 
226 
227  bool result = true;
228 
229 
230  for (int i = 0; i < config.size(); ++i)
231  {
232  // The unmanaged instance created here is later passed to std::shared_ptr
233  // to handle its lifetime (this is done because pluginlib does not support
234  // creating std::shared_ptr pointers).
235  auto p(loader_.createUnmanagedInstance(config[i]["type"]));
236  if (p == nullptr)
237  return false;
238  std::shared_ptr<filters::FilterBase<T>> ptr(p);
239  result = result && ptr->configure(config[i]);
240  reference_pointers_.push_back(ptr);
241  std::string type = config[i]["type"];
242  std::string name = config[i]["name"];
243  ROS_DEBUG("%s: Configured %s:%s filter at %p\n", filter_ns.c_str(), type.c_str(),
244  name.c_str(), p);
245  }
246 
247  if (result == true)
248  {
249  configured_ = true;
250  }
251  return result;
252  };
253 
256  std::vector<std::shared_ptr<filters::FilterBase<T>>> getFilters() const
257  {
258  return reference_pointers_;
259  }
260 
261 private:
262 
263  std::vector<std::shared_ptr<filters::FilterBase<T>>> reference_pointers_;
264 
267  bool configured_;
268 
269 };
270 
274 template <typename T>
276 {
277 private:
279 public:
281  MultiChannelFilterChain(std::string data_type): loader_("filters", std::string("filters::MultiChannelFilterBase<") + data_type + std::string(">")), configured_(false)
282  {
283  std::string lib_string = "";
284  std::vector<std::string> libs = loader_.getDeclaredClasses();
285  for (unsigned int i = 0 ; i < libs.size(); i ++)
286  {
287  lib_string = lib_string + std::string(", ") + libs[i];
288  }
289  ROS_DEBUG("In MultiChannelFilterChain ClassLoader found the following libs: %s", lib_string.c_str());
290  };
291 
296  bool configure(unsigned int size, std::string param_name, ros::NodeHandle node = ros::NodeHandle())
297  {
298  XmlRpc::XmlRpcValue config;
299  if(node.getParam(param_name + "/filter_chain", config))
300  {
301  std::string resolved_name = node.resolveName(param_name).c_str();
302  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());
303  }
304  else if(!node.getParam(param_name, config))
305  {
306  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());
307  /********************** Do the allocation *********************/
308  buffer0_.resize(size);
309  buffer1_.resize(size);
310  configured_ = true;
311  return false;
312  }
313  return this->configure(size, config);
314  }
315 
317  bool update(const std::vector<T>& data_in, std::vector<T>& data_out)
318  {
319  unsigned int list_size = reference_pointers_.size();
320  bool result;
321  if (list_size == 0)
322  {
323  data_out = data_in;
324  result = true;
325  }
326  else if (list_size == 1)
327  result = reference_pointers_[0]->update(data_in, data_out);
328  else if (list_size == 2)
329  {
330  result = reference_pointers_[0]->update(data_in, buffer0_);
331  if (result == false) {return false; };//don't keep processing on failure
332  result = result && reference_pointers_[1]->update(buffer0_, data_out);
333  }
334  else
335  {
336  result = reference_pointers_[0]->update(data_in, buffer0_); //first copy in
337  for (unsigned int i = 1; i < reference_pointers_.size() - 1; i++) // all but first and last (never if size = 2)
338  {
339  if (i %2 == 1)
340  result = result && reference_pointers_[i]->update(buffer0_, buffer1_);
341  else
342  result = result && reference_pointers_[i]->update(buffer1_, buffer0_);
343 
344  if (result == false) {return false; }; //don't keep processing on failure
345  }
346  if (list_size % 2 == 1) // odd number last deposit was in buffer1
347  result = result && reference_pointers_.back()->update(buffer1_, data_out);
348  else
349  result = result && reference_pointers_.back()->update(buffer0_, data_out);
350  }
351  return result;
352 
353  };
354 
355 
357  {
358  clear();
359 
360  };
361 
363  bool clear()
364  {
365  configured_ = false;
366  reference_pointers_.clear();
367  buffer0_.clear();
368  buffer1_.clear();
369  return true;
370  };
371 
372 
373 
377  bool configure(unsigned int size, XmlRpc::XmlRpcValue& config)
378  {
379  /*************************** Parse the XmlRpcValue ***********************************/
380  //Verify proper naming and structure
381  if (config.getType() != XmlRpc::XmlRpcValue::TypeArray)
382  {
383  ROS_ERROR("The filter chain specification must be a list. but is of of XmlRpcType %d", config.getType());
384  ROS_ERROR("The xml passed in is formatted as follows:\n %s", config.toXml().c_str());
385 
386  return false;
387  }
388 
389  //Iterate over all filter in filters (may be just one)
390  for (int i = 0; i < config.size(); ++i)
391  {
392  if(config[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
393  {
394  ROS_ERROR("Filters must be specified as maps, but they are XmlRpcType:%d", config[i].getType());
395  return false;
396  }
397  else if (!config[i].hasMember("type"))
398  {
399  ROS_ERROR("Could not add a filter because no type was given");
400  return false;
401  }
402  else if (!config[i].hasMember("name"))
403  {
404  ROS_ERROR("Could not add a filter because no name was given");
405  return false;
406  }
407  else
408  {
409  //Check for name collisions within the list itself.
410  for (int j = i + 1; j < config.size(); ++j)
411  {
412  if(config[j].getType() != XmlRpc::XmlRpcValue::TypeStruct)
413  {
414  ROS_ERROR("Filters must be specified as maps");
415  return false;
416  }
417 
418  if(!config[j].hasMember("name")
419  ||config[i]["name"].getType() != XmlRpc::XmlRpcValue::TypeString
420  || config[j]["name"].getType() != XmlRpc::XmlRpcValue::TypeString)
421  {
422  ROS_ERROR("Filters names must be strings");
423  return false;
424  }
425 
426  std::string namei = config[i]["name"];
427  std::string namej = config[j]["name"];
428  if (namei == namej)
429  {
430  std::string name = config[i]["name"];
431  ROS_ERROR("A self_filter with the name %s already exists", name.c_str());
432  return false;
433  }
434  }
435  //CHeck for backwards compatible declarations
436  if (std::string(config[i]["type"]).find("/") == std::string::npos)
437  {
438  ROS_WARN("Deprecation Warning: No '/' detected in FilterType, Please update to 1.2 plugin syntax. ");
439  std::vector<std::string> libs = loader_.getDeclaredClasses();
440  for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
441  {
442  size_t position = it->find(std::string(config[i]["type"]));
443  if (position != std::string::npos)
444  {
445  ROS_WARN("Replaced %s with %s", std::string(config[i]["type"]).c_str(), it->c_str());
446  config[i]["type"] = *it;
447  }
448  }
449  }
450  //Make sure the filter chain has a valid type
451  std::vector<std::string> libs = loader_.getDeclaredClasses();
452  bool found = false;
453  for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
454  {
455  if (*it == std::string(config[i]["type"]))
456  {
457  found = true;
458  break;
459  }
460  }
461  if (!found)
462  {
463  ROS_ERROR("Couldn't find filter of type %s", std::string(config[i]["type"]).c_str());
464  return false;
465  }
466 
467 
468  }
469  }
470 
471  /********************** Do the allocation *********************/
472  buffer0_.resize(size);
473  buffer1_.resize(size);
474 
475  bool result = true;
476 
477 
478  for (int i = 0; i < config.size(); ++i)
479  {
480  // The unmanaged instance created here is later passed to std::shared_ptr
481  // to handle its lifetime (this is done because pluginlib does not support
482  // creating std::shared_ptr pointers).
483  auto p(loader_.createUnmanagedInstance(config[i]["type"]));
484  if (p == nullptr)
485  return false;
486  std::shared_ptr<filters::MultiChannelFilterBase<T>> ptr(p);
487  result = result && ptr->configure(size, config[i]);
488  reference_pointers_.push_back(ptr);
489  std::string type = config[i]["type"];
490  std::string name = config[i]["name"];
491  ROS_DEBUG("Configured %s:%s filter at %p\n", type.c_str(),
492  name.c_str(), p);
493  }
494 
495  if (result == true)
496  {
497  configured_ = true;
498  }
499  return result;
500  };
501 
504  std::vector<std::shared_ptr<filters::MultiChannelFilterBase<T>>> getFilters() const
505  {
506  return reference_pointers_;
507  }
508 
509 private:
510 
511  std::vector<std::shared_ptr<filters::MultiChannelFilterBase<T>>> reference_pointers_;
512 
513  std::vector<T> buffer0_;
514  std::vector<T> buffer1_;
515  bool configured_;
516 
517 };
518 
519 };
520 
521 #endif //#ifndef FILTERS_FILTER_CHAIN_H_
T buffer0_
! A temporary intermediate buffer
Definition: filter_chain.h:265
bool clear()
Clear all filters from this chain.
Definition: filter_chain.h:363
A class which will construct and sequentially call Filters according to xml This is the primary way i...
Definition: filter_chain.h:275
bool configured_
! whether the system is configured
Definition: filter_chain.h:515
pluginlib::ClassLoader< filters::MultiChannelFilterBase< T > > loader_
Definition: filter_chain.h:278
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:513
T * createUnmanagedInstance(const std::string &lookup_name)
std::vector< std::shared_ptr< filters::MultiChannelFilterBase< T > > > getFilters() const
Return a copy of the vector of loaded filters (the pointers point to the actual filters used by the c...
Definition: filter_chain.h:504
T buffer1_
! A temporary intermediate buffer
Definition: filter_chain.h:266
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:317
#define ROS_WARN(...)
Type const & getType() const
std::vector< std::string > getDeclaredClasses()
MultiChannelFilterChain(std::string data_type)
Create the filter chain object.
Definition: filter_chain.h:281
std::vector< std::shared_ptr< filters::FilterBase< T > > > getFilters() const
Return a copy of the vector of loaded filters (the pointers point to the actual filters used by the c...
Definition: filter_chain.h:256
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
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:377
std::string toXml() const
std::vector< std::shared_ptr< filters::FilterBase< T > > > reference_pointers_
! A vector of pointers to currently constructed filters
Definition: filter_chain.h:263
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:514
bool configured_
! whether the system is configured
Definition: filter_chain.h:267
std::vector< std::shared_ptr< filters::MultiChannelFilterBase< T > > > reference_pointers_
! A vector of pointers to currently constructed filters
Definition: filter_chain.h:511
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:296
#define ROS_ERROR(...)
pluginlib::ClassLoader< filters::FilterBase< T > > loader_
Definition: filter_chain.h:50
#define ROS_DEBUG(...)


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