We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
There was an error while loading. Please reload this page.
1 parent b21a7e1 commit 18c9f1fCopy full SHA for 18c9f1f
joint_trajectory_controller/src/joint_trajectory_controller.cpp
@@ -1167,6 +1167,11 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
1167
read_state_from_state_interfaces(state_current_);
1168
read_state_from_state_interfaces(last_commanded_state_);
1169
}
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
+ }
1175
last_commanded_time_ = rclcpp::Time();
1176
1177
// The controller should start by holding position at the beginning of active state
0 commit comments