Template Class LowPassFilter

Inheritance Relationships

Base Type

  • public filters::FilterBase< T >

Class Documentation

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

A Low-pass filter class.

This class implements a low-pass filter for various data types based on an Infinite Impulse Response Filter. For vector elements, the filtering is applied separately on each element of the vector.

In particular, this class implements a simplified version of an IIR filter equation :

\(y(n) = b x(n-1) + a y(n-1)\)

where:

  • \( x(n)\) is the input signal

  • \( y(n)\) is the output signal (filtered)

  • \( b \) is the feedforward filter coefficient

  • \( a \) is the feedback filter coefficient

and the Low-Pass coefficient equation:

  • \( a = e^{\frac{-1}{sf} \frac{2\pi df}{10^{\frac{di}{-10}}}} \)

  • \( b = 1 - a \)

where:

  • \( sf \) is the sampling frequency

  • \( df \) is the damping frequency

  • \( di \) is the damping intensity (amplitude)

Usage

The LowPassFilter class is meant to be instantiated as a filter in a controller but can also be used elsewhere. For manual instantiation, you should first call configure() (in non-realtime) and then call update() at every update step.

Public Functions

LowPassFilter()
~LowPassFilter() override

Destructor of LowPassFilter class.

bool configure() override

Configure the LowPassFilter (access and process params).

bool update(const T &data_in, T &data_out) override

Applies one iteration of the IIR filter.

Parameters:
  • data_in – input to the filter

  • data_out – filtered output

Returns:

false if filter is not configured, true otherwise

inline bool update(const geometry_msgs::msg::WrenchStamped &data_in, geometry_msgs::msg::WrenchStamped &data_out)

Protected Functions

inline void compute_internal_params()

Internal computation of the feedforward and feedbackward coefficients according to the LowPassFilter parameters.