40 #include <rclcpp/clock.hpp>
41 #include <rclcpp/logging.hpp>
47 constexpr
double EPSILON = 1e-9;
51 : previous_measurements_{ 0., 0. }
52 , previous_filtered_measurement_(0.)
53 , scale_term_(1. / (1. + low_pass_filter_coeff))
54 , feedback_term_(1. - low_pass_filter_coeff)
57 static_assert(ButterworthFilter::FILTER_LENGTH == 2,
58 "online_signal_smoothing::ButterworthFilter::FILTER_LENGTH should be 2");
60 if (std::isinf(feedback_term_))
61 throw std::length_error(
"online_signal_smoothing::ButterworthFilter: infinite feedback_term_");
63 if (std::isinf(scale_term_))
64 throw std::length_error(
"online_signal_smoothing::ButterworthFilter: infinite scale_term_");
66 if (low_pass_filter_coeff < 1)
67 throw std::length_error(
68 "online_signal_smoothing::ButterworthFilter: Filter coefficient < 1. makes the lowpass filter unstable");
70 if (std::abs(feedback_term_) <
EPSILON)
71 throw std::length_error(
72 "online_signal_smoothing::ButterworthFilter: Filter coefficient value resulted in feedback term of 0");
78 previous_measurements_[1] = previous_measurements_[0];
79 previous_measurements_[0] = new_measurement;
81 previous_filtered_measurement_ = scale_term_ * (previous_measurements_[1] + previous_measurements_[0] -
82 feedback_term_ * previous_filtered_measurement_);
84 return previous_filtered_measurement_;
89 previous_measurements_[0] = data;
90 previous_measurements_[1] = data;
91 previous_filtered_measurement_ = data;
98 num_joints_ = num_joints;
99 double filter_coeff = 1.5;
101 online_signal_smoothing::ParamListener param_listener(node_);
102 filter_coeff = param_listener.get_params().butterworth_filter_coeff;
105 for (std::size_t i = 0; i < num_joints_; ++i)
107 position_filters_.emplace_back(filter_coeff);
114 if (position_vector.size() != position_filters_.size())
116 RCLCPP_ERROR_THROTTLE(node_->get_logger(), *node_->get_clock(), 1000,
117 "Position vector to be smoothed does not have the right length.");
120 for (
size_t i = 0; i < position_vector.size(); ++i)
123 position_vector[i] = position_filters_.at(i).filter(position_vector[i]);
130 if (joint_positions.size() != position_filters_.size())
132 RCLCPP_ERROR_THROTTLE(node_->get_logger(), *node_->get_clock(), 1000,
133 "Position vector to be reset does not have the right length.");
136 for (
size_t joint_idx = 0; joint_idx < joint_positions.size(); ++joint_idx)
138 position_filters_.at(joint_idx).reset(joint_positions.at(joint_idx));
145 #include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
bool initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr robot_model, size_t num_joints) override
bool doSmoothing(std::vector< double > &position_vector) override
bool reset(const std::vector< double > &joint_positions) override
ButterworthFilter()=delete
double filter(double new_measurement)
void reset(const double data)