ros2_control - rolling
Loading...
Searching...
No Matches
exponential_filter.hpp
1// Copyright (c) 2024, AIT Austrian Institute of Technology GmbH
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#ifndef CONTROL_FILTERS__EXPONENTIAL_FILTER_HPP_
16#define CONTROL_FILTERS__EXPONENTIAL_FILTER_HPP_
17
18#include <limits>
19#include <memory>
20#include <string>
21
22#include "filters/filter_base.hpp"
23
24#include "control_toolbox/exponential_filter_parameters.hpp"
25#include "control_toolbox/filters.hpp"
26
27namespace control_filters
28{
29
30/***************************************************/
45/***************************************************/
46
47template <typename T>
48class ExponentialFilter : public filters::FilterBase<T>
49{
50public:
54 bool configure() override;
55
64 bool update(const T & data_in, T & data_out) override;
65
66private:
67 std::shared_ptr<rclcpp::Logger> logger_;
68 std::shared_ptr<exponential_filter::ParamListener> parameter_handler_;
69 exponential_filter::Params parameters_;
70 T last_smoothed_value;
71};
72
73template <typename T>
75{
76 logger_.reset(
77 new rclcpp::Logger(this->logging_interface_->get_logger().get_child(this->filter_name_)));
78
79 // Initialize the parameters once
80 if (!parameter_handler_)
81 {
82 try
83 {
84 parameter_handler_ = std::make_shared<exponential_filter::ParamListener>(
85 this->params_interface_, this->param_prefix_);
86 }
87 catch (const std::exception & ex)
88 {
89 RCLCPP_ERROR(
90 (*logger_), "Exponential filter cannot be configured: %s (type : %s)", ex.what(),
91 typeid(ex).name());
92 parameter_handler_.reset();
93 return false;
94 }
95 catch (...)
96 {
97 RCLCPP_ERROR((*logger_), "Caught unknown exception while configuring Exponential filter");
98 parameter_handler_.reset();
99 return false;
100 }
101 }
102 parameters_ = parameter_handler_->get_params();
103
104 last_smoothed_value = std::numeric_limits<double>::quiet_NaN();
105
106 return true;
107}
108
109template <typename T>
110bool ExponentialFilter<T>::update(const T & data_in, T & data_out)
111{
112 if (!this->configured_)
113 {
114 throw std::runtime_error("Filter is not configured");
115 }
116
117 // Update internal parameters if required
118 if (parameter_handler_->is_old(parameters_))
119 {
120 parameters_ = parameter_handler_->get_params();
121 }
122
123 if (std::isnan(last_smoothed_value))
124 {
125 last_smoothed_value = data_in;
126 }
127
128 data_out = last_smoothed_value =
129 filters::exponentialSmoothing(data_in, last_smoothed_value, parameters_.alpha);
130 return true;
131}
132
133} // namespace control_filters
134
135#endif // CONTROL_FILTERS__EXPONENTIAL_FILTER_HPP_
A exponential filter class.
Definition exponential_filter.hpp:49
bool update(const T &data_in, T &data_out) override
Applies one iteration of the exponential filter.
Definition exponential_filter.hpp:110
bool configure() override
Configure the ExponentialFilter (access and process params).
Definition exponential_filter.hpp:74