Skip to content

Commit

Permalink
Rename base class again and move to different namespace
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 4, 2024
1 parent e04739b commit 3171fb0
Show file tree
Hide file tree
Showing 3 changed files with 25 additions and 25 deletions.
4 changes: 2 additions & 2 deletions include/control_filters/low_pass_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,10 @@
// Deprecation notice
#ifdef _WIN32
#pragma message( \
"This header include is deprecated. Please update your code to use 'low_pass_filter_ros.hpp' header and link against 'control_toolbox' library.") //NOLINT
"This header include is deprecated. Please update your code to use 'control_toolbox/low_pass_filter_ros.hpp' header.") //NOLINT
#else
#warning \
"This header include is deprecated. Please update your code to use 'low_pass_filter_ros.hpp' header and link against 'control_toolbox' library." //NOLINT
"This header include is deprecated. Please update your code to use 'control_toolbox/low_pass_filter_ros.hpp' header." //NOLINT
#endif

namespace control_filters
Expand Down
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_base.hpp"
#include "control_toolbox/low_pass_filter.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<LowPassFilterBase<T>> lpf_;
std::shared_ptr<control_toolbox::LowPassFilter<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<LowPassFilterBase<T>>(
lpf_ = std::make_shared<control_toolbox::LowPassFilter<T>>(
parameters_.sampling_frequency,
parameters_.damping_frequency,
parameters_.damping_intensity);
Expand Down
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_BASE_HPP_
#define CONTROL_FILTERS__LOW_PASS_FILTER_BASE_HPP_
#ifndef CONTROL_TOOLBOX__LOW_PASS_FILTER_HPP_
#define CONTROL_TOOLBOX__LOW_PASS_FILTER_HPP_

#include <Eigen/Dense>
#include <cmath>
Expand All @@ -23,11 +23,11 @@

#include "geometry_msgs/msg/wrench_stamped.hpp"

namespace control_filters
namespace control_toolbox
{

/***************************************************/
/*! \class LowPassFilterBase
/*! \class LowPassFilter
\brief A Low-pass filter class.
This class implements a low-pass filter for
Expand Down Expand Up @@ -71,23 +71,23 @@ namespace control_filters
/***************************************************/

template <typename T>
class LowPassFilterBase
class LowPassFilter
{
public:
// Default constructor
LowPassFilterBase();
LowPassFilter();

LowPassFilterBase(double sampling_frequency, double damping_frequency, double damping_intensity){
LowPassFilter(double sampling_frequency, double damping_frequency, double damping_intensity){
set_params(sampling_frequency, damping_frequency, damping_intensity);
}

/*!
* \brief Destructor of LowPassFilterBase class.
* \brief Destructor of LowPassFilter class.
*/
~LowPassFilterBase();
~LowPassFilter();

/*!
* \brief Configure the LowPassFilterBase (access and process params).
* \brief Configure the LowPassFilter (access and process params).
*/
bool configure();

Expand Down Expand Up @@ -122,7 +122,7 @@ class LowPassFilterBase
protected:
/*!
* \brief Internal computation of the feedforward and feedbackward coefficients
* according to the LowPassFilterBase parameters.
* according to the LowPassFilter parameters.
*/
void compute_internal_params()
{
Expand All @@ -139,23 +139,23 @@ class LowPassFilterBase
/** internal data storage (wrench). */
Eigen::Matrix<double, 6, 1> msg_filtered, msg_filtered_old, msg_old;
double sampling_frequency, damping_frequency, damping_intensity;
double a1_; /**< feedbackward coefficient. */
double b1_; /**< feedforward coefficient. */
double a1_; /** feedbackward coefficient. */
double b1_; /** feedforward coefficient. */
bool configured_ = false;
};

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

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

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

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

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

template <typename T>
bool LowPassFilterBase<T>::update(const T & data_in, T & data_out)
bool LowPassFilter<T>::update(const T & data_in, T & data_out)
{
if (!configured_)
{
Expand All @@ -219,6 +219,6 @@ bool LowPassFilterBase<T>::update(const T & data_in, T & data_out)
return true;
}

} // namespace control_filters
} // namespace control_toolbox

#endif // CONTROL_FILTERS__LOW_PASS_FILTER_BASE_HPP_
#endif // CONTROL_TOOLBOX__LOW_PASS_FILTER_HPP_

0 comments on commit 3171fb0

Please sign in to comment.