Apollo  6.0
Open source self driving car software
digital_filter_coefficients.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 <vector>
25 
26 #include "cyber/common/log.h"
27 
32 namespace apollo {
33 namespace common {
34 
42 void LpfCoefficients(const double ts, const double cutoff_freq,
43  std::vector<double> *denominators,
44  std::vector<double> *numerators);
45 
55 void LpFirstOrderCoefficients(const double ts, const double settling_time,
56  const double dead_time,
57  std::vector<double> *denominators,
58  std::vector<double> *numerators);
59 
60 } // namespace common
61 } // namespace apollo
void LpFirstOrderCoefficients(const double ts, const double settling_time, const double dead_time, std::vector< double > *denominators, std::vector< double > *numerators)
Get first order low-pass coefficients for ZOH digital filter.
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void LpfCoefficients(const double ts, const double cutoff_freq, std::vector< double > *denominators, std::vector< double > *numerators)
Get low-pass coefficients for digital filter.