Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add env hook for Gazebo paths #47

Merged
merged 2 commits into from
Aug 26, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions iiwa_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,4 +32,6 @@ install(
DESTINATION share/${PROJECT_NAME}
)

ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/${PROJECT_NAME}.sh.in")

ament_package()
7 changes: 7 additions & 0 deletions iiwa_description/env-hooks/iiwa_description.sh.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# Gazebo classic
ament_prepend_unique_value GAZEBO_MODEL_PATH "$COLCON_CURRENT_PREFIX/share/@PROJECT_NAME@/meshes"
ament_prepend_unique_value GAZEBO_RESOURCE_PATH "$COLCON_CURRENT_PREFIX/share/@PROJECT_NAME@/meshes"

# Gazebo ignition and forward
ament_prepend_unique_value IGN_GAZEBO_RESOURCE_PATH "$COLCON_CURRENT_PREFIX/share/@PROJECT_NAME@/meshes"
ament_prepend_unique_value GZ_SIM_RESOURCE_PATH "$COLCON_CURRENT_PREFIX/share/@PROJECT_NAME@/meshes"
32 changes: 16 additions & 16 deletions iiwa_description/urdf/iiwa.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,13 @@
<visual>
<origin rpy="0.0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/base_link.dae"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/base_link.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/base_link.stl"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/base_link.stl"/>
</geometry>
</collision>
<inertial>
Expand All @@ -44,13 +44,13 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/link_1.dae"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/link_1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/link_1.stl"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/link_1.stl"/>
</geometry>
</collision>
<inertial>
Expand All @@ -63,13 +63,13 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/link_2.dae"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/link_2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/link_2.stl"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/link_2.stl"/>
</geometry>
</collision>
<inertial>
Expand All @@ -82,13 +82,13 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/link_3.dae"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/link_3.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/link_3.stl"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/link_3.stl"/>
</geometry>
</collision>
<inertial>
Expand All @@ -101,13 +101,13 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/link_4.dae"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/link_4.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/link_4.stl"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/link_4.stl"/>
</geometry>
</collision>
<inertial>
Expand All @@ -120,13 +120,13 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/link_5.dae"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/link_5.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/link_5.stl"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/link_5.stl"/>
</geometry>
</collision>
<inertial>
Expand All @@ -139,13 +139,13 @@
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/link_6.dae"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/link_6.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/link_6.stl"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/link_6.stl"/>
</geometry>
</collision>
<inertial>
Expand All @@ -159,13 +159,13 @@
<origin rpy="0 0 0" xyz="0 0 0.07"/>
<material name="gray"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/visual/link_7_2.stl" scale ="0.001 0.001 0.001"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/visual/link_7_2.stl" scale ="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.07"/>
<geometry>
<mesh filename="package://iiwa_description/meshes/lbr_iiwa_14_r820/collision/link_7_2.stl" scale ="0.001 0.001 0.001"/>
<mesh filename="file://$(find iiwa_description)/meshes/lbr_iiwa_14_r820/collision/link_7_2.stl" scale ="0.001 0.001 0.001"/>
</geometry>
</collision>
<inertial>
Expand Down
Loading