Skip to content

Commit 18c9f1f

Browse files
authored
Reset JTC PID's to zero on_activate() (#1840)
1 parent b21a7e1 commit 18c9f1f

File tree

1 file changed

+5
-0
lines changed

1 file changed

+5
-0
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1167,6 +1167,11 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
11671167
read_state_from_state_interfaces(state_current_);
11681168
read_state_from_state_interfaces(last_commanded_state_);
11691169
}
1170+
// reset/zero out all of the PID's (The integral term is not retained and reset to zero)
1171+
for (auto & pid : pids_)
1172+
{
1173+
pid->reset();
1174+
}
11701175
last_commanded_time_ = rclcpp::Time();
11711176

11721177
// The controller should start by holding position at the beginning of active state

0 commit comments

Comments
 (0)