Apollo 10.0
自动驾驶开放平台
digital_filter_coefficients.h
浏览该文件的文档.
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
30namespace apollo {
31namespace common {
32
40void LpfCoefficients(const double ts, const double cutoff_freq,
41 std::vector<double> *denominators,
42 std::vector<double> *numerators);
43
53void LpFirstOrderCoefficients(const double ts, const double settling_time,
54 const double dead_time,
55 std::vector<double> *denominators,
56 std::vector<double> *numerators);
57
58} // namespace common
59} // 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.
void LpfCoefficients(const double ts, const double cutoff_freq, std::vector< double > *denominators, std::vector< double > *numerators)
Get low-pass coefficients for digital filter.
class register implement
Definition arena_queue.h:37