Skip to content

Commit

Permalink
Add thirdparty experimental Kuka KR120R2500Pro URDF file
Browse files Browse the repository at this point in the history
  • Loading branch information
j3soon committed Nov 8, 2023
1 parent cc1aab0 commit fa39cbf
Show file tree
Hide file tree
Showing 15 changed files with 1,934 additions and 0 deletions.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.

Large diffs are not rendered by default.

311 changes: 311 additions & 0 deletions thirdparty/kuka_kr120_support/meshes/kr120r2500pro/visual/link_1.dae

Large diffs are not rendered by default.

198 changes: 198 additions & 0 deletions thirdparty/kuka_kr120_support/meshes/kr120r2500pro/visual/link_2.dae

Large diffs are not rendered by default.

395 changes: 395 additions & 0 deletions thirdparty/kuka_kr120_support/meshes/kr120r2500pro/visual/link_3.dae

Large diffs are not rendered by default.

198 changes: 198 additions & 0 deletions thirdparty/kuka_kr120_support/meshes/kr120r2500pro/visual/link_4.dae

Large diffs are not rendered by default.

198 changes: 198 additions & 0 deletions thirdparty/kuka_kr120_support/meshes/kr120r2500pro/visual/link_5.dae

Large diffs are not rendered by default.

198 changes: 198 additions & 0 deletions thirdparty/kuka_kr120_support/meshes/kr120r2500pro/visual/link_6.dae

Large diffs are not rendered by default.

196 changes: 196 additions & 0 deletions thirdparty/kuka_kr120_support/urdf/kr120r2500pro.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,196 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from kr120r2500pro.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!--Generates a urdf from the macro in kr120r2500pro_macro.xacro -->
<robot name="kuka_kr120r2500pro" xmlns:xacro="http://wiki.ros.org/xacro">
<link name="base_link">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/visual/base_link.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/collision/base_link.stl"/>
</geometry>
</collision>
</link>
<link name="link_1">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/visual/link_1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/collision/link_1.stl"/>
</geometry>
</collision>
</link>
<link name="link_2">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/visual/link_2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/collision/link_2.stl"/>
</geometry>
</collision>
</link>
<link name="link_3">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/visual/link_3.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/collision/link_3.stl"/>
</geometry>
</collision>
</link>
<link name="link_4">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/visual/link_4.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/collision/link_4.stl"/>
</geometry>
</collision>
</link>
<link name="link_5">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/visual/link_5.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/collision/link_5.stl"/>
</geometry>
</collision>
</link>
<link name="link_6">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/visual/link_6.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr120_support/meshes/kr120r2500pro/collision/link_6.stl"/>
</geometry>
</collision>
</link>
<link name="tool0"/>
<joint name="joint_a1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.675"/>
<parent link="base_link"/>
<child link="link_1"/>
<axis xyz="0 0 -1"/>
<limit effort="0" lower="-3.22885911619" upper="3.22885911619" velocity="2.72271363311"/>
</joint>
<joint name="joint_a2" type="revolute">
<origin rpy="0 0 0" xyz="0.35 0 0"/>
<parent link="link_1"/>
<child link="link_2"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.70526034059" upper="0.610865238198" velocity="2.72271363311"/>
</joint>
<joint name="joint_a3" type="revolute">
<origin rpy="0 0 0" xyz="1.150 0 0"/>
<parent link="link_2"/>
<child link="link_3"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.26892802759" upper="2.68780704807" velocity="2.72271363311"/>
</joint>
<joint name="joint_a4" type="revolute">
<origin rpy="0 0 0" xyz="1.0 0 -0.041"/>
<parent link="link_3"/>
<child link="link_4"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-6.10865238198" upper="6.10865238198" velocity="5.75958653158"/>
</joint>
<joint name="joint_a5" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_4"/>
<child link="link_5"/>
<axis xyz="0 1 0"/>
<limit effort="0" lower="-2.26892802759" upper="2.26892802759" velocity="5.75958653158"/>
</joint>
<joint name="joint_a6" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="link_5"/>
<child link="link_6"/>
<axis xyz="-1 0 0"/>
<limit effort="0" lower="-6.10865238198" upper="6.10865238198" velocity="10.7337748998"/>
</joint>
<joint name="joint_a6-tool0" type="fixed">
<parent link="link_6"/>
<child link="tool0"/>
<origin rpy="0 1.57079632679 0" xyz="0.215 0 0"/>
</joint>
<link name="base"/>
<joint name="base_link-base" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
</robot>

0 comments on commit fa39cbf

Please sign in to comment.