Skip to content

Commit

Permalink
Update ur10.urdf.xacro
Browse files Browse the repository at this point in the history
Corrected UR10's urdf to faithfully represent joint effort thresholds, velocity limits, and dynamics parameters.
  • Loading branch information
kphawkins committed Dec 17, 2013
1 parent 09ef4ea commit 78b2702
Showing 1 changed file with 11 additions and 11 deletions.
22 changes: 11 additions & 11 deletions ur_description/urdf/ur10.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,8 @@
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.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="330.0" velocity="2.16"/>
<dynamics damping="1.2" friction="0.0"/>
</joint>

<link name="${prefix}shoulder_link">
Expand Down Expand Up @@ -112,7 +112,7 @@
<origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0.0 1.0 0.0" />
<limit lower="${-2.0 * pi}" upper="${2.0 * pi}" effort="10.0" velocity="${pi}"/>
<dynamics damping="10" friction="0.1"/>
<dynamics damping="1.2" friction="0.0"/>
</joint>

<link name="${prefix}upper_arm_link">
Expand Down Expand Up @@ -143,8 +143,8 @@
<child link = "${prefix}forearm_link" />
<origin xyz="0.0 ${-elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.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.6" friction="0.0"/>
</joint>

<link name="${prefix}forearm_link">
Expand Down Expand Up @@ -173,8 +173,8 @@
<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.0 1.0 0.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="54.0" velocity="${pi}"/>
<dynamics damping="0.6" friction="0.0"/>
</joint>

<link name="${prefix}wrist_1_link">
Expand Down Expand Up @@ -205,8 +205,8 @@
<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 0.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="54.0" velocity="${pi}"/>
<dynamics damping="0.6" friction="0.0"/>
</joint>

<link name="${prefix}wrist_2_link">
Expand Down Expand Up @@ -237,8 +237,8 @@
<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.0 1.0 0.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="54.0" velocity="${pi}"/>
<dynamics damping="0.6" friction="0.0"/>
</joint>

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

0 comments on commit 78b2702

Please sign in to comment.