Skip to content

Commit

Permalink
Initialize antiwindup variable properly (#326) (#328)
Browse files Browse the repository at this point in the history
(cherry picked from commit 1ef9652)

Co-authored-by: Christoph Fröhlich <[email protected]>
  • Loading branch information
mergify[bot] and christophfroehlich authored May 17, 2024
1 parent 64916f0 commit 522a3a9
Showing 1 changed file with 1 addition and 3 deletions.
4 changes: 1 addition & 3 deletions gazebo_ros2_control/src/gazebo_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ control_toolbox::Pid GazeboSystem::extractPID(
double kd;
double max_integral_error;
double min_integral_error;
bool antiwindup;
bool antiwindup = false;

if (joint_info.parameters.find(prefix + "kp") != joint_info.parameters.end()) {
kp = std::stod(joint_info.parameters.at(prefix + "kp"));
Expand Down Expand Up @@ -199,8 +199,6 @@ control_toolbox::Pid GazeboSystem::extractPID(
{
antiwindup = true;
}
} else {
antiwindup = false;
}

RCLCPP_INFO_STREAM(
Expand Down

0 comments on commit 522a3a9

Please sign in to comment.