Skip to content

Commit

Permalink
Remove shadowed variables
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 6, 2024
1 parent 7d008a4 commit 683ffe9
Showing 1 changed file with 3 additions and 20 deletions.
23 changes: 3 additions & 20 deletions include/control_toolbox/low_pass_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,30 +101,16 @@ class LowPassFilter
*/
bool update(const T & data_in, T & data_out);

bool set_params(
const double sampling_frequency,
const double damping_frequency,
const double damping_intensity)
{
// TODO(roncapat): parameters validation
this->sampling_frequency = sampling_frequency;
this->damping_frequency = damping_frequency;
this->damping_intensity = damping_intensity;
compute_internal_params();
return true;
}

bool is_configured() const
{
return configured_;
}

protected:
/*!
* \brief Internal computation of the feedforward and feedbackward coefficients
* according to the LowPassFilter parameters.
*/
void compute_internal_params()
void set_params(double sampling_frequency, double damping_frequency, double damping_intensity)
{
a1_ = exp(
-1.0 / sampling_frequency * (2.0 * M_PI * damping_frequency) /
Expand All @@ -134,13 +120,12 @@ class LowPassFilter

private:
// Filter parameters
double a1_; /** feedbackward coefficient. */
double b1_; /** feedforward coefficient. */
/** internal data storage (double). */
double filtered_value, filtered_old_value, old_value;
/** 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. */
bool configured_ = false;
};

Expand All @@ -157,8 +142,6 @@ LowPassFilter<T>::~LowPassFilter()
template <typename T>
bool LowPassFilter<T>::configure()
{
compute_internal_params();

// Initialize storage Vectors
filtered_value = filtered_old_value = old_value = 0;
// TODO(destogl): make the size parameterizable and more intelligent is using complex types
Expand Down

0 comments on commit 683ffe9

Please sign in to comment.