Skip to content
This repository has been archived by the owner on Dec 13, 2024. It is now read-only.

Commit

Permalink
Clean up config and launch files to reduce duplication (#32)
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass authored Jun 9, 2023
1 parent 4dc6581 commit 532de41
Show file tree
Hide file tree
Showing 7 changed files with 8 additions and 236 deletions.
20 changes: 7 additions & 13 deletions src/picknik_ur_base_config/config/base_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -38,29 +38,23 @@ hardware:
ip: "!!! Please set the IP address of the robot"

# Specify additional launch files for running the robot with real hardware.
# [Required]
# [Optional, defaults to a blank launch file if not specified]
robot_driver_persist_launch_file:
package: "picknik_ur_base_config"
path: "launch/robot_drivers_to_persist.launch.py"
robot_driver_restart_launch_file:
package: "picknik_ur_base_config"
path: "launch/robot_drivers_to_restart.launch.py"
hardware_launch_file:
package: "picknik_ur_base_config"
path: "launch/hardware.launch.py"
package: "moveit_studio_agent"
path: "launch/blank.launch.py"

# Specify any additional launch files for running the robot in simulation mode.
# Used when simulated is True.
# [Required]
# Used when hardware.simulated is True.
# [Optional, defaults to a blank launch file if not specified]
simulated_robot_driver_persist_launch_file:
package: "picknik_ur_base_config"
path: "launch/sim/robot_drivers_to_persist_sim.launch.py"
simulated_robot_driver_restart_launch_file:
package: "picknik_ur_base_config"
path: "launch/sim/robot_drivers_to_restart_sim.launch.py"
simulated_hardware_launch_file:
package: "picknik_ur_base_config"
path: "launch/sim/hardware_sim.launch.py"
package: "moveit_studio_agent"
path: "launch/blank.launch.py"

# Configuration details for cameras and scene planning.
# [Required]
Expand Down
67 changes: 0 additions & 67 deletions src/picknik_ur_base_config/launch/hardware.launch.py

This file was deleted.

This file was deleted.

69 changes: 0 additions & 69 deletions src/picknik_ur_base_config/launch/sim/hardware_sim.launch.py

This file was deleted.

This file was deleted.

1 change: 1 addition & 0 deletions src/picknik_ur_base_config/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>moveit_ros_perception</exec_depend>
<exec_depend>moveit_studio_agent</exec_depend>
<exec_depend>moveit_studio_behavior</exec_depend>
<exec_depend>moveit_studio_ur_pstop_manager</exec_depend>
<exec_depend>pick_ik</exec_depend>
Expand Down
19 changes: 0 additions & 19 deletions src/picknik_ur_gazebo_config/launch/sim/hardware_sim.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
xacro_to_urdf,
)
from moveit_studio_utils_py.system_config import get_config_folder, SystemConfigParser
from moveit_studio_utils_py.generate_camera_frames import generate_camera_frames


def path_pattern_change_for_ignition(urdf_string):
Expand Down Expand Up @@ -99,7 +98,6 @@ def generate_simulation_description(context, *args, **settings):
def generate_launch_description():
system_config_parser = SystemConfigParser()
optional_feature_setting = system_config_parser.get_optional_feature_configs()
cameras_config = system_config_parser.get_cameras_config()

# The path to the auto_created urdf files
robot_urdf = system_config_parser.get_processed_urdf()
Expand Down Expand Up @@ -257,22 +255,6 @@ def generate_launch_description():
output="both",
)

frame_pair_params = [
{
"world_frame": "world",
"camera_frames": generate_camera_frames(cameras_config),
}
]

camera_transforms_node = Node(
package="moveit_studio_agent",
executable="camera_transforms_node",
name="camera_transforms_node",
output="both",
parameters=frame_pair_params,
arguments=["--ros-args"],
)

#####################
# Environment Scene #
#####################
Expand Down Expand Up @@ -311,6 +293,5 @@ def generate_launch_description():
gazebo,
spawn_robot,
spawn_scene,
camera_transforms_node,
]
)

0 comments on commit 532de41

Please sign in to comment.