Skip to content
Snippets Groups Projects
Commit 78b27026 authored by kphawkins's avatar kphawkins
Browse files

Update ur10.urdf.xacro

Corrected UR10's urdf to faithfully represent joint effort thresholds, velocity limits, and dynamics parameters.
parent 09ef4ead
Branches
Tags
No related merge requests found
......@@ -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">
......@@ -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">
......@@ -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">
......@@ -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">
......@@ -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">
......@@ -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">
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment