runtime/env_manager/rbs_gym/launch/optimize.launch.py
Bill Finger ea4ae0ed69 feat(rbs): refactor controller paths and launch configuration
- Rename default controllers file `rbs_arm0_controllers.yaml` to `controllers.yaml` across all launch files
- Enhance `runtime.launch.py` by adding imports (`URDF_parser`, `ControllerManager`, `yaml`) and new arguments (`scene_config_file`, `ee_link_name`, `base_link_name`)
  - Implement xacro argument loading via YAML
  - Configure `robot_builder` to save controllers to `controllers.yaml` based on URDF parsing
- Add `control.launch.py` in `rbs_bringup` for dynamic controller spawning based on strategies/configurations
- Add `rbs_bringup.launch.py` as a unified entry point for single robot setup, initializing core settings like gripper, robot type, and controllers
- Remove `launch_env.launch.py`
- Remove `multi_robot.launch.py`
- Enhance `rbs_robot.launch.py` with `ee_link_name` and `base_link_name` arguments for end-effector and base link customization
- Add `ee_link_name` and `base_link_name` to `skills.launch.py` for flexible robot setup in skills
- Update `mtp_jtc_cart.cpp` with `base_link` and `robot_ee_link` parameters for KDL chain retrieval
- Remove `single_robot.launch.py` for simplified single robot deployment
2024-11-12 22:23:12 +03:00

519 lines
18 KiB
Python

from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
IncludeLaunchDescription,
OpaqueFunction,
TimerAction
)
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from launch_ros.actions import Node
import os
from os import cpu_count
from ament_index_python.packages import get_package_share_directory
def launch_setup(context, *args, **kwargs):
# Initialize Arguments
robot_type = LaunchConfiguration("robot_type")
# General arguments
with_gripper_condition = LaunchConfiguration("with_gripper")
controllers_file = LaunchConfiguration("controllers_file")
cartesian_controllers = LaunchConfiguration("cartesian_controllers")
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
robot_name = LaunchConfiguration("robot_name")
start_joint_controller = LaunchConfiguration("start_joint_controller")
initial_joint_controller = LaunchConfiguration("initial_joint_controller")
launch_simulation = LaunchConfiguration("launch_sim")
launch_moveit = LaunchConfiguration("launch_moveit")
launch_task_planner = LaunchConfiguration("launch_task_planner")
launch_perception = LaunchConfiguration("launch_perception")
moveit_config_package = LaunchConfiguration("moveit_config_package")
moveit_config_file = LaunchConfiguration("moveit_config_file")
use_sim_time = LaunchConfiguration("use_sim_time")
sim_gazebo = LaunchConfiguration("sim_gazebo")
hardware = LaunchConfiguration("hardware")
env_manager = LaunchConfiguration("env_manager")
launch_controllers = LaunchConfiguration("launch_controllers")
gripper_name = LaunchConfiguration("gripper_name")
# training arguments
env = LaunchConfiguration("env")
env_kwargs = LaunchConfiguration("env_kwargs")
algo = LaunchConfiguration("algo")
hyperparams = LaunchConfiguration("hyperparams")
n_timesteps = LaunchConfiguration("n_timesteps")
num_threads = LaunchConfiguration("num_threads")
seed = LaunchConfiguration("seed")
preload_replay_buffer = LaunchConfiguration("preload_replay_buffer")
log_folder = LaunchConfiguration("log_folder")
tensorboard_log = LaunchConfiguration("tensorboard_log")
log_interval = LaunchConfiguration("log_interval")
uuid = LaunchConfiguration("uuid")
eval_episodes = LaunchConfiguration("eval_episodes")
verbose = LaunchConfiguration("verbose")
truncate_last_trajectory = LaunchConfiguration("truncate_last_trajectory")
use_sim_time = LaunchConfiguration("use_sim_time")
log_level = LaunchConfiguration("log_level")
sampler = LaunchConfiguration("sampler")
pruner = LaunchConfiguration("pruner")
n_trials = LaunchConfiguration("n_trials")
n_startup_trials = LaunchConfiguration("n_startup_trials")
n_evaluations = LaunchConfiguration("n_evaluations")
n_jobs = LaunchConfiguration("n_jobs")
storage = LaunchConfiguration("storage")
study_name = LaunchConfiguration("study_name")
sim_gazebo = LaunchConfiguration("sim_gazebo")
launch_simulation = LaunchConfiguration("launch_sim")
initial_joint_controllers_file_path = os.path.join(
get_package_share_directory('rbs_arm'), 'config', 'controllers.yaml'
)
single_robot_setup = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
PathJoinSubstitution([
FindPackageShare('rbs_bringup'),
"launch",
"rbs_robot.launch.py"
])
]),
launch_arguments={
"env_manager": env_manager,
"with_gripper": with_gripper_condition,
"gripper_name": gripper_name,
"controllers_file": controllers_file,
"robot_type": robot_type,
"controllers_file": initial_joint_controllers_file_path,
"cartesian_controllers": cartesian_controllers,
"description_package": description_package,
"description_file": description_file,
"robot_name": robot_name,
"start_joint_controller": start_joint_controller,
"initial_joint_controller": initial_joint_controller,
"launch_simulation": launch_simulation,
"launch_moveit": launch_moveit,
"launch_task_planner": launch_task_planner,
"launch_perception": launch_perception,
"moveit_config_package": moveit_config_package,
"moveit_config_file": moveit_config_file,
"use_sim_time": use_sim_time,
"sim_gazebo": sim_gazebo,
"hardware": hardware,
"launch_controllers": launch_controllers,
# "gazebo_gui": gazebo_gui
}.items()
)
args = [
"--env",
env,
"--env-kwargs",
env_kwargs,
"--algo",
algo,
"--seed",
seed,
"--num-threads",
num_threads,
"--n-timesteps",
n_timesteps,
"--preload-replay-buffer",
preload_replay_buffer,
"--log-folder",
log_folder,
"--tensorboard-log",
tensorboard_log,
"--log-interval",
log_interval,
"--uuid",
uuid,
"--optimize-hyperparameters",
"True",
"--sampler",
sampler,
"--pruner",
pruner,
"--n-trials",
n_trials,
"--n-startup-trials",
n_startup_trials,
"--n-evaluations",
n_evaluations,
"--n-jobs",
n_jobs,
"--storage",
storage,
"--study-name",
study_name,
"--eval-episodes",
eval_episodes,
"--verbose",
verbose,
"--truncate-last-trajectory",
truncate_last_trajectory,
"--ros-args",
"--log-level",
log_level,
]
rl_task = Node(
package="rbs_gym",
executable="train",
output="log",
arguments = args,
parameters=[{"use_sim_time": True}]
)
delay_robot_control_stack = TimerAction(
period=10.0,
actions=[single_robot_setup]
)
nodes_to_start = [
rl_task,
delay_robot_control_stack
]
return nodes_to_start
def generate_launch_description():
declared_arguments = []
declared_arguments.append(
DeclareLaunchArgument(
"robot_type",
description="Type of robot by name",
choices=["rbs_arm","ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"],
default_value="rbs_arm",
)
)
# General arguments
declared_arguments.append(
DeclareLaunchArgument(
"controllers_file",
default_value="controllers_gazebosim.yaml",
description="YAML file with the controllers configuration.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_package",
default_value="rbs_arm",
description="Description package with robot URDF/XACRO files. Usually the argument \
is not set, it enables use of a custom description.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"description_file",
default_value="rbs_arm_modular.xacro",
description="URDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"robot_name",
default_value="arm0",
description="Name for robot, used to apply namespace for specific robot in multirobot setup",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"start_joint_controller",
default_value="false",
description="Enable headless mode for robot control",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"initial_joint_controller",
default_value="joint_trajectory_controller",
description="Robot controller to start.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"moveit_config_package",
default_value="rbs_arm",
description="MoveIt config package with robot SRDF/XACRO files. Usually the argument \
is not set, it enables use of a custom moveit config.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"moveit_config_file",
default_value="rbs_arm.srdf.xacro",
description="MoveIt SRDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"use_sim_time",
default_value="true",
description="Make MoveIt to use simulation time.\
This is needed for the trajectory planing in simulation.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"gripper_name",
default_value="rbs_gripper",
choices=["rbs_gripper", ""],
description="choose gripper by name (leave empty if hasn't)",
)
)
declared_arguments.append(
DeclareLaunchArgument("with_gripper",
default_value="true",
description="With gripper or not?")
)
declared_arguments.append(
DeclareLaunchArgument("sim_gazebo",
default_value="true",
description="Gazebo Simulation")
)
declared_arguments.append(
DeclareLaunchArgument("env_manager",
default_value="false",
description="Launch env_manager?")
)
declared_arguments.append(
DeclareLaunchArgument("launch_sim",
default_value="true",
description="Launch simulator (Gazebo)?\
Most general arg")
)
declared_arguments.append(
DeclareLaunchArgument("launch_moveit",
default_value="false",
description="Launch moveit?")
)
declared_arguments.append(
DeclareLaunchArgument("launch_perception",
default_value="false",
description="Launch perception?")
)
declared_arguments.append(
DeclareLaunchArgument("launch_task_planner",
default_value="false",
description="Launch task_planner?")
)
declared_arguments.append(
DeclareLaunchArgument("cartesian_controllers",
default_value="true",
description="Load cartesian\
controllers?")
)
declared_arguments.append(
DeclareLaunchArgument("hardware",
choices=["gazebo", "mock"],
default_value="gazebo",
description="Choose your harware_interface")
)
declared_arguments.append(
DeclareLaunchArgument("launch_controllers",
default_value="true",
description="Launch controllers?")
)
declared_arguments.append(
DeclareLaunchArgument("gazebo_gui",
default_value="true",
description="Launch gazebo with gui?")
)
# training arguments
declared_arguments.append(
DeclareLaunchArgument(
"env",
default_value="Reach-Gazebo-v0",
description="Environment ID",
))
declared_arguments.append(
DeclareLaunchArgument(
"env_kwargs",
default_value="",
description="Optional keyword argument to pass to the env constructor.",
))
declared_arguments.append(
DeclareLaunchArgument(
"vec_env",
default_value="dummy",
description="Type of VecEnv to use (dummy or subproc).",
))
# Algorithm and training
declared_arguments.append(
DeclareLaunchArgument(
"algo",
default_value="sac",
description="RL algorithm to use during the training.",
))
declared_arguments.append(
DeclareLaunchArgument(
"n_timesteps",
default_value="-1",
description="Overwrite the number of timesteps.",
))
declared_arguments.append(
DeclareLaunchArgument(
"hyperparams",
default_value="",
description="Optional RL hyperparameter overwrite (e.g. learning_rate:0.01 train_freq:10).",
))
declared_arguments.append(
DeclareLaunchArgument(
"num_threads",
default_value="-1",
description="Number of threads for PyTorch (-1 to use default).",
))
# Continue training an already trained agent
declared_arguments.append(
DeclareLaunchArgument(
"trained_agent",
default_value="",
description="Path to a pretrained agent to continue training.",
))
# Random seed
declared_arguments.append(
DeclareLaunchArgument(
"seed",
default_value="84",
description="Random generator seed.",
))
# Saving of model
declared_arguments.append(
DeclareLaunchArgument(
"save_freq",
default_value="10000",
description="Save the model every n steps (if negative, no checkpoint).",
))
declared_arguments.append(
DeclareLaunchArgument(
"save_replay_buffer",
default_value="False",
description="Save the replay buffer too (when applicable).",
))
# Pre-load a replay buffer and start training on it
declared_arguments.append(
DeclareLaunchArgument(
"preload_replay_buffer",
default_value="",
description="Path to a replay buffer that should be preloaded before starting the training process.",
))
# Logging
declared_arguments.append(
DeclareLaunchArgument(
"log_folder",
default_value="logs",
description="Path to the log directory.",
))
declared_arguments.append(
DeclareLaunchArgument(
"tensorboard_log",
default_value="tensorboard_logs",
description="Tensorboard log dir.",
))
declared_arguments.append(
DeclareLaunchArgument(
"log_interval",
default_value="-1",
description="Override log interval (default: -1, no change).",
))
declared_arguments.append(
DeclareLaunchArgument(
"uuid",
default_value="False",
description="Ensure that the run has a unique ID.",
))
declared_arguments.append(
DeclareLaunchArgument(
"sampler",
default_value="tpe",
description="Sampler to use when optimizing hyperparameters (random, tpe or skopt).",
))
declared_arguments.append(
DeclareLaunchArgument(
"pruner",
default_value="median",
description="Pruner to use when optimizing hyperparameters (halving, median or none).",
))
declared_arguments.append(
DeclareLaunchArgument(
"n_trials",
default_value="10",
description="Number of trials for optimizing hyperparameters.",
))
declared_arguments.append(
DeclareLaunchArgument(
"n_startup_trials",
default_value="5",
description="Number of trials before using optuna sampler.",
))
declared_arguments.append(
DeclareLaunchArgument(
"n_evaluations",
default_value="2",
description="Number of evaluations for hyperparameter optimization.",
))
declared_arguments.append(
DeclareLaunchArgument(
"n_jobs",
default_value="1",
description="Number of parallel jobs when optimizing hyperparameters.",
))
declared_arguments.append(
DeclareLaunchArgument(
"storage",
default_value="",
description="Database storage path if distributed optimization should be used.",
))
declared_arguments.append(
DeclareLaunchArgument(
"study_name",
default_value="",
description="Study name for distributed optimization.",
))
# Evaluation
declared_arguments.append(
DeclareLaunchArgument(
"eval_freq",
default_value="-1",
description="Evaluate the agent every n steps (if negative, no evaluation).",
))
declared_arguments.append(
DeclareLaunchArgument(
"eval_episodes",
default_value="5",
description="Number of episodes to use for evaluation.",
))
# Verbosity
declared_arguments.append(
DeclareLaunchArgument(
"verbose",
default_value="1",
description="Verbose mode (0: no output, 1: INFO).",
))
# HER specifics
declared_arguments.append(
DeclareLaunchArgument(
"truncate_last_trajectory",
default_value="True",
description="When using HER with online sampling the last trajectory in the replay buffer will be truncated after) reloading the replay buffer."
)),
declared_arguments.append(
DeclareLaunchArgument(
"log_level",
default_value="error",
description="The level of logging that is applied to all ROS 2 nodes launched by this script.",
))
# env_variables = [
# SetEnvironmentVariable(name="OMP_DYNAMIC", value="TRUE"),
# SetEnvironmentVariable(name="OMP_NUM_THREADS", value=str(cpu_count() // 2))
# ]
return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])