Branch data Line data Source code
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. 16 : : /// \file 17 : : /// \brief Interface definition for signal processing filters 18 : : #ifndef SIGNAL_FILTERS__FILTER_FACTORY_HPP_ 19 : : #define SIGNAL_FILTERS__FILTER_FACTORY_HPP_ 20 : : 21 : : #include <signal_filters/visibility_control.hpp> 22 : : #include <signal_filters/signal_filter.hpp> 23 : : #include <signal_filters/low_pass_filter.hpp> 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, 40 : : LowPassFilter 41 : : }; // enum class FilterType 42 : : 43 : : /// Factory class to create some kind of low pass filter 44 : : class SIGNAL_FILTERS_PUBLIC FilterFactory 45 : : { 46 : : public: 47 : : /// Create a low pass filter 48 : : /// \param[in] type The name of the filter type, expects one of "none, "low_pass_filter" 49 : : /// \param[in] cutoff_frequency The filter starts to have < 1.0 frequency response starting 50 : : /// around here 51 : : /// \tparam T The floating point type of the filter 52 : : /// \tparam ClockT The clock type of the filter. Use default parameter if you want to provide 53 : : /// durations between points yourself 54 : : template<typename T, typename ClockT = DummyClock> 55 : 18 : static std::unique_ptr<FilterBase<T, ClockT>> create(const std::string & type, T cutoff_frequency) 56 : : { 57 : : FilterType type_enum = FilterType::LowPassFilter; 58 : : auto type_clean = type; 59 : : (void)std::transform( 60 : : type_clean.begin(), type_clean.end(), type_clean.begin(), 61 : 42 : [](auto c) {return std::tolower(c);}); 62 [ + - ]: 18 : if ("low_pass_filter" == type_clean) { 63 : : type_enum = FilterType::LowPassFilter; 64 [ + + + + ]: 30 : } else if (type_clean.empty() || ("none" == type_clean)) { 65 : : type_enum = FilterType::None; 66 : : } else { 67 [ + - ]: 6 : std::string err{"Unknown filter type: "}; 68 : : err += type; 69 [ + - ]: 6 : throw std::domain_error{err}; 70 : : } 71 [ + - ]: 24 : return create<T, ClockT>(type_enum, cutoff_frequency); 72 : : } 73 : : 74 : : /// Create a low pass filter 75 : : /// \param[in] type The type of the filter type 76 : : /// \param[in] cutoff_frequency The filter starts to have < 1.0 frequency response starting 77 : : /// around here 78 : : /// \tparam T The floating point type of the filter 79 : : /// \tparam ClockT The clock type of the filter. Use default parameter if you want to provide 80 : : /// durations between points yourself 81 : : template<typename T, typename ClockT = DummyClock> 82 : 36 : static std::unique_ptr<FilterBase<T, ClockT>> create(FilterType type, T cutoff_frequency) 83 : : { 84 [ + + - ]: 36 : switch (type) { 85 : : case FilterType::None: 86 : : return nullptr; 87 : 24 : case FilterType::LowPassFilter: 88 : 24 : return std::make_unique<LowPassFilter<T, ClockT>>(cutoff_frequency); 89 : 0 : default: 90 [ # # ]: 0 : 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_