Autoware.Auto
autoware::motion::control::trajectory_follower::LowpassFilter1d Class Reference

Simple filter with gain on the first derivative of the value. More...

#include <lowpass_filter.hpp>

Public Member Functions

 LowpassFilter1d (const float64_t x, const float64_t gain)
 constructor with initial value and first-order gain More...
 
void reset (const float64_t x)
 set the current value of the filter More...
 
float64_t getValue () const
 get the current value of the filter More...
 
float64_t filter (const float64_t u)
 filter a new value More...
 

Detailed Description

Simple filter with gain on the first derivative of the value.

Constructor & Destructor Documentation

◆ LowpassFilter1d()

autoware::motion::control::trajectory_follower::LowpassFilter1d::LowpassFilter1d ( const float64_t  x,
const float64_t  gain 
)
inline

constructor with initial value and first-order gain

Parameters
[in]xinitial value
[in]gainfirst-order gain

Member Function Documentation

◆ filter()

float64_t autoware::motion::control::trajectory_follower::LowpassFilter1d::filter ( const float64_t  u)
inline

filter a new value

Parameters
[in]unew value

◆ getValue()

float64_t autoware::motion::control::trajectory_follower::LowpassFilter1d::getValue ( ) const
inline

get the current value of the filter

◆ reset()

void autoware::motion::control::trajectory_follower::LowpassFilter1d::reset ( const float64_t  x)
inline

set the current value of the filter

Parameters
[in]xnew value

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