The DigitalFilter class is used to pass signals with a frequency lower than a certain cutoff frequency and attenuates signals with frequencies higher than the cutoff frequency.
More...
#include <digital_filter.h>
The DigitalFilter class is used to pass signals with a frequency lower than a certain cutoff frequency and attenuates signals with frequencies higher than the cutoff frequency.
◆ DigitalFilter() [1/2]
apollo::common::DigitalFilter::DigitalFilter |
( |
| ) |
|
|
default |
◆ DigitalFilter() [2/2]
apollo::common::DigitalFilter::DigitalFilter |
( |
const std::vector< double > & |
denominators, |
|
|
const std::vector< double > & |
numerators |
|
) |
| |
Initializes a DigitalFilter with given denominators and numerators.
- Parameters
-
◆ ~DigitalFilter()
apollo::common::DigitalFilter::~DigitalFilter |
( |
| ) |
|
|
default |
◆ dead_zone()
double apollo::common::DigitalFilter::dead_zone |
( |
| ) |
const |
get dead_zone
- Returns
- double The dead_zone
◆ denominators()
const std::vector<double>& apollo::common::DigitalFilter::denominators |
( |
| ) |
const |
get denominators
- Returns
- vector<double> The denominators of filter
◆ Filter()
double apollo::common::DigitalFilter::Filter |
( |
const double |
x_insert | ) |
|
Processes a new measurement with the filter.
- Parameters
-
x_insert | The new input to be processed by the filter. |
◆ inputs_queue()
const std::deque<double>& apollo::common::DigitalFilter::inputs_queue |
( |
| ) |
const |
get inputs of the filter
- Returns
- deque<double> The queue of inputs of filter
◆ numerators()
const std::vector<double>& apollo::common::DigitalFilter::numerators |
( |
| ) |
const |
get numerators
- Returns
- vector<double> The numerators of filter
◆ outputs_queue()
const std::deque<double>& apollo::common::DigitalFilter::outputs_queue |
( |
| ) |
const |
get outputs of the filter
- Returns
- deque<double> The queue of outputs of filter
◆ reset_values()
void apollo::common::DigitalFilter::reset_values |
( |
| ) |
|
re-set the x_values_ and y_values_
- Parameters
-
deadzone | The value of deadzone |
◆ set_coefficients()
void apollo::common::DigitalFilter::set_coefficients |
( |
const std::vector< double > & |
denominators, |
|
|
const std::vector< double > & |
numerators |
|
) |
| |
set denominators and numerators
- Parameters
-
denominators | The denominators of filter |
numerators | The numerators of filter |
◆ set_dead_zone()
void apollo::common::DigitalFilter::set_dead_zone |
( |
const double |
deadzone | ) |
|
set filter deadzone
- Parameters
-
deadzone | The value of deadzone |
◆ set_denominators()
void apollo::common::DigitalFilter::set_denominators |
( |
const std::vector< double > & |
denominators | ) |
|
set denominators by an input vector
: Filter by the input x_insert Input: new value of x_insert Remove x[n - 1], insert x_insert into x[0] Remove y[n - 1], Solve den[0] * y + den[1] * y[0] + ... + den[n - 1]*y[n - 2] = num[0] * x[0] + num[1] * x[1] + ... + num[n - 1] * x[n - 1] for y Insert y into y[0] Output: y[0]
- Parameters
-
denominators | The denominators of filter |
◆ set_numerators()
void apollo::common::DigitalFilter::set_numerators |
( |
const std::vector< double > & |
numerators | ) |
|
set numerators by an input vector
- Parameters
-
numerators | The numerators of filter |
The documentation for this class was generated from the following file: