Skip to content

Commit 7619306

Browse files
author
Felix Exner
committed
Attempt to fix moveit servo_node
This makes it start but I couldn't get the robot moving.
1 parent d3d53d5 commit 7619306

File tree

2 files changed

+2
-1
lines changed

2 files changed

+2
-1
lines changed

ur_moveit_config/config/ur_servo.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ num_outgoing_halt_msgs_to_publish: 4
5252
## Configure handling of singularities and joint limits
5353
lower_singularity_threshold: 100.0 # Start decelerating when the condition number hits this (close to singularity)
5454
hard_stop_singularity_threshold: 200.0 # Stop when the condition number hits this
55-
joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger.
55+
joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians]. If moving quickly, make this larger.
5656

5757
## Topic names
5858
cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands

ur_moveit_config/launch/ur_moveit.launch.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -256,6 +256,7 @@ def launch_setup(context, *args, **kwargs):
256256
servo_params,
257257
robot_description,
258258
robot_description_semantic,
259+
robot_description_kinematics,
259260
],
260261
output="screen",
261262
)

0 commit comments

Comments
 (0)