ros2_control - humble
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 <memory>
19#include <limits>
20#include <string>
21
22#include "filters/filter_base.hpp"
23
24#include "control_toolbox/filters.hpp"
25#include "exponential_filter_parameters.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 rclcpp::Clock::SharedPtr clock_;
68 std::shared_ptr<rclcpp::Logger> logger_;
69 std::shared_ptr<exponential_filter::ParamListener> parameter_handler_;
70 exponential_filter::Params parameters_;
71 T last_smoothed_value;
72};
73
74template <typename T>
76{
77 logger_.reset(
78 new rclcpp::Logger(this->logging_interface_->get_logger().get_child(this->filter_name_)));
79
80 // Initialize the parameters once
81 if (!parameter_handler_)
82 {
83 try
84 {
85 parameter_handler_ =
86 std::make_shared<exponential_filter::ParamListener>(this->params_interface_,
87 this->param_prefix_);
88 }
89 catch (const std::exception & ex) {
90 RCLCPP_ERROR((*logger_),
91 "Exponential filter cannot be configured: %s (type : %s)", ex.what(), typeid(ex).name());
92 parameter_handler_.reset();
93 return false;
94 }
95 catch (...) {
96 RCLCPP_ERROR((*logger_), "Caught unknown exception while configuring Exponential filter");
97 parameter_handler_.reset();
98 return false;
99 }
100 }
101 parameters_ = parameter_handler_->get_params();
102
103 last_smoothed_value = std::numeric_limits<double>::quiet_NaN();
104
105 return true;
106}
107
108template <typename T>
109bool ExponentialFilter<T>::update(const T & data_in, T & data_out)
110{
111 if (!this->configured_)
112 {
113 throw std::runtime_error("Filter is not configured");
114 }
115
116 // Update internal parameters if required
117 if (parameter_handler_->is_old(parameters_))
118 {
119 parameters_ = parameter_handler_->get_params();
120 }
121
122 if (std::isnan(last_smoothed_value))
123 {
124 last_smoothed_value = data_in;
125 }
126
127 data_out = last_smoothed_value =
128 filters::exponentialSmoothing(data_in, last_smoothed_value, parameters_.alpha);
129 return true;
130}
131
132} // namespace control_filters
133
134#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:109
bool configure() override
Configure the ExponentialFilter (access and process params).
Definition exponential_filter.hpp:75