Apollo  6.0
Open source self driving car software
digital_filter.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2017 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 
22 #pragma once
23 
24 #include <deque>
25 #include <vector>
26 
31 namespace apollo {
32 namespace common {
33 
41  public:
42  DigitalFilter() = default;
43 
49  DigitalFilter(const std::vector<double> &denominators,
50  const std::vector<double> &numerators);
51 
55  ~DigitalFilter() = default;
56 
61  double Filter(const double x_insert);
77  void set_denominators(const std::vector<double> &denominators);
78 
83  void set_numerators(const std::vector<double> &numerators);
84 
90  void set_coefficients(const std::vector<double> &denominators,
91  const std::vector<double> &numerators);
92 
97  void set_dead_zone(const double deadzone);
98 
103  void reset_values();
104 
109  const std::vector<double> &denominators() const;
110 
115  const std::vector<double> &numerators() const;
116 
121  double dead_zone() const;
122 
127  const std::deque<double> &inputs_queue() const;
128 
133  const std::deque<double> &outputs_queue() const;
134 
135  private:
140  double UpdateLast(const double input);
141 
146  double Compute(const std::deque<double> &values,
147  const std::vector<double> &coefficients,
148  const std::size_t coeff_start, const std::size_t coeff_end);
149 
150  // Front is latest, back is oldest.
151  std::deque<double> x_values_;
152 
153  // Front is latest, back is oldest.
154  std::deque<double> y_values_;
155 
156  // Coefficients with y values
157  std::vector<double> denominators_;
158 
159  // Coefficients with x values
160  std::vector<double> numerators_;
161 
162  // threshold of updating last-filtered value
163  double dead_zone_ = 0.0;
164 
165  // last-filtered value
166  double last_ = 0.0;
167 };
168 
169 } // namespace common
170 } // namespace apollo
const std::vector< double > & numerators() const
get numerators
double Filter(const double x_insert)
Processes a new measurement with the filter.
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
double dead_zone() const
get dead_zone
void reset_values()
re-set the x_values_ and y_values_
void set_numerators(const std::vector< double > &numerators)
set numerators by an input vector
void set_coefficients(const std::vector< double > &denominators, const std::vector< double > &numerators)
set denominators and numerators
const std::vector< double > & denominators() const
get denominators
The DigitalFilter class is used to pass signals with a frequency lower than a certain cutoff frequenc...
Definition: digital_filter.h:40
~DigitalFilter()=default
Default destructor.
const std::deque< double > & outputs_queue() const
get outputs of the filter
void set_dead_zone(const double deadzone)
set filter deadzone
const std::deque< double > & inputs_queue() const
get inputs of the filter
void set_denominators(const std::vector< double > &denominators)
set denominators by an input vector