#include <mc_filter/LowPassFiniteDifferences.h>
Public Types | |
using | LowPassT = LowPass< T > |
Public Member Functions | |
LowPassFiniteDifferences (double dt, double period) | |
void | reset (const T &pos, const T &vel) |
void | update (const T &newPos) |
const T & | prevValue () const |
Public Member Functions inherited from mc_filter::LowPass< T > | |
LowPass (double dt, double period=0) | |
double | cutoffPeriod () const |
void | cutoffPeriod (double period) |
void | reset (const T &value) |
void | update (const T &newValue) |
const T & | eval () const |
double | dt () const |
void | dt (double dt) |
Protected Attributes | |
T | prevValue_ |
Protected Attributes inherited from mc_filter::LowPass< T > | |
double | dt_ = 0.005 |
Low-pass velocity filter from series of position measurements.
Expects T to have:
using mc_filter::LowPassFiniteDifferences< T >::LowPassT = LowPass<T> |
|
inline |
Constructor with cutoff period.
dt | Sampling period. |
period | Cutoff period. |
|
inline |
|
inline |
Reset filter to initial rest value.
pos | Initial position. |
vel | Initial velocity. |
|
inline |
Update velocity estimate from new position value.
newPos | New observed position. |
|
protected |