utils::LowPassVelocityFilter< T > Struct Template Reference

Compute velocity by finite difference of position measurements, applying a low-pass filter to it. More...

#include <lipm_walking/utils/LowPassVelocityFilter.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW LowPassVelocityFilter (double dt)
 Constructor. More...
 
 LowPassVelocityFilter (double dt, double period)
 Constructor with cutoff period. More...
 
double cutoffPeriod () const
 Get cutoff period. More...
 
void cutoffPeriod (double period)
 Set cutoff period. More...
 
void reset (T pos)
 Reset position to an initial rest value. More...
 
void update (const T &newPos)
 Update velocity estimate from new position value. More...
 
void updatePositionOnly (const T &newPos)
 Update position only. More...
 
const T & vel ()
 Get filtered velocity. More...
 

Detailed Description

template<typename T>
struct utils::LowPassVelocityFilter< T >

Compute velocity by finite difference of position measurements, applying a low-pass filter to it.

Definition at line 40 of file LowPassVelocityFilter.h.

Constructor & Destructor Documentation

template<typename T>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW utils::LowPassVelocityFilter< T >::LowPassVelocityFilter ( double  dt)
inline

Constructor.

Parameters
dtSampling period.

Definition at line 49 of file LowPassVelocityFilter.h.

template<typename T>
utils::LowPassVelocityFilter< T >::LowPassVelocityFilter ( double  dt,
double  period 
)
inline

Constructor with cutoff period.

Parameters
dtSampling period.
periodCutoff period.

Definition at line 61 of file LowPassVelocityFilter.h.

Member Function Documentation

template<typename T>
double utils::LowPassVelocityFilter< T >::cutoffPeriod ( ) const
inline

Get cutoff period.

Definition at line 70 of file LowPassVelocityFilter.h.

template<typename T>
void utils::LowPassVelocityFilter< T >::cutoffPeriod ( double  period)
inline

Set cutoff period.

Parameters
periodNew cutoff period.

Definition at line 80 of file LowPassVelocityFilter.h.

template<typename T>
void utils::LowPassVelocityFilter< T >::reset ( pos)
inline

Reset position to an initial rest value.

Parameters
posNew position.

Definition at line 91 of file LowPassVelocityFilter.h.

template<typename T>
void utils::LowPassVelocityFilter< T >::update ( const T &  newPos)
inline

Update velocity estimate from new position value.

Parameters
newPosNew observed position.

Definition at line 102 of file LowPassVelocityFilter.h.

template<typename T>
void utils::LowPassVelocityFilter< T >::updatePositionOnly ( const T &  newPos)
inline

Update position only.

Definition at line 114 of file LowPassVelocityFilter.h.

template<typename T>
const T& utils::LowPassVelocityFilter< T >::vel ( )
inline

Get filtered velocity.

Definition at line 122 of file LowPassVelocityFilter.h.