30 #ifndef FILTERS_FILTER_CHAIN_H_ 31 #define FILTERS_FILTER_CHAIN_H_ 38 #include "boost/shared_ptr.hpp" 55 std::string lib_string =
"";
57 for (
unsigned int i = 0 ; i < libs.size(); i ++)
59 lib_string = lib_string + std::string(
", ") + libs[i];
61 ROS_DEBUG(
"In FilterChain ClassLoader found the following libs: %s", lib_string.c_str());
77 if(node.getParam(param_name +
"/filter_chain", config))
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());
82 else if(!node.getParam(param_name, config))
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());
88 return this->
configure(config, node.getNamespace());
92 bool update(
const T& data_in, T& data_out)
101 else if (list_size == 1)
103 else if (list_size == 2)
106 if (result ==
false) {
return false; };
119 if (result ==
false) {
return false; };
121 if (list_size % 2 == 1)
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());
155 for (
int i = 0; i < config.
size(); ++i)
159 ROS_ERROR(
"%s: Filters must be specified as maps, but they are XmlRpcType:%d", filter_ns.c_str(), config[i].
getType());
162 else if (!config[i].hasMember(
"type"))
164 ROS_ERROR(
"%s: Could not add a filter because no type was given", filter_ns.c_str());
167 else if (!config[i].hasMember(
"name"))
169 ROS_ERROR(
"%s: Could not add a filter because no name was given", filter_ns.c_str());
175 for (
int j = i + 1; j < config.
size(); ++j)
179 ROS_ERROR(
"%s: Filters must be specified as maps, but they are XmlRpcType:%d", filter_ns.c_str(), config[j].
getType());
183 if(!config[j].hasMember(
"name")
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());
191 std::string namei = config[i][
"name"];
192 std::string namej = config[j][
"name"];
195 ROS_ERROR(
"%s: A self_filter with the name %s already exists", filter_ns.c_str(), namei.c_str());
201 if (std::string(config[i][
"type"]).find(
"/") == std::string::npos)
203 ROS_ERROR(
"Bad filter type %s. Filter type must be of form <package_name>/<filter_name>", std::string(config[i][
"type"]).c_str());
209 for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
211 if (*it == std::string(config[i][
"type"]))
219 ROS_ERROR(
"Couldn't find filter of type %s", std::string(config[i][
"type"]).c_str());
230 for (
int i = 0; i < config.
size(); ++i)
235 result = result && p.get()->configure(config[i]);
237 std::string type = config[i][
"type"];
238 std::string name = config[i][
"name"];
239 ROS_DEBUG(
"%s: Configured %s:%s filter at %p\n", filter_ns.c_str(), type.c_str(),
240 name.c_str(), p.get());
263 template <
typename T>
272 std::string lib_string =
"";
274 for (
unsigned int i = 0 ; i < libs.size(); i ++)
276 lib_string = lib_string + std::string(
", ") + libs[i];
278 ROS_DEBUG(
"In MultiChannelFilterChain ClassLoader found the following libs: %s", lib_string.c_str());
288 if(node.getParam(param_name +
"/filter_chain", config))
290 std::string resolved_name = node.resolveName(param_name).c_str();
291 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());
293 else if(!node.getParam(param_name, config))
295 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 bool update(
const std::vector<T>& data_in, std::vector<T>& data_out)
315 else if (list_size == 1)
317 else if (list_size == 2)
320 if (result ==
false) {
return false; };
333 if (result ==
false) {
return false; };
335 if (list_size % 2 == 1)
372 ROS_ERROR(
"The filter chain specification must be a list. but is of of XmlRpcType %d", config.
getType());
373 ROS_ERROR(
"The xml passed in is formatted as follows:\n %s", config.
toXml().c_str());
379 for (
int i = 0; i < config.
size(); ++i)
383 ROS_ERROR(
"Filters must be specified as maps, but they are XmlRpcType:%d", config[i].getType());
386 else if (!config[i].hasMember(
"type"))
388 ROS_ERROR(
"Could not add a filter because no type was given");
391 else if (!config[i].hasMember(
"name"))
393 ROS_ERROR(
"Could not add a filter because no name was given");
399 for (
int j = i + 1; j < config.
size(); ++j)
403 ROS_ERROR(
"Filters must be specified as maps");
407 if(!config[j].hasMember(
"name")
411 ROS_ERROR(
"Filters names must be strings");
415 std::string namei = config[i][
"name"];
416 std::string namej = config[j][
"name"];
419 std::string name = config[i][
"name"];
420 ROS_ERROR(
"A self_filter with the name %s already exists", name.c_str());
425 if (std::string(config[i][
"type"]).find(
"/") == std::string::npos)
427 ROS_WARN(
"Deprecation Warning: No '/' detected in FilterType, Please update to 1.2 plugin syntax. ");
429 for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
431 size_t position = it->find(std::string(config[i][
"type"]));
432 if (position != std::string::npos)
434 ROS_WARN(
"Replaced %s with %s", std::string(config[i][
"type"]).c_str(), it->c_str());
435 config[i][
"type"] = *it;
442 for (std::vector<std::string>::iterator it = libs.begin(); it != libs.end(); ++it)
444 if (*it == std::string(config[i][
"type"]))
452 ROS_ERROR(
"Couldn't find filter of type %s", std::string(config[i][
"type"]).c_str());
467 for (
int i = 0; i < config.
size(); ++i)
472 result = result && p.get()->configure(size, config[i]);
474 std::string type = config[i][
"type"];
475 std::string name = config[i][
"name"];
476 ROS_DEBUG(
"Configured %s:%s filter at %p\n", type.c_str(),
477 name.c_str(), p.get());
499 #endif //#ifndef FILTERS_FILTER_CHAIN_H_ T buffer0_
! A temporary intermediate buffer
bool clear()
Clear all filters from this chain.
A class which will construct and sequentially call Filters according to xml This is the primary way i...
bool configured_
! whether the system is configured
pluginlib::ClassLoader< filters::MultiChannelFilterBase< T > > loader_
FilterChain(std::string data_type)
Create the filter chain object.
std::vector< T > buffer0_
! A temporary intermediate buffer
T buffer1_
! A temporary intermediate buffer
bool update(const std::vector< T > &data_in, std::vector< T > &data_out)
process data through each of the filters added sequentially
Type const & getType() const
std::string toXml() const
std::vector< std::string > getDeclaredClasses()
MultiChannelFilterChain(std::string data_type)
Create the filter chain object.
A class which will construct and sequentially call Filters according to xml This is the primary way i...
bool clear()
Clear all filters from this chain.
std::vector< boost::shared_ptr< filters::FilterBase< T > > > reference_pointers_
! A vector of pointers to currently constructed filters
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...
std::vector< boost::shared_ptr< filters::MultiChannelFilterBase< T > > > reference_pointers_
! A vector of pointers to currently constructed filters
bool update(const T &data_in, T &data_out)
process data through each of the filters added sequentially
bool configure(std::string param_name, ros::NodeHandle node=ros::NodeHandle())
Configure the filter chain from a configuration stored on the parameter server.
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...
std::vector< T > buffer1_
! A temporary intermediate buffer
bool configured_
! whether the system is configured
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.
~MultiChannelFilterChain()
pluginlib::ClassLoader< filters::FilterBase< T > > loader_