64 bool update(
const T & data_in, T & data_out)
override;
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;
78 new rclcpp::Logger(this->logging_interface_->get_logger().get_child(this->filter_name_)));
81 if (!parameter_handler_)
86 std::make_shared<exponential_filter::ParamListener>(this->params_interface_,
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();
96 RCLCPP_ERROR((*logger_),
"Caught unknown exception while configuring Exponential filter");
97 parameter_handler_.reset();
101 parameters_ = parameter_handler_->get_params();
103 last_smoothed_value = std::numeric_limits<double>::quiet_NaN();
111 if (!this->configured_)
113 throw std::runtime_error(
"Filter is not configured");
117 if (parameter_handler_->is_old(parameters_))
119 parameters_ = parameter_handler_->get_params();
122 if (std::isnan(last_smoothed_value))
124 last_smoothed_value = data_in;
127 data_out = last_smoothed_value =
128 filters::exponentialSmoothing(data_in, last_smoothed_value, parameters_.alpha);
bool update(const T &data_in, T &data_out) override
Applies one iteration of the exponential filter.
Definition exponential_filter.hpp:109