Autoware.Auto
filter_factory.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
18 #ifndef SIGNAL_FILTERS__FILTER_FACTORY_HPP_
19 #define SIGNAL_FILTERS__FILTER_FACTORY_HPP_
20 
24 
25 #include <algorithm>
26 #include <memory>
27 #include <stdexcept>
28 #include <string>
29 
30 namespace autoware
31 {
32 namespace common
33 {
34 namespace signal_filters
35 {
36 
37 enum class FilterType : int32_t
38 {
39  None = 0,
41 }; // enum class FilterType
42 
45 {
46 public:
54  template<typename T, typename ClockT = DummyClock>
55  static std::unique_ptr<FilterBase<T, ClockT>> create(const std::string & type, T cutoff_frequency)
56  {
58  auto type_clean = type;
59  (void)std::transform(
60  type_clean.begin(), type_clean.end(), type_clean.begin(),
61  [](auto c) {return std::tolower(c);});
62  if ("low_pass_filter" == type_clean) {
63  type_enum = FilterType::LowPassFilter;
64  } else if (type_clean.empty() || ("none" == type_clean)) {
65  type_enum = FilterType::None;
66  } else {
67  std::string err{"Unknown filter type: "};
68  err += type;
69  throw std::domain_error{err};
70  }
71  return create<T, ClockT>(type_enum, cutoff_frequency);
72  }
73 
81  template<typename T, typename ClockT = DummyClock>
82  static std::unique_ptr<FilterBase<T, ClockT>> create(FilterType type, T cutoff_frequency)
83  {
84  switch (type) {
85  case FilterType::None:
86  return nullptr;
88  return std::make_unique<LowPassFilter<T, ClockT>>(cutoff_frequency);
89  default:
90  throw std::domain_error{"Unknown filter type"};
91  }
92  }
93 }; // class FilterFactory
94 
95 } // namespace signal_filters
96 } // namespace common
97 } // namespace autoware
98 
99 #endif // SIGNAL_FILTERS__FILTER_FACTORY_HPP_
autoware::common::signal_filters::FilterType::None
@ None
visibility_control.hpp
autoware::common::signal_filters::FilterFactory::create
static std::unique_ptr< FilterBase< T, ClockT > > create(FilterType type, T cutoff_frequency)
Definition: filter_factory.hpp:82
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::signal_filters::FilterType
FilterType
Definition: filter_factory.hpp:37
autoware::common::signal_filters::FilterType::LowPassFilter
@ LowPassFilter
autoware::common::signal_filters::FilterFactory
Factory class to create some kind of low pass filter.
Definition: filter_factory.hpp:44
signal_filter.hpp
Interface definition for signal processing filters.
autoware::common::signal_filters::LowPassFilter
Definition: low_pass_filter.hpp:36
SIGNAL_FILTERS_PUBLIC
#define SIGNAL_FILTERS_PUBLIC
Definition: common/signal_filters/include/signal_filters/visibility_control.hpp:44
autoware::common::signal_filters::FilterFactory::create
static std::unique_ptr< FilterBase< T, ClockT > > create(const std::string &type, T cutoff_frequency)
Definition: filter_factory.hpp:55
low_pass_filter.hpp
Interface definition for signal processing filters.