Skip to content

Commit

Permalink
Rename to *Base
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 4, 2024
1 parent 7cd9576 commit 1ec808b
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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 <Eigen/Dense>
#include <cmath>
Expand All @@ -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
Expand Down Expand Up @@ -64,32 +64,30 @@ 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.
*/
/***************************************************/

template <typename T>
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();

Expand Down Expand Up @@ -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()
{
Expand All @@ -147,17 +145,17 @@ class LowPassFilter
};

template <typename T>
LowPassFilter<T>::LowPassFilter() : a1_(1.0), b1_(0.0)
LowPassFilterBase<T>::LowPassFilterBase() : a1_(1.0), b1_(0.0)
{
}

template <typename T>
LowPassFilter<T>::~LowPassFilter()
LowPassFilterBase<T>::~LowPassFilterBase()
{
}

template <typename T>
bool LowPassFilter<T>::configure()
bool LowPassFilterBase<T>::configure()
{
compute_internal_params();

Expand All @@ -173,7 +171,7 @@ bool LowPassFilter<T>::configure()
}

template <>
inline bool LowPassFilter<geometry_msgs::msg::WrenchStamped>::update(
inline bool LowPassFilterBase<geometry_msgs::msg::WrenchStamped>::update(
const geometry_msgs::msg::WrenchStamped & data_in, geometry_msgs::msg::WrenchStamped & data_out)
{
if (!configured_)
Expand Down Expand Up @@ -206,7 +204,7 @@ inline bool LowPassFilter<geometry_msgs::msg::WrenchStamped>::update(
}

template <typename T>
bool LowPassFilter<T>::update(const T & data_in, T & data_out)
bool LowPassFilterBase<T>::update(const T & data_in, T & data_out)
{
if (!configured_)
{
Expand All @@ -223,4 +221,4 @@ bool LowPassFilter<T>::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_
6 changes: 3 additions & 3 deletions include/control_filters/low_pass_filter_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -100,7 +100,7 @@ class LowPassFilterRos : public filters::FilterBase<T>
std::shared_ptr<rclcpp::Logger> logger_;
std::shared_ptr<low_pass_filter::ParamListener> parameter_handler_;
low_pass_filter::Params parameters_;
std::shared_ptr<LowPassFilter<T>> lpf_;
std::shared_ptr<LowPassFilterBase<T>> lpf_;
};

template <typename T>
Expand Down Expand Up @@ -131,7 +131,7 @@ bool LowPassFilterRos<T>::configure()
}
}
parameters_ = parameter_handler_->get_params();
lpf_ = std::make_shared<LowPassFilter<T>>(
lpf_ = std::make_shared<LowPassFilterBase<T>>(
parameters_.sampling_frequency,
parameters_.damping_frequency,
parameters_.damping_intensity);
Expand Down
4 changes: 2 additions & 2 deletions test/control_filters/test_load_low_pass_filter_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand All @@ -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();
}

0 comments on commit 1ec808b

Please sign in to comment.