Skip to content

Commit

Permalink
Disable deprecation warning of deprecated class member
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 18, 2024
1 parent f694d57 commit 46e89a4
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 0 deletions.
1 change: 1 addition & 0 deletions include/control_toolbox/pid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -548,6 +548,7 @@ class CONTROL_TOOLBOX_PUBLIC Pid
double i_error_; /**< Integral of position error. */
double d_error_; /**< Derivative of position error. */
double cmd_; /**< Command to send. */
// TODO(christophfroehlich) remove this -> breaks ABI
[[deprecated("Use d_error_")]] double error_dot_; /**< Derivative error */
};

Expand Down
16 changes: 16 additions & 0 deletions src/pid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@

#include "control_toolbox/pid.hpp"

// Disable deprecated warnings
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
namespace control_toolbox
{
Pid::Pid(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Expand All @@ -66,6 +69,9 @@ Pid::Pid(const Pid & source)
reset();
}

// Enable deprecated warnings again
#pragma GCC diagnostic pop

Pid::~Pid() {}

void Pid::initialize(double p, double i, double d, double i_max, double i_min, bool antiwindup)
Expand All @@ -81,7 +87,13 @@ void Pid::reset()
p_error_ = 0.0;
i_error_ = 0.0;
d_error_ = 0.0;

// Disable deprecated warnings
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
error_dot_ = 0.0; // deprecated
#pragma GCC diagnostic pop

cmd_ = 0.0;
}

Expand Down Expand Up @@ -168,7 +180,11 @@ double Pid::compute_command(double error, double error_dot, const double & dt_s)
double p_term, d_term, i_term;
p_error_ = error; // this is error = target - state
d_error_ = error_dot;

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
error_dot_ = error_dot; // deprecated
#pragma GCC diagnostic pop

if (
dt_s <= 0.0 || !std::isfinite(error) || !std::isfinite(error_dot)) {
Expand Down

0 comments on commit 46e89a4

Please sign in to comment.