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

Fix rviz model paths #42

Merged
merged 3 commits into from
Nov 23, 2023
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
1 change: 1 addition & 0 deletions rosbot_xl_description/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,4 +9,5 @@ install(DIRECTORY
DESTINATION share/${PROJECT_NAME}
)

ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/env-hooks/${PROJECT_NAME}.sh.in")
ament_package()
3 changes: 3 additions & 0 deletions rosbot_xl_description/env-hooks/rosbot_xl_description.sh.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ament_prepend_unique_value GAZEBO_MODEL_PATH "@CMAKE_INSTALL_PREFIX@/share"
ament_prepend_unique_value GZ_SIM_RESOURCE_PATH "@CMAKE_INSTALL_PREFIX@/share"
ament_prepend_unique_value IGN_GAZEBO_RESOURCE_PATH "@CMAKE_INSTALL_PREFIX@/share"
4 changes: 2 additions & 2 deletions rosbot_xl_description/urdf/body.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,14 @@
<link name="body_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_xl_description)/meshes/body.dae" scale="1 1 1" />
<mesh filename="package://rosbot_xl_description/meshes/body.dae" scale="1 1 1" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</visual>

<collision>
<geometry>
<mesh filename="file://$(find rosbot_xl_description)/meshes/body_colision.stl" scale="1 1 1" />
<mesh filename="package://rosbot_xl_description/meshes/body_colision.stl" scale="1 1 1" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
Expand Down
4 changes: 2 additions & 2 deletions rosbot_xl_description/urdf/components/antenna.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
<link name="${tf_prefix_ext}antenna_connector_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_xl_description)/meshes/components/antenna_connector.dae"
<mesh filename="package://rosbot_xl_description/meshes/components/antenna_connector.dae"
scale="1 1 1" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
Expand All @@ -40,7 +40,7 @@
<link name="${tf_prefix_ext}antenna_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_xl_description)/meshes/components/antenna.dae"
<mesh filename="package://rosbot_xl_description/meshes/components/antenna.dae"
scale="1 1 1" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
Expand Down
6 changes: 3 additions & 3 deletions rosbot_xl_description/urdf/components/camera_mount.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
<link name="${tf_prefix_ext}camera_mount_bot_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_xl_description)/meshes/components/camera_mount_bot.dae"
<mesh filename="package://rosbot_xl_description/meshes/components/camera_mount_bot.dae"
scale="1 1 1" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
Expand All @@ -46,7 +46,7 @@
<link name="${tf_prefix_ext}camera_mount_mid_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_xl_description)/meshes/components/camera_mount_mid.dae"
<mesh filename="package://rosbot_xl_description/meshes/components/camera_mount_mid.dae"
scale="1 1 1" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
Expand All @@ -69,7 +69,7 @@
<link name="${tf_prefix_ext}camera_mount_top_link">
<visual>
<geometry>
<mesh filename="file://$(find rosbot_xl_description)/meshes/components/camera_mount_top.dae"
<mesh filename="package://rosbot_xl_description/meshes/components/camera_mount_top.dae"
scale="1 1 1" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
Expand Down
8 changes: 4 additions & 4 deletions rosbot_xl_description/urdf/wheel.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -31,28 +31,28 @@
<xacro:if value="${prefix == 'fl'}">
<xacro:property name="x" value="${wheel_separation_x/2}" />
<xacro:property name="y" value="${wheel_separation_y/2}" />
<xacro:property name="mesh" value="file://$(find rosbot_xl_description)/meshes/${wheel_file}_b.dae" />
<xacro:property name="mesh" value="package://rosbot_xl_description/meshes/${wheel_file}_b.dae" />
<xacro:property name="visual_rotation" value="${pi}" />
<xacro:property name="fdir" value="1 -1 0" />
</xacro:if>
<xacro:if value="${prefix == 'fr'}">
<xacro:property name="x" value="${wheel_separation_x/2}" />
<xacro:property name="y" value="${-wheel_separation_y/2}" />
<xacro:property name="mesh" value="file://$(find rosbot_xl_description)/meshes/${wheel_file}_a.dae" />
<xacro:property name="mesh" value="package://rosbot_xl_description/meshes/${wheel_file}_a.dae" />
<xacro:property name="visual_rotation" value="${pi}" />
<xacro:property name="fdir" value="1 1 0" />
</xacro:if>
<xacro:if value="${prefix == 'rl'}">
<xacro:property name="x" value="${-wheel_separation_x/2}" />
<xacro:property name="y" value="${wheel_separation_y/2}" />
<xacro:property name="mesh" value="file://$(find rosbot_xl_description)/meshes/${wheel_file}_a.dae" />
<xacro:property name="mesh" value="package://rosbot_xl_description/meshes/${wheel_file}_a.dae" />
<xacro:property name="visual_rotation" value="${0.0}" />
<xacro:property name="fdir" value="1 1 0" />
</xacro:if>
<xacro:if value="${prefix == 'rr'}">
<xacro:property name="x" value="${-wheel_separation_x/2}" />
<xacro:property name="y" value="${-wheel_separation_y/2}" />
<xacro:property name="mesh" value="file://$(find rosbot_xl_description)/meshes/${wheel_file}_b.dae" />
<xacro:property name="mesh" value="package://rosbot_xl_description/meshes/${wheel_file}_b.dae" />
<xacro:property name="visual_rotation" value="${0.0}" />
<xacro:property name="fdir" value="1 -1 0" />
</xacro:if>
Expand Down
Loading