Skip to content

Commit 5f26538

Browse files
authored
Disable enforcing command limits (#1342)
This feature has recently been added in ros2_control and enabled in Rolling / Kilted by default. However, this causes command clampings due to the tracking error that comes from the controller cascade using servoj on the robot. This may be changed in the future once there is another implementation available taking tracking errors into account.
1 parent d497de3 commit 5f26538

File tree

1 file changed

+8
-0
lines changed

1 file changed

+8
-0
lines changed

ur_robot_driver/config/ur_controllers.yaml

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,14 @@ controller_manager:
4242
tool_contact_controller:
4343
type: ur_controllers/ToolContactController
4444

45+
# The way this is currently implemented upstream doesn't really work for us. When using
46+
# position control, the robot will have a tracking error. However, limits will be enforced
47+
# from the currently reported position, effectively limiting the possible step size using the
48+
# joints' velocity limits. Until this is resolved, we will keep command limits non-enforced.
49+
# Note: On Jazzy this is the default behavior, anyway. For Rolling / Kilted this defaults to
50+
# true.
51+
enforce_command_limits: false
52+
4553
speed_scaling_state_broadcaster:
4654
ros__parameters:
4755
state_publish_rate: 100.0

0 commit comments

Comments
 (0)