Removed some hgardcoded paths and stray files

This commit is contained in:
Bastian Hofmann
2023-03-21 13:04:16 +00:00
parent b682211369
commit 7193070220
5 changed files with 18 additions and 418 deletions

View File

@@ -10,7 +10,7 @@ import xacro
def generate_launch_description():
moveit_config = MoveItConfigsBuilder("iisy", package_name="iisy_config").to_moveit_configs()
load_joint_state_broadcaster = ExecuteProcess(
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'joint_state_broadcaster'],
output='screen'
@@ -35,7 +35,7 @@ def generate_launch_description():
return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('ros_gz_sim'), 'launch', 'gz_sim.launch.py')),
launch_arguments={'gz_args': '-v 4 -r /home/ros/workspace/src/ign_world/world/gaz_new_test.sdf'}.items(),
launch_arguments={'gz_args': '-v 4 -r '+get_package_share_directory('ign_world')+'/world/gaz_new_test.sdf'}.items(),
),
Node(

View File

@@ -217,7 +217,7 @@ def generate_launch_description():
#IncludeLaunchDescription(
# PythonLaunchDescriptionSource(os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py')),
# launch_arguments={'gz_args': '-r /home/ros/workspace/src/ign_world/world/gaz_new_test.sdf'}.items(),
# launch_arguments={'gz_args': '-r '+get_package_share_directory('ign_world')+'/world/gaz_new_test.sdf'}.items(),
#),
Node(

View File

@@ -15,7 +15,7 @@ def generate_launch_description():
IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(get_package_share_directory('ros_gz_sim'), 'launch', 'gz_sim.launch.py')),
launch_arguments={'gz_args': '-v 4 -r /home/ros/workspace/src/ign_world/world/gaz_new_test.sdf'}.items(),
launch_arguments={'gz_args': '-v 4 -r '+get_package_share_directory('ign_world')+'/world/gaz_new_test.sdf'}.items(),
),
Node(

View File

@@ -9,24 +9,24 @@
<link name="table">
<collision>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/table.stl"/>
<mesh filename="$(find iisy_config)/stl/table.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/table.stl"/>
<mesh filename="$(find iisy_config)/stl/table.stl"/>
</geometry>
</visual>
</link>
<link name="base_bottom">
<collision>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/base_bottom_coll.stl"/>
<mesh filename="$(find iisy_config)/stl/base_bottom_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/base_bottom_low.stl"/>
<mesh filename="$(find iisy_config)/stl/base_bottom_low.stl"/>
</geometry>
</visual>
<inertial>
@@ -44,7 +44,7 @@
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/base_top_low.stl"/>
<mesh filename="$(find iisy_config)/stl/base_top_low.stl"/>
</geometry>
</visual>
<inertial>
@@ -56,12 +56,12 @@
<link name="link1_full">
<collision>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_1_full_coll.stl"/>
<mesh filename="$(find iisy_config)/stl/link_1_full_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_1_full_low.stl"/>
<mesh filename="$(find iisy_config)/stl/link_1_full_low.stl"/>
</geometry>
</visual>
<inertial>
@@ -79,7 +79,7 @@
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_2_bottom_low.stl"/>
<mesh filename="$(find iisy_config)/stl/link_2_bottom_low.stl"/>
</geometry>
</visual>
<inertial>
@@ -91,12 +91,12 @@
<link name="link2_top">
<collision>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_2_top_coll.stl"/>
<mesh filename="$(find iisy_config)/stl/link_2_top_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_2_top_low.stl"/>
<mesh filename="$(find iisy_config)/stl/link_2_top_low.stl"/>
</geometry>
</visual>
<inertial>
@@ -108,12 +108,12 @@
<link name="link3_bottom">
<collision>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_3_bottom_coll.stl"/>
<mesh filename="$(find iisy_config)/stl/link_3_bottom_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_3_bottom_low.stl"/>
<mesh filename="$(find iisy_config)/stl/link_3_bottom_low.stl"/>
</geometry>
</visual>
<inertial>
@@ -125,12 +125,12 @@
<link name="link3_top">
<collision>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_3_top_coll.stl"/>
<mesh filename="$(find iisy_config)/stl/link_3_top_coll.stl"/>
</geometry>
</collision>
<visual>
<geometry>
<mesh filename="file:///home/ros/workspace/install/iisy_config/share/iisy_config/stl/link_3_top_low.stl"/>
<mesh filename="$(find iisy_config)/stl/link_3_top_low.stl"/>
</geometry>
</visual>
<inertial>