moveit2
The MoveIt Motion Planning Framework for ROS 2.
butterworth_filter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Andy Zelenak
36  Description: A first-order Butterworth low-pass filter. There is only one parameter to tune.
37  */
38 
40 #include <rclcpp/clock.hpp>
41 #include <rclcpp/logging.hpp>
42 
44 {
45 namespace
46 {
47 constexpr double EPSILON = 1e-9;
48 }
49 
50 ButterworthFilter::ButterworthFilter(double low_pass_filter_coeff)
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)
55 {
56  // guarantee this doesn't change because the logic below depends on this length implicitly
57  static_assert(ButterworthFilter::FILTER_LENGTH == 2,
58  "online_signal_smoothing::ButterworthFilter::FILTER_LENGTH should be 2");
59 
60  if (std::isinf(feedback_term_))
61  throw std::length_error("online_signal_smoothing::ButterworthFilter: infinite feedback_term_");
62 
63  if (std::isinf(scale_term_))
64  throw std::length_error("online_signal_smoothing::ButterworthFilter: infinite scale_term_");
65 
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");
69 
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");
73 }
74 
75 double ButterworthFilter::filter(double new_measurement)
76 {
77  // Push in the new measurement
78  previous_measurements_[1] = previous_measurements_[0];
79  previous_measurements_[0] = new_measurement;
80 
81  previous_filtered_measurement_ = scale_term_ * (previous_measurements_[1] + previous_measurements_[0] -
82  feedback_term_ * previous_filtered_measurement_);
83 
84  return previous_filtered_measurement_;
85 }
86 
87 void ButterworthFilter::reset(const double data)
88 {
89  previous_measurements_[0] = data;
90  previous_measurements_[1] = data;
91  previous_filtered_measurement_ = data;
92 }
93 
94 bool ButterworthFilterPlugin::initialize(rclcpp::Node::SharedPtr node, moveit::core::RobotModelConstPtr /* unused */,
95  size_t num_joints)
96 {
97  node_ = node;
98  num_joints_ = num_joints;
99  double filter_coeff = 1.5;
100  {
101  online_signal_smoothing::ParamListener param_listener(node_);
102  filter_coeff = param_listener.get_params().butterworth_filter_coeff;
103  }
104 
105  for (std::size_t i = 0; i < num_joints_; ++i)
106  {
107  position_filters_.emplace_back(filter_coeff);
108  }
109  return true;
110 };
111 
112 bool ButterworthFilterPlugin::doSmoothing(std::vector<double>& position_vector)
113 {
114  if (position_vector.size() != position_filters_.size())
115  {
116  RCLCPP_ERROR_THROTTLE(node_->get_logger(), *node_->get_clock(), 1000,
117  "Position vector to be smoothed does not have the right length.");
118  return false;
119  }
120  for (size_t i = 0; i < position_vector.size(); ++i)
121  {
122  // Lowpass filter the position command
123  position_vector[i] = position_filters_.at(i).filter(position_vector[i]);
124  }
125  return true;
126 };
127 
128 bool ButterworthFilterPlugin::reset(const std::vector<double>& joint_positions)
129 {
130  if (joint_positions.size() != position_filters_.size())
131  {
132  RCLCPP_ERROR_THROTTLE(node_->get_logger(), *node_->get_clock(), 1000,
133  "Position vector to be reset does not have the right length.");
134  return false;
135  }
136  for (size_t joint_idx = 0; joint_idx < joint_positions.size(); ++joint_idx)
137  {
138  position_filters_.at(joint_idx).reset(joint_positions.at(joint_idx));
139  }
140  return true;
141 };
142 
143 } // namespace online_signal_smoothing
144 
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