Skip to content

Commit

Permalink
[URDF] Adding inertial and using find for getting package paths for…
Browse files Browse the repository at this point in the history
… simulators to work (#13)

Co-authored-by: Dr. Denis <[email protected]>
  • Loading branch information
Robotgir and destogl authored Mar 3, 2023
1 parent 672c7a6 commit bfbfaaf
Show file tree
Hide file tree
Showing 15 changed files with 298 additions and 206 deletions.
38 changes: 23 additions & 15 deletions kuka_kr10_support/urdf/kr10r1100sixx_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,110 +1,118 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find kuka_resources)/urdf/common_materials.xacro"/>
<xacro:include filename="$(find kuka_resources)/urdf/common_properties.xacro"/>

<xacro:macro name="kuka_kr10r1100sixx" params="prefix">
<xacro:include filename="$(find kuka_resources)/urdf/common_materials.xacro"/>
<link name="${prefix}base_link">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/visual/base_link.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/visual/base_link.stl" />
</geometry>
<xacro:material_kuka_black />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/collision/base_link.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/collision/base_link.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_1">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/visual/link_1.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/visual/link_1.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/collision/link_1.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/collision/link_1.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_2">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/visual/link_2.stl"/>
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/visual/link_2.stl"/>
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/collision/link_2.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/collision/link_2.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_3">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/visual/link_3.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/visual/link_3.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/collision/link_3.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/collision/link_3.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_4">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/visual/link_4.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/visual/link_4.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/collision/link_4.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/collision/link_4.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_5">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/visual/link_5.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/visual/link_5.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/collision/link_5.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/collision/link_5.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_6">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/visual/link_6.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/visual/link_6.stl" />
</geometry>
<xacro:material_kuka_pedestal />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1100sixx/collision/link_6.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1100sixx/collision/link_6.stl" />
</geometry>
</collision>
</link>
Expand Down
38 changes: 23 additions & 15 deletions kuka_kr10_support/urdf/kr10r1420_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,110 +1,118 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="$(find kuka_resources)/urdf/common_materials.xacro"/>
<xacro:include filename="$(find kuka_resources)/urdf/common_properties.xacro"/>

<xacro:macro name="kuka_kr10r1420" params="prefix">
<xacro:include filename="$(find kuka_resources)/urdf/common_materials.xacro"/>
<link name="${prefix}base_link">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/visual/base_link.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/visual/base_link.stl" />
</geometry>
<xacro:material_kuka_black />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/collision/base_link.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/collision/base_link.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_1">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/visual/link_1.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/visual/link_1.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/collision/link_1.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/collision/link_1.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_2">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/visual/link_2.stl"/>
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/visual/link_2.stl"/>
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/collision/link_2.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/collision/link_2.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_3">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/visual/link_3.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/visual/link_3.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/collision/link_3.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/collision/link_3.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_4">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/visual/link_4.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/visual/link_4.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/collision/link_4.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/collision/link_4.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_5">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/visual/link_5.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/visual/link_5.stl" />
</geometry>
<xacro:material_kuka_orange />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/collision/link_5.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/collision/link_5.stl" />
</geometry>
</collision>
</link>
<link name="${prefix}link_6">
<xacro:default_inertial/>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/visual/link_6.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/visual/link_6.stl" />
</geometry>
<xacro:material_kuka_pedestal />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://kuka_kr10_support/meshes/kr10r1420/collision/link_6.stl" />
<mesh filename="file://$(find kuka_kr10_support)/meshes/kr10r1420/collision/link_6.stl" />
</geometry>
</collision>
</link>
Expand Down
Loading

0 comments on commit bfbfaaf

Please sign in to comment.