Template Class FilterBase

Inheritance Relationships

Derived Types

Class Documentation

template<typename T>
class FilterBase

A Base filter class to provide a standard interface for all filters.

Subclassed by filters::IncrementFilter< T >, filters::MeanFilter< T >, filters::MedianFilter< T >, filters::MultiChannelFilterBase< T >, filters::ParamTest< T >, filters::SingleChannelTransferFunctionFilter< T >

Public Functions

inline FilterBase()

Default constructor used by Filter Factories.

virtual ~FilterBase() = default

Virtual Destructor.

inline bool configure(const std::string &param_prefix, const std::string &filter_name, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &node_logger, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_params)

Configure the filter from the parameter server.

Parameters:
  • The – parameter from which to read the configuration

  • node_handle – The optional node handle, useful if operating in a different namespace.

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 overridden in the derived class.

Parameters:
  • data_in – A reference to the data to be input to the filter

  • data_out – A reference to the data output location

inline const std::string &getName()

Get the name of the filter as a string.

Protected Functions

virtual bool configure() = 0

Pure virtual function for the sub class to configure the filter This function must be implemented in the derived class.

inline bool getParam(const std::string &name, std::string &value)

Get a filter parameter as a string.

Parameters:
  • name – The name of the parameter

  • value – The string to set with the value

Returns:

Whether or not the parameter of name/type was set

inline bool getParam(const std::string &name, bool &value)

Get a filter parameter as a boolean.

Parameters:
  • name – The name of the parameter

  • value – The boolean to set with the value

Returns:

Whether or not the parameter of name/type was set

inline bool getParam(const std::string &name, double &value)

Get a filter parameter as a double.

Parameters:
  • name – The name of the parameter

  • value – The double to set with the value

Returns:

Whether or not the parameter of name/type was set

inline bool getParam(const std::string &name, int &value)

Get a filter parameter as a int.

Parameters:
  • name – The name of the parameter

  • value – The int to set with the value

Returns:

Whether or not the parameter of name/type was set

inline bool getParam(const std::string &name, unsigned int &value)

Get a filter parameter as an unsigned int.

Parameters:
  • name – The name of the parameter

  • value – The int to set with the value

Returns:

Whether or not the parameter of name/type was set

inline bool getParam(const std::string &name, size_t &value)

Get a filter parameter as a size_t.

Parameters:
  • name – The name of the parameter

  • value – The int to set with the value

Returns:

Whether or not the parameter of name/type was set

inline bool getParam(const std::string &name, std::vector<double> &value)

Get a filter parameter as a std::vector<double>

Parameters:
  • name – The name of the parameter

  • value – The std::vector<double> to set with the value

Returns:

Whether or not the parameter of name/type was set

inline bool getParam(const std::string &name, std::vector<std::string> &value)

Get a filter parameter as a std::vector<string>

Parameters:
  • name – The name of the parameter

  • value – The std::vector<sgring> to set with the value

Returns:

Whether or not the parameter of name/type was set

Protected Attributes

std::string filter_name_

The name of the filter.

bool configured_

Whether the filter has been configured.

std::string param_prefix_
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr params_interface_
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logging_interface_