Skip to content

Commit

Permalink
Update ur5.urdf.xacro
Browse files Browse the repository at this point in the history
Corrected effort thresholds and friction values for UR5 urdf.
  • Loading branch information
kphawkins committed Dec 17, 2013
1 parent 6e58204 commit 09ef4ea
Showing 1 changed file with 12 additions and 12 deletions.
24 changes: 12 additions & 12 deletions ur_description/urdf/ur5.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0 0 1" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="${pi}"/>
<dynamics damping="0.4" friction="0.0"/>
</joint>

<link name="${prefix}shoulder_link">
Expand All @@ -107,8 +107,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "${prefix}upper_arm_link" />
<origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="${pi}"/>
<dynamics damping="0.4" friction="0.0"/>
</joint>

<link name="${prefix}upper_arm_link">
Expand Down Expand Up @@ -136,8 +136,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "${prefix}forearm_link" />
<origin xyz="0.0 ${-elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="150.0" velocity="${pi}"/>
<dynamics damping="0.4" friction="0.0"/>
</joint>

<link name="${prefix}forearm_link">
Expand All @@ -164,8 +164,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "${prefix}wrist_1_link" />
<origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-1.0 * pi}" upper="${0.25 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<limit lower="${-1.0 * pi}" upper="${0.25 * pi}" effort="28.0" velocity="${pi}"/>
<dynamics damping="0.3" friction="0.0"/>
</joint>

<link name="${prefix}wrist_1_link">
Expand Down Expand Up @@ -193,8 +193,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "${prefix}wrist_2_link" />
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" />
<axis xyz="0 0 1" />
<limit lower="${-1.0 * pi}" upper="${1.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<limit lower="${-1.0 * pi}" upper="${1.0 * pi}" effort="28.0" velocity="${pi}"/>
<dynamics damping="0.3" friction="0.0"/>
</joint>

<link name="${prefix}wrist_2_link">
Expand Down Expand Up @@ -222,8 +222,8 @@ center_of_mass = [ [0, -0.02561, 0.00193], [0.2125, 0, 0.11336], [0.11993, 0.0,
<child link = "${prefix}wrist_3_link" />
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0 1 0" />
<limit lower="${-1.0 * pi}" upper="${1.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<limit lower="${-1.0 * pi}" upper="${1.0 * pi}" effort="28.0" velocity="${pi}"/>
<dynamics damping="0.3" friction="0.0"/>
</joint>

<link name="${prefix}wrist_3_link">
Expand Down

0 comments on commit 09ef4ea

Please sign in to comment.