Skip to content

Commit b243308

Browse files
committed
Added PID gains for the SJTC velocity interface
The gains are set to work for all e-series robots, but will not work for UR15/20/30. As far as I can tell, those models do not support this kind of control.
1 parent e860145 commit b243308

File tree

1 file changed

+9
-1
lines changed

1 file changed

+9
-1
lines changed

ur_robot_driver/config/ur_controllers.yaml

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,7 @@ joint_trajectory_controller:
8787
- $(var tf_prefix)wrist_2_joint
8888
- $(var tf_prefix)wrist_3_joint
8989
command_interfaces:
90-
- position
90+
- velocity
9191
state_interfaces:
9292
- position
9393
- velocity
@@ -137,6 +137,14 @@ scaled_joint_trajectory_controller:
137137
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
138138
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
139139
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
140+
gains:
141+
# These values will work for all e-series robots, but will not work for UR15/20/30
142+
$(var tf_prefix)shoulder_pan_joint: {p: 5.0, i: 0.3, d: 0.01, ff_velocity_scale: 1.0, i_clamp: 1.0, antiwindup_strategy: conditional_integration}
143+
$(var tf_prefix)shoulder_lift_joint: {p: 5.0, i: 0.3, d: 0.01, ff_velocity_scale: 1.0, i_clamp: 1.0, antiwindup_strategy: conditional_integration}
144+
$(var tf_prefix)elbow_joint: {p: 5.0, i: 0.3, d: 0.01, ff_velocity_scale: 1.0, i_clamp: 1.0, antiwindup_strategy: conditional_integration}
145+
$(var tf_prefix)wrist_1_joint: {p: 5.0, i: 0.3, d: 0.01, ff_velocity_scale: 1.0, i_clamp: 1.0, antiwindup_strategy: conditional_integration}
146+
$(var tf_prefix)wrist_2_joint: {p: 5.0, i: 0.3, d: 0.01, ff_velocity_scale: 1.0, i_clamp: 1.0, antiwindup_strategy: conditional_integration}
147+
$(var tf_prefix)wrist_3_joint: {p: 5.0, i: 0.3, d: 0.01, ff_velocity_scale: 1.0, i_clamp: 1.0, antiwindup_strategy: conditional_integration}
140148

141149
passthrough_trajectory_controller:
142150
ros__parameters:

0 commit comments

Comments
 (0)