-
Notifications
You must be signed in to change notification settings - Fork 49
/
filter_chain.h
521 lines (460 loc) · 18.4 KB
/
filter_chain.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
/*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef FILTERS_FILTER_CHAIN_H_
#define FILTERS_FILTER_CHAIN_H_
#include "ros/ros.h"
#include "filters/filter_base.h"
#include <pluginlib/class_loader.h>
#include <memory>
#include <sstream>
#include <vector>
namespace filters
{
/** \brief A class which will construct and sequentially call Filters according to xml
* This is the primary way in which users are expected to interact with Filters
*/
template <typename T>
class FilterChain
{
private:
pluginlib::ClassLoader<filters::FilterBase<T> > loader_;
public:
/** \brief Create the filter chain object */
FilterChain(std::string data_type): loader_("filters", std::string("filters::FilterBase<") + data_type + std::string(">")), configured_(false)
{
std::string lib_string = "";
std::vector<std::string> libs = loader_.getDeclaredClasses();
for (unsigned int i = 0 ; i < libs.size(); i ++)
{
lib_string = lib_string + std::string(", ") + libs[i];
}
ROS_DEBUG("In FilterChain ClassLoader found the following libs: %s", lib_string.c_str());
};
~FilterChain()
{
clear();
};
/**@brief Configure the filter chain from a configuration stored on the parameter server
* @param param_name The name of the filter chain to load
* @param node The node handle to use if a different namespace is required
*/
bool configure(std::string param_name, ros::NodeHandle node = ros::NodeHandle())
{
XmlRpc::XmlRpcValue config;
if(node.getParam(param_name + "/filter_chain", config))
{
std::string resolved_name = node.resolveName(param_name).c_str();
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());
}
else if(!node.getParam(param_name, config))
{
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());
configured_ = true;
return true;
}
return this->configure(config, node.getNamespace());
}
/** \brief process data through each of the filters added sequentially */
bool update(const T& data_in, T& data_out)
{
unsigned int list_size = reference_pointers_.size();
bool result;
if (list_size == 0)
{
data_out = data_in;
result = true;
}
else if (list_size == 1)
result = reference_pointers_[0]->update(data_in, data_out);
else if (list_size == 2)
{
result = reference_pointers_[0]->update(data_in, buffer0_);
if (result == false) {return false; };//don't keep processing on failure
result = result && reference_pointers_[1]->update(buffer0_, data_out);
}
else
{
result = reference_pointers_[0]->update(data_in, buffer0_); //first copy in
for (unsigned int i = 1; i < reference_pointers_.size() - 1; i++) // all but first and last (never called if size=2)
{
if (i %2 == 1)
result = result && reference_pointers_[i]->update(buffer0_, buffer1_);
else
result = result && reference_pointers_[i]->update(buffer1_, buffer0_);
if (result == false) {return false; }; //don't keep processing on failure
}
if (list_size % 2 == 1) // odd number last deposit was in buffer1
result = result && reference_pointers_.back()->update(buffer1_, data_out);
else
result = result && reference_pointers_.back()->update(buffer0_, data_out);
}
return result;
};
/** \brief Clear all filters from this chain */
bool clear()
{
configured_ = false;
reference_pointers_.clear();
return true;
};
/** \brief Configure the filter chain
* This will call configure on all filters which have been added */
bool configure(XmlRpc::XmlRpcValue& config, const std::string& filter_ns)
{
/*************************** Parse the XmlRpcValue ***********************************/
//Verify proper naming and structure
if (config.getType() != XmlRpc::XmlRpcValue::TypeArray)
{
ROS_ERROR("%s: The filter chain specification must be a list. but is of of XmlRpcType %d", filter_ns.c_str(), config.getType());
ROS_ERROR("The xml passed in is formatted as follows:\n %s", config.toXml().c_str());
return false;
}
//Iterate over all filter in filters (may be just one)
for (int i = 0; i < config.size(); ++i)
{
if(config[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("%s: Filters must be specified as maps, but they are XmlRpcType:%d", filter_ns.c_str(), config[i].getType());
return false;
}
else if (!config[i].hasMember("type"))
{
ROS_ERROR("%s: Could not add a filter because no type was given", filter_ns.c_str());
return false;
}
else if (!config[i].hasMember("name"))
{
ROS_ERROR("%s: Could not add a filter because no name was given", filter_ns.c_str());
return false;
}
else
{
//Check for name collisions within the list itself.
for (int j = i + 1; j < config.size(); ++j)
{
if(config[j].getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("%s: Filters must be specified as maps, but they are XmlRpcType:%d", filter_ns.c_str(), config[j].getType());
return false;
}
if(!config[j].hasMember("name")
||config[i]["name"].getType() != XmlRpc::XmlRpcValue::TypeString
|| config[j]["name"].getType() != XmlRpc::XmlRpcValue::TypeString)
{
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());
return false;
}
std::string namei = config[i]["name"];
std::string namej = config[j]["name"];
if (namei == namej)
{
ROS_ERROR("%s: A self_filter with the name %s already exists", filter_ns.c_str(), namei.c_str());
return false;
}
}
if (std::string(config[i]["type"]).find("/") == std::string::npos)
{
ROS_ERROR("Bad filter type %s. Filter type must be of form <package_name>/<filter_name>", std::string(config[i]["type"]).c_str());
return false;
}
//Make sure the filter chain has a valid type
std::vector<std::string> libs = loader_.getDeclaredClasses();
bool found = false;
for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
{
if (*it == std::string(config[i]["type"]))
{
found = true;
break;
}
}
if (!found)
{
ROS_ERROR("Couldn't find filter of type %s", std::string(config[i]["type"]).c_str());
return false;
}
}
}
bool result = true;
for (int i = 0; i < config.size(); ++i)
{
// The unmanaged instance created here is later passed to std::shared_ptr
// to handle its lifetime (this is done because pluginlib does not support
// creating std::shared_ptr pointers).
auto p(loader_.createUnmanagedInstance(config[i]["type"]));
if (p == nullptr)
return false;
std::shared_ptr<filters::FilterBase<T>> ptr(p);
result = result && ptr->configure(config[i]);
reference_pointers_.push_back(ptr);
std::string type = config[i]["type"];
std::string name = config[i]["name"];
ROS_DEBUG("%s: Configured %s:%s filter at %p\n", filter_ns.c_str(), type.c_str(),
name.c_str(), p);
}
if (result == true)
{
configured_ = true;
}
return result;
};
/** \brief Return a copy of the vector of loaded filters (the pointers point
* to the actual filters used by the chain). */
std::vector<std::shared_ptr<filters::FilterBase<T>>> getFilters() const
{
return reference_pointers_;
}
private:
std::vector<std::shared_ptr<filters::FilterBase<T>>> reference_pointers_; ///<! A vector of pointers to currently constructed filters
T buffer0_; ///<! A temporary intermediate buffer
T buffer1_; ///<! A temporary intermediate buffer
bool configured_; ///<! whether the system is configured
};
/** \brief A class which will construct and sequentially call Filters according to xml
* This is the primary way in which users are expected to interact with Filters
*/
template <typename T>
class MultiChannelFilterChain
{
private:
pluginlib::ClassLoader<filters::MultiChannelFilterBase<T> > loader_;
public:
/** \brief Create the filter chain object */
MultiChannelFilterChain(std::string data_type): loader_("filters", std::string("filters::MultiChannelFilterBase<") + data_type + std::string(">")), configured_(false)
{
std::string lib_string = "";
std::vector<std::string> libs = loader_.getDeclaredClasses();
for (unsigned int i = 0 ; i < libs.size(); i ++)
{
lib_string = lib_string + std::string(", ") + libs[i];
}
ROS_DEBUG("In MultiChannelFilterChain ClassLoader found the following libs: %s", lib_string.c_str());
};
/**@brief Configure the filter chain from a configuration stored on the parameter server
* @param param_name The name of the filter chain to load
* @param node The node handle to use if a different namespace is required
*/
bool configure(unsigned int size, std::string param_name, ros::NodeHandle node = ros::NodeHandle())
{
XmlRpc::XmlRpcValue config;
if(node.getParam(param_name + "/filter_chain", config))
{
std::string resolved_name = node.resolveName(param_name).c_str();
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());
}
else if(!node.getParam(param_name, config))
{
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());
/********************** Do the allocation *********************/
buffer0_.resize(size);
buffer1_.resize(size);
configured_ = true;
return false;
}
return this->configure(size, config);
}
/** \brief process data through each of the filters added sequentially */
bool update(const std::vector<T>& data_in, std::vector<T>& data_out)
{
unsigned int list_size = reference_pointers_.size();
bool result;
if (list_size == 0)
{
data_out = data_in;
result = true;
}
else if (list_size == 1)
result = reference_pointers_[0]->update(data_in, data_out);
else if (list_size == 2)
{
result = reference_pointers_[0]->update(data_in, buffer0_);
if (result == false) {return false; };//don't keep processing on failure
result = result && reference_pointers_[1]->update(buffer0_, data_out);
}
else
{
result = reference_pointers_[0]->update(data_in, buffer0_); //first copy in
for (unsigned int i = 1; i < reference_pointers_.size() - 1; i++) // all but first and last (never if size = 2)
{
if (i %2 == 1)
result = result && reference_pointers_[i]->update(buffer0_, buffer1_);
else
result = result && reference_pointers_[i]->update(buffer1_, buffer0_);
if (result == false) {return false; }; //don't keep processing on failure
}
if (list_size % 2 == 1) // odd number last deposit was in buffer1
result = result && reference_pointers_.back()->update(buffer1_, data_out);
else
result = result && reference_pointers_.back()->update(buffer0_, data_out);
}
return result;
};
~MultiChannelFilterChain()
{
clear();
};
/** \brief Clear all filters from this chain */
bool clear()
{
configured_ = false;
reference_pointers_.clear();
buffer0_.clear();
buffer1_.clear();
return true;
};
/** \brief Configure the filter chain
* This will call configure on all filters which have been added
* as well as allocate the buffers*/
bool configure(unsigned int size, XmlRpc::XmlRpcValue& config)
{
/*************************** Parse the XmlRpcValue ***********************************/
//Verify proper naming and structure
if (config.getType() != XmlRpc::XmlRpcValue::TypeArray)
{
ROS_ERROR("The filter chain specification must be a list. but is of of XmlRpcType %d", config.getType());
ROS_ERROR("The xml passed in is formatted as follows:\n %s", config.toXml().c_str());
return false;
}
//Iterate over all filter in filters (may be just one)
for (int i = 0; i < config.size(); ++i)
{
if(config[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("Filters must be specified as maps, but they are XmlRpcType:%d", config[i].getType());
return false;
}
else if (!config[i].hasMember("type"))
{
ROS_ERROR("Could not add a filter because no type was given");
return false;
}
else if (!config[i].hasMember("name"))
{
ROS_ERROR("Could not add a filter because no name was given");
return false;
}
else
{
//Check for name collisions within the list itself.
for (int j = i + 1; j < config.size(); ++j)
{
if(config[j].getType() != XmlRpc::XmlRpcValue::TypeStruct)
{
ROS_ERROR("Filters must be specified as maps");
return false;
}
if(!config[j].hasMember("name")
||config[i]["name"].getType() != XmlRpc::XmlRpcValue::TypeString
|| config[j]["name"].getType() != XmlRpc::XmlRpcValue::TypeString)
{
ROS_ERROR("Filters names must be strings");
return false;
}
std::string namei = config[i]["name"];
std::string namej = config[j]["name"];
if (namei == namej)
{
std::string name = config[i]["name"];
ROS_ERROR("A self_filter with the name %s already exists", name.c_str());
return false;
}
}
//CHeck for backwards compatible declarations
if (std::string(config[i]["type"]).find("/") == std::string::npos)
{
ROS_WARN("Deprecation Warning: No '/' detected in FilterType, Please update to 1.2 plugin syntax. ");
std::vector<std::string> libs = loader_.getDeclaredClasses();
for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
{
size_t position = it->find(std::string(config[i]["type"]));
if (position != std::string::npos)
{
ROS_WARN("Replaced %s with %s", std::string(config[i]["type"]).c_str(), it->c_str());
config[i]["type"] = *it;
}
}
}
//Make sure the filter chain has a valid type
std::vector<std::string> libs = loader_.getDeclaredClasses();
bool found = false;
for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
{
if (*it == std::string(config[i]["type"]))
{
found = true;
break;
}
}
if (!found)
{
ROS_ERROR("Couldn't find filter of type %s", std::string(config[i]["type"]).c_str());
return false;
}
}
}
/********************** Do the allocation *********************/
buffer0_.resize(size);
buffer1_.resize(size);
bool result = true;
for (int i = 0; i < config.size(); ++i)
{
// The unmanaged instance created here is later passed to std::shared_ptr
// to handle its lifetime (this is done because pluginlib does not support
// creating std::shared_ptr pointers).
auto p(loader_.createUnmanagedInstance(config[i]["type"]));
if (p == nullptr)
return false;
std::shared_ptr<filters::MultiChannelFilterBase<T>> ptr(p);
result = result && ptr->configure(size, config[i]);
reference_pointers_.push_back(ptr);
std::string type = config[i]["type"];
std::string name = config[i]["name"];
ROS_DEBUG("Configured %s:%s filter at %p\n", type.c_str(),
name.c_str(), p);
}
if (result == true)
{
configured_ = true;
}
return result;
};
/** \brief Return a copy of the vector of loaded filters (the pointers point
* to the actual filters used by the chain). */
std::vector<std::shared_ptr<filters::MultiChannelFilterBase<T>>> getFilters() const
{
return reference_pointers_;
}
private:
std::vector<std::shared_ptr<filters::MultiChannelFilterBase<T>>> reference_pointers_; ///<! A vector of pointers to currently constructed filters
std::vector<T> buffer0_; ///<! A temporary intermediate buffer
std::vector<T> buffer1_; ///<! A temporary intermediate buffer
bool configured_; ///<! whether the system is configured
};
};
#endif //#ifndef FILTERS_FILTER_CHAIN_H_