Drake
Drake C++ Documentation
MovingAverageFilter< T > Class Template Reference

Detailed Description

template<typename T>
class drake::manipulation::util::MovingAverageFilter< T >

The implementation of a Moving Average Filter.

This discrete time filter outputs the average of the last n samples i.e. y[k] = 1/n ∑ⱼ x[k-j] ∀ j = 0..n-1, when n<k and, = 1/k ∑ⱼ x[j] ∀ j = 0..k otherwise; where n is the window size and x being the discrete-time signal that is to be filtered, y is the filtered signal and k is the index of latest element in the signal time-series.

Note that this class is meant to serve as a standalone simple utility and a filter of this form in a more `drake::systems` flavour can be generated from a `systems::AffineSystem` since this is a LTI filter.

Template Parameters
TThe element type. Instantiated templates for the following kinds of T's are provided:
  • double
  • VectorX<double>

#include <drake/manipulation/util/moving_average_filter.h>

Public Member Functions

 MovingAverageFilter (int window_size)
 Constructs the filter with the specified window_size. More...
 
Update (const T &new_data)
 Updates the average filter result. More...
 
const std::queue< T > & window () const
 
const T moving_average () const
 Returns the most recent result of the averaging filter. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 MovingAverageFilter (const MovingAverageFilter &)=default
 
MovingAverageFilteroperator= (const MovingAverageFilter &)=default
 
 MovingAverageFilter (MovingAverageFilter &&)=default
 
MovingAverageFilteroperator= (MovingAverageFilter &&)=default
 

Constructor & Destructor Documentation

◆ MovingAverageFilter() [1/3]

MovingAverageFilter ( const MovingAverageFilter< T > &  )
default

◆ MovingAverageFilter() [2/3]

◆ MovingAverageFilter() [3/3]

MovingAverageFilter ( int  window_size)
explicit

Constructs the filter with the specified window_size.

Parameters
window_sizeThe size of the window.
Exceptions
std::exceptionwhen window_size <= 0.

Member Function Documentation

◆ moving_average()

const T moving_average ( ) const

Returns the most recent result of the averaging filter.

◆ operator=() [1/2]

MovingAverageFilter& operator= ( MovingAverageFilter< T > &&  )
default

◆ operator=() [2/2]

MovingAverageFilter& operator= ( const MovingAverageFilter< T > &  )
default

◆ Update()

T Update ( const T &  new_data)

Updates the average filter result.

Every call to this method modifies the internal state of this filter thus resulting in a computation of the moving average of the data present within the filter window.

Parameters
new_data
Returns

◆ window()

const std::queue<T>& window ( ) const

The documentation for this class was generated from the following file: