Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

PID: Improve the API docs and change default value of antiwindup #202

Merged
merged 3 commits into from
Jul 18, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 39 additions & 6 deletions include/control_toolbox/pid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,12 +113,34 @@ class CONTROL_TOOLBOX_PUBLIC Pid
*/
struct Gains
{
// Optional constructor for passing in values without antiwindup
/*!
* \brief Optional constructor for passing in values without antiwindup
*
* \param p The proportional gain.
* \param i The integral gain.
* \param d The derivative gain.
* \param i_max The max integral windup.
* \param i_min The min integral windup.
*
* \throws An std::invalid_argument exception is thrown if i_min > i_max
*/
Gains(double p, double i, double d, double i_max, double i_min)
: p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(false)
{
}
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

does this constructor make sense at all? shouldn't be andiwindup_ set to true? Otherwise i_max and i_min doesn't have any effect.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think it is good to change it to true as well by default

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done

// Optional constructor for passing in values

/*!
* \brief Optional constructor for passing in values
*
* \param p The proportional gain.
* \param i The integral gain.
* \param d The derivative gain.
* \param i_max The max integral windup.
* \param i_min The min integral windup.
* \param antiwindup If true, antiwindup is enabled and i_max/i_min are enforced
*
* \throws An std::invalid_argument exception is thrown if i_min > i_max
*/
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
: p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(antiwindup)
{
Expand All @@ -145,9 +167,9 @@ class CONTROL_TOOLBOX_PUBLIC Pid
* \param d The derivative gain.
* \param i_max The max integral windup.
* \param i_min The min integral windup.
* \param antiwindup If true, antiwindup is enabled and i_max/i_min are enforced
*
* \note
* An std::invalid_argument exception is thrown if i_min > i_max
* \throws An std::invalid_argument exception is thrown if i_min > i_max
*/
Pid(
double p = 0.0, double i = 0.0, double d = 0.0, double i_max = 0.0, double i_min = -0.0,
Expand All @@ -173,6 +195,7 @@ class CONTROL_TOOLBOX_PUBLIC Pid
* \param d The derivative gain.
* \param i_max The max integral windup.
* \param i_min The min integral windup.
* \param antiwindup If true, antiwindup is enabled and i_max/i_min are enforced
*
* \note New gains are not applied if i_min_ > i_max_
*/
Expand All @@ -192,6 +215,15 @@ class CONTROL_TOOLBOX_PUBLIC Pid
* \param i_min The min integral windup.
*/
void getGains(double & p, double & i, double & d, double & i_max, double & i_min);
/*!
* \brief Get PID gains for the controller.
* \param p The proportional gain.
* \param i The integral gain.
* \param d The derivative gain.
* \param i_max The max integral windup.
* \param i_min The min integral windup.
* \param antiwindup If true, antiwindup is enabled and i_max/i_min are enforced
*/
void getGains(
double & p, double & i, double & d, double & i_max, double & i_min, bool & antiwindup);

Expand All @@ -208,6 +240,7 @@ class CONTROL_TOOLBOX_PUBLIC Pid
* \param d The derivative gain.
* \param i_max The max integral windup.
* \param i_min The min integral windup.
* \param antiwindup If true, antiwindup is enabled and i_max/i_min are enforced
*
* \note New gains are not applied if i_min > i_max
*/
Expand All @@ -231,7 +264,7 @@ class CONTROL_TOOLBOX_PUBLIC Pid
*
* \returns PID command
*/
double computeCommand(double error, uint64_t dt);
[[nodiscard]] double computeCommand(double error, uint64_t dt);

/*!
* \brief Set the PID error and compute the PID command with nonuniform
Expand All @@ -244,7 +277,7 @@ class CONTROL_TOOLBOX_PUBLIC Pid
*
* \returns PID command
*/
double computeCommand(double error, double error_dot, uint64_t dt);
[[nodiscard]] double computeCommand(double error, double error_dot, uint64_t dt);

/*!
* \brief Set current command for this PID controller
Expand Down
2 changes: 1 addition & 1 deletion test/pid_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ TEST(ParameterTest, gainSettingCopyPIDTest)

// Send update command to populate errors -------------------------------------------------
pid1.setCurrentCmd(10);
pid1.computeCommand(20, 1.0 * 1e9);
(void) pid1.computeCommand(20, 1.0 * 1e9);

// Test copy constructor -------------------------------------------------
Pid pid2(pid1);
Expand Down
Loading