77 new rclcpp::Logger(this->logging_interface_->get_logger().get_child(this->filter_name_)));
80 if (!parameter_handler_)
84 parameter_handler_ = std::make_shared<exponential_filter::ParamListener>(
85 this->params_interface_, this->param_prefix_);
87 catch (
const std::exception & ex)
90 (*logger_),
"Exponential filter cannot be configured: %s (type : %s)", ex.what(),
92 parameter_handler_.reset();
97 RCLCPP_ERROR((*logger_),
"Caught unknown exception while configuring Exponential filter");
98 parameter_handler_.reset();
102 parameters_ = parameter_handler_->get_params();
104 last_smoothed_value = std::numeric_limits<double>::quiet_NaN();
112 if (!this->configured_)
114 throw std::runtime_error(
"Filter is not configured");
118 if (parameter_handler_->is_old(parameters_))
120 parameters_ = parameter_handler_->get_params();
123 if (std::isnan(last_smoothed_value))
125 last_smoothed_value = data_in;
128 data_out = last_smoothed_value =
129 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:110