Skip to content

Commit

Permalink
Apply suggestions from code review
Browse files Browse the repository at this point in the history
Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com>
  • Loading branch information
christophfroehlich and saikishor authored Jan 23, 2025
1 parent 8c7a6bc commit 410c61d
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 7 deletions.
1 change: 1 addition & 0 deletions include/control_toolbox/pid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,6 +208,7 @@ class Pid

/*!
* \brief Reset the state of this PID controller
* @note The integral term is not retained and it is reset to zero
*/
void reset();

Expand Down
3 changes: 2 additions & 1 deletion include/control_toolbox/pid_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,6 +125,7 @@ class PidROS

/*!
* \brief Reset the state of this PID controller
* @note The integral term is not retained and it is reset to zero
*/
void reset();

Expand All @@ -133,7 +134,7 @@ class PidROS
*
* \param save_iterm boolean indicating if integral term is retained on reset()
*/
void reset(bool save_iterm = false);
void reset(bool save_iterm);

/*!
* \brief Set the PID error and compute the PID command with nonuniform time
Expand Down
6 changes: 0 additions & 6 deletions src/pid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,6 @@ void Pid::reset(bool save_iterm)
d_error_ = 0.0;
cmd_ = 0.0;

// If last integral error is already zero, just return
if (std::abs(i_error_) < std::numeric_limits<double>::epsilon())
{
return;
}

// Check to see if we should reset integral error here
if (!save_iterm) clear_saved_iterm();
}
Expand Down

0 comments on commit 410c61d

Please sign in to comment.