From 1ec808b330802ba1ee9508155d8121eb29bfbf0d Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Mon, 4 Nov 2024 21:13:01 +0000 Subject: [PATCH] Rename to *Base --- ...ss_filter.hpp => low_pass_filter_base.hpp} | 34 +++++++++---------- .../control_filters/low_pass_filter_ros.hpp | 6 ++-- .../test_load_low_pass_filter_ros.cpp | 4 +-- 3 files changed, 21 insertions(+), 23 deletions(-) rename include/control_filters/{low_pass_filter.hpp => low_pass_filter_base.hpp} (85%) diff --git a/include/control_filters/low_pass_filter.hpp b/include/control_filters/low_pass_filter_base.hpp similarity index 85% rename from include/control_filters/low_pass_filter.hpp rename to include/control_filters/low_pass_filter_base.hpp index df8a97af..977b6a70 100644 --- a/include/control_filters/low_pass_filter.hpp +++ b/include/control_filters/low_pass_filter_base.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef CONTROL_FILTERS__LOW_PASS_FILTER_HPP_ -#define CONTROL_FILTERS__LOW_PASS_FILTER_HPP_ +#ifndef CONTROL_FILTERS__LOW_PASS_FILTER_BASE_HPP_ +#define CONTROL_FILTERS__LOW_PASS_FILTER_BASE_HPP_ #include #include @@ -27,7 +27,7 @@ namespace control_filters { /***************************************************/ -/*! \class LowPassFilter +/*! \class LowPassFilterBase \brief A Low-pass filter class. This class implements a low-pass filter for @@ -64,8 +64,6 @@ namespace control_filters \section Usage - The LowPassFilter class is meant to be instantiated as a filter in - a controller but can also be used elsewhere. For manual instantiation, you should first call configure() (in non-realtime) and then call update() at every update step. @@ -73,23 +71,23 @@ namespace control_filters /***************************************************/ template -class LowPassFilter +class LowPassFilterBase { public: // Default constructor - LowPassFilter(); + LowPassFilterBase(); - LowPassFilter(double sampling_frequency, double damping_frequency, double damping_intensity){ + LowPassFilterBase(double sampling_frequency, double damping_frequency, double damping_intensity){ set_params(sampling_frequency, damping_frequency, damping_intensity); } /*! - * \brief Destructor of LowPassFilter class. + * \brief Destructor of LowPassFilterBase class. */ - ~LowPassFilter(); + ~LowPassFilterBase(); /*! - * \brief Configure the LowPassFilter (access and process params). + * \brief Configure the LowPassFilterBase (access and process params). */ bool configure(); @@ -124,7 +122,7 @@ class LowPassFilter protected: /*! * \brief Internal computation of the feedforward and feedbackward coefficients - * according to the LowPassFilter parameters. + * according to the LowPassFilterBase parameters. */ void compute_internal_params() { @@ -147,17 +145,17 @@ class LowPassFilter }; template -LowPassFilter::LowPassFilter() : a1_(1.0), b1_(0.0) +LowPassFilterBase::LowPassFilterBase() : a1_(1.0), b1_(0.0) { } template -LowPassFilter::~LowPassFilter() +LowPassFilterBase::~LowPassFilterBase() { } template -bool LowPassFilter::configure() +bool LowPassFilterBase::configure() { compute_internal_params(); @@ -173,7 +171,7 @@ bool LowPassFilter::configure() } template <> -inline bool LowPassFilter::update( +inline bool LowPassFilterBase::update( const geometry_msgs::msg::WrenchStamped & data_in, geometry_msgs::msg::WrenchStamped & data_out) { if (!configured_) @@ -206,7 +204,7 @@ inline bool LowPassFilter::update( } template -bool LowPassFilter::update(const T & data_in, T & data_out) +bool LowPassFilterBase::update(const T & data_in, T & data_out) { if (!configured_) { @@ -223,4 +221,4 @@ bool LowPassFilter::update(const T & data_in, T & data_out) } // namespace control_filters -#endif // CONTROL_FILTERS__LOW_PASS_FILTER_HPP_ +#endif // CONTROL_FILTERS__LOW_PASS_FILTER_BASE_HPP_ diff --git a/include/control_filters/low_pass_filter_ros.hpp b/include/control_filters/low_pass_filter_ros.hpp index a9b040ae..2b9be803 100644 --- a/include/control_filters/low_pass_filter_ros.hpp +++ b/include/control_filters/low_pass_filter_ros.hpp @@ -24,7 +24,7 @@ #include "filters/filter_base.hpp" #include "geometry_msgs/msg/wrench_stamped.hpp" -#include "low_pass_filter.hpp" +#include "low_pass_filter_base.hpp" #include "low_pass_filter_parameters.hpp" namespace control_filters @@ -100,7 +100,7 @@ class LowPassFilterRos : public filters::FilterBase std::shared_ptr logger_; std::shared_ptr parameter_handler_; low_pass_filter::Params parameters_; - std::shared_ptr> lpf_; + std::shared_ptr> lpf_; }; template @@ -131,7 +131,7 @@ bool LowPassFilterRos::configure() } } parameters_ = parameter_handler_->get_params(); - lpf_ = std::make_shared>( + lpf_ = std::make_shared>( parameters_.sampling_frequency, parameters_.damping_frequency, parameters_.damping_intensity); diff --git a/test/control_filters/test_load_low_pass_filter_ros.cpp b/test/control_filters/test_load_low_pass_filter_ros.cpp index f49b56f8..fab3667a 100644 --- a/test/control_filters/test_load_low_pass_filter_ros.cpp +++ b/test/control_filters/test_load_low_pass_filter_ros.cpp @@ -39,7 +39,7 @@ TEST(TestLoadLowPassFilter, load_low_pass_filter_double) std::string filter_type = "control_filters/LowPassFilterDouble"; ASSERT_TRUE(filter_loader.isClassAvailable(filter_type)) << sstr.str(); - ASSERT_NO_THROW(filter = filter_loader.createSharedInstance(filter_type)); + EXPECT_NO_THROW(filter = filter_loader.createSharedInstance(filter_type)); rclcpp::shutdown(); } @@ -61,7 +61,7 @@ TEST(TestLoadLowPassFilter, load_low_pass_filter_wrench) std::string filter_type = "control_filters/LowPassFilterWrench"; ASSERT_TRUE(filter_loader.isClassAvailable(filter_type)) << sstr.str(); - ASSERT_NO_THROW(filter = filter_loader.createSharedInstance(filter_type)); + EXPECT_NO_THROW(filter = filter_loader.createSharedInstance(filter_type)); rclcpp::shutdown(); }