30 #ifndef FILTERS_FILTER_BASE_H_ 31 #define FILTERS_FILTER_BASE_H_ 38 #include "boost/scoped_ptr.hpp" 39 #include <boost/algorithm/string.hpp> 68 if (!node_handle.getParam(param_name, config))
70 ROS_ERROR(
"Could not find parameter %s on the server, are you sure that it was pushed up correctly?", param_name.c_str());
100 virtual bool update(
const T& data_in, T& data_out)=0;
121 bool getParam(
const std::string& name, std::string& value)
123 string_map_t::iterator it =
params_.find(name);
134 value = std::string(it->second);
142 bool getParam(
const std::string& name,
bool& value)
144 string_map_t::iterator it =
params_.find(name);
155 value = (bool)(it->second);
163 bool getParam(
const std::string&name,
double& value)
165 string_map_t::iterator it =
params_.find(name);
186 string_map_t::iterator it =
params_.find(name);
205 bool getParam(
const std::string&name,
unsigned int& value)
210 if (signed_value < 0)
212 value = signed_value;
220 bool getParam(
const std::string&name, std::vector<double>& value)
222 string_map_t::iterator it =
params_.find(name);
237 for (
int i = 0; i < double_array.
size(); ++i){
244 value.push_back(double_value);
254 bool getParam(
const std::string&name, std::vector<std::string>& value)
256 string_map_t::iterator it =
params_.find(name);
271 for (
unsigned int i = 0; i < string_array.
size(); ++i){
277 value.push_back(string_array[i]);
289 string_map_t::iterator it =
params_.find(name);
317 ROS_ERROR(
"Filter didn't have name defined, other strings are not allowed");
321 std::string name = config[
"name"];
325 ROS_ERROR(
"Filter %s didn't have type defined, other strings are not allowed", name.c_str());
329 std::string type = config[
"type"];
333 ROS_DEBUG(
"Configuring Filter of Type: %s with name %s", type.c_str(), name.c_str());
342 ROS_ERROR(
"A filter configuration must be a map with fields name, type, and params");
366 ROS_DEBUG(
"Loading param %s\n", it->first.c_str());
367 params_[it->first] = it->second;
377 template <
typename T>
391 if (!node_handle.getParam(param_name, config))
393 ROS_ERROR(
"Could not find parameter %s on the server, are you sure that it was pushed up correctly?", param_name.c_str());
396 return configure(number_of_channels, config);
407 ROS_DEBUG(
"FilterBase being configured with XmlRpc xml: %s type: %d", config.
toXml().c_str(), config.
getType());
413 number_of_channels_ = number_of_channels;
414 ROS_DEBUG(
"MultiChannelFilterBase configured with %d channels", number_of_channels_);
427 ROS_ERROR(
"MultiChannelFilterBase configure should be called with a number of channels argument, assuming 1");
439 virtual bool update(
const std::vector<T>& data_in, std::vector<T>& data_out)=0;
441 virtual bool update(
const T& data_in, T& data_out)
443 ROS_ERROR(
"THIS IS A MULTI FILTER DON'T CALL SINGLE FORM OF UPDATE");
460 #endif //#ifndef FILTERS_FILTER_BASE_H_ bool configure(const std::string ¶m_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
ValueStruct::iterator iterator
A Base filter class to provide a standard interface for all filters.
std::string filter_name_
The name of the filter.
bool configure(unsigned int number_of_channels, const std::string ¶m_name, ros::NodeHandle node_handle=ros::NodeHandle())
Configure the filter from the parameter server.
std::map< std::string, XmlRpc::XmlRpcValue > string_map_t
FilterBase()
Default constructor used by Filter Factories.
bool configured_
Whether the filter has been configured.
const std::string & getName()
Get the name of the filter as a string.
Type const & getType() const
bool getParam(const std::string &name, bool &value)
Get a filter parameter as a boolean.
bool getParam(const std::string &name, unsigned int &value)
Get a filter parameter as an unsigned int.
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.
bool configure(XmlRpc::XmlRpcValue &config)
The public method to configure a filter from XML.
std::string toXml() const
std::string getType()
Get the type of the filter as a string.
bool configure(unsigned int number_of_channels, XmlRpc::XmlRpcValue &config)
The public method to configure a filter from XML.
bool loadConfiguration(XmlRpc::XmlRpcValue &config)
string_map_t params_
Storage of the parsed xml parameters.
unsigned int number_of_channels_
How many parallel inputs for which the filter is to be configured.
bool getParam(const std::string &name, XmlRpc::XmlRpcValue &value)
Get a filter parameter as a XmlRpcValue.
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...
bool getParam(const std::string &name, std::vector< std::string > &value)
Get a filter parameter as a std::vector<string>
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.
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>
bool getParam(const std::string &name, int &value)
Get a filter parameter as a int.
std::string filter_type_
The type of the filter (Used by FilterChain for Factory construction)
bool getParam(const std::string &name, double &value)
Get a filter parameter as a double.
bool setNameAndType(XmlRpc::XmlRpcValue &config)
Set the name and type of the filter from the parameter server.
bool configure(XmlRpc::XmlRpcValue &config)
A method to hide the base class method and warn if improperly called.