Skip to content

Commit

Permalink
Fix velocity limits of KR 10 R1100sixx (ros-industrial#186)
Browse files Browse the repository at this point in the history
  • Loading branch information
99arp authored Sep 22, 2021
1 parent 3119d19 commit 38e5dbf
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions kuka_kr10_support/urdf/kr10r1100sixx_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -117,47 +117,47 @@
<parent link="${prefix}base_link"/>
<child link="${prefix}link_1"/>
<axis xyz="0 0 -1"/>
<limit effort="0" lower="${-DEG2RAD * 170}" upper="${DEG2RAD * 170}" velocity="${DEG2RAD * 360}"/>
<limit effort="0" lower="${radians(-170)}" upper="${radians(170)}" velocity="${radians(300)}"/>
</joint>
<joint name="${prefix}joint_a2" type="revolute">
<origin xyz="0.025 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_1"/>
<child link="${prefix}link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="${-DEG2RAD * 190}" upper="${DEG2RAD * 45}" velocity="${DEG2RAD * 300}"/>
<limit effort="0" lower="${radians(-190)}" upper="${radians(45)}" velocity="${radians(225)}"/>
</joint>
<joint name="${prefix}joint_a3" type="revolute">
<origin xyz="0.560 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_2"/>
<child link="${prefix}link_3"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="${-DEG2RAD * 120}" upper="${DEG2RAD * 156}" velocity="${DEG2RAD * 360}"/>
<limit effort="0" lower="${radians(-120)}" upper="${radians(156)}" velocity="${radians(225)}"/>
</joint>
<joint name="${prefix}joint_a4" type="revolute">
<origin xyz="0 0 0.035" rpy="0 0 0"/>
<parent link="${prefix}link_3"/>
<child link="${prefix}link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="${-DEG2RAD * 185}" upper="${DEG2RAD * 185}" velocity="${DEG2RAD * 381}"/>
<limit effort="0" lower="${radians(-185)}" upper="${radians(185)}" velocity="${radians(381)}"/>
</joint>
<joint name="${prefix}joint_a5" type="revolute">
<origin xyz="0.515 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_4"/>
<child link="${prefix}link_5"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="${-DEG2RAD * 120}" upper="${DEG2RAD * 120}" velocity="${DEG2RAD * 388}"/>
<limit effort="0" lower="${radians(-120)}" upper="${radians(120)}" velocity="${radians(311)}"/>
</joint>
<joint name="${prefix}joint_a6" type="revolute">
<origin xyz="0.080 0 0" rpy="0 0 0"/>
<parent link="${prefix}link_5"/>
<child link="${prefix}link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="${-DEG2RAD * 350}" upper="${DEG2RAD * 350}" velocity="${DEG2RAD * 615}"/>
<limit effort="0" lower="${radians(-350)}" upper="${radians(350)}" velocity="${radians(492)}"/>
</joint>
<joint name="${prefix}joint_a6-tool0" type="fixed">
<parent link="${prefix}link_6"/>
<child link="${prefix}tool0"/>
<origin xyz="0 0 0" rpy="0 ${DEG2RAD * 90} 0"/>
<origin xyz="0 0 0" rpy="0 ${radians(90)} 0"/>
</joint>

<!-- ROS base_link to KUKA $ROBROOT coordinate system transform -->
Expand Down

0 comments on commit 38e5dbf

Please sign in to comment.