Apollo  6.0
Open source self driving car software
mean_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 <cstdint>
25 #include <deque>
26 #include <utility>
27 #include <vector>
28 
33 namespace apollo {
34 namespace common {
35 
45 class MeanFilter {
46  public:
52  explicit MeanFilter(const std::uint_fast8_t window_size);
56  MeanFilter() = default;
60  ~MeanFilter() = default;
65  double Update(const double measurement);
66 
67  private:
68  void RemoveEarliest();
69  void Insert(const double value);
70  double GetMin() const;
71  double GetMax() const;
72  bool ShouldPopOldestCandidate(const std::uint_fast8_t old_time) const;
73  std::uint_fast8_t window_size_ = 0;
74  double sum_ = 0.0;
75  std::uint_fast8_t time_ = 0;
76  // front = earliest
77  std::deque<double> values_;
78  // front = min
79  std::deque<std::pair<std::uint_fast8_t, double>> min_candidates_;
80  // front = max
81  std::deque<std::pair<std::uint_fast8_t, double>> max_candidates_;
82  bool initialized_ = false;
83 };
84 
85 } // namespace common
86 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
The MeanFilter class is used to smoothen a series of noisy numbers, such as sensor data or the output...
Definition: mean_filter.h:45
~MeanFilter()=default
Default destructor.
double Update(const double measurement)
Processes a new measurement in amortized constant time.
apollo::cyber::base::std value
MeanFilter()=default
Default constructor; defers initialization.