Template Class MultiChannelFilterBase

Inheritance Relationships

Base Type

Derived Types

Class Documentation

template<typename T>
class MultiChannelFilterBase : public filters::FilterBase<T>

Subclassed by filters::MultiChannelIncrementFilter< T >, filters::MultiChannelMeanFilter< T >, filters::MultiChannelMedianFilter< T >, filters::MultiChannelTransferFunctionFilter< T >

Public Functions

inline MultiChannelFilterBase()
virtual ~MultiChannelFilterBase() = default

Virtual Destructor.

inline virtual bool configure()

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

inline bool configure(size_t number_of_channels, 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:
  • number_of_channels – How many parallel channels the filter will process

  • 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 std::vector<T> &data_in, std::vector<T> &data_out) = 0

Update the filter and return the data seperately.

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

  • data_out – A reference to the data output location This funciton must be implemented in the derived class.

inline virtual bool update(const T&, T&)

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

Protected Attributes

size_t number_of_channels_

How many parallel inputs for which the filter is to be configured.