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
This commit is contained in:
Ilya Uraev 2024-11-12 22:23:12 +03:00
parent a7b7225dd1
commit ea4ae0ed69
13 changed files with 279 additions and 880 deletions

View file

@ -14,6 +14,10 @@ from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from robot_builder.parser.urdf import URDF_parser
from robot_builder.external.ros2_control import ControllerManager
import yaml
def launch_setup(context, *args, **kwargs):
# Initialize Arguments
@ -29,29 +33,70 @@ def launch_setup(context, *args, **kwargs):
use_sim_time = LaunchConfiguration("use_sim_time")
hardware = LaunchConfiguration("hardware")
gripper_name = LaunchConfiguration("gripper_name")
scene_config_file = LaunchConfiguration("scene_config_file").perform(context)
initial_joint_controllers_file_path = os.path.join(
get_package_share_directory("rbs_arm"), "config", "rbs_arm0_controllers.yaml"
ee_link_name = LaunchConfiguration("ee_link_name").perform(context)
base_link_name = LaunchConfiguration("base_link_name").perform(context)
if not scene_config_file == "":
config_file = {"config_file": scene_config_file}
else:
config_file = {}
description_package_abs_path = get_package_share_directory(description_package.perform(context))
simulation_controllers = os.path.join(
description_package_abs_path, "config", "controllers.yaml"
)
xacro_file = os.path.join(
get_package_share_directory(description_package.perform(context)),
description_package_abs_path,
"urdf",
description_file.perform(context),
)
robot_description_doc = xacro.process_file(
xacro_file,
mappings={
"gripper_name": gripper_name.perform(context),
"hardware": hardware.perform(context),
"simulation_controllers": initial_joint_controllers_file_path,
"namespace": "",
},
)
xacro_config_file = f"{description_package_abs_path}/config/xacro_args.yaml"
# TODO: hide this to another place
# Load xacro_args
def param_constructor(loader, node, local_vars):
value = loader.construct_scalar(node)
return LaunchConfiguration(value).perform(
local_vars.get("context", "Launch context if not defined")
)
def variable_constructor(loader, node, local_vars):
value = loader.construct_scalar(node)
return local_vars.get(value, f"Variable '{value}' not found")
def load_xacro_args(yaml_file, local_vars):
# Get valut from ros2 argument
yaml.add_constructor(
"!param", lambda loader, node: param_constructor(loader, node, local_vars)
)
# Get value from local variable in this code
# The local variable should be initialized before the loader was called
yaml.add_constructor(
"!variable",
lambda loader, node: variable_constructor(loader, node, local_vars),
)
with open(yaml_file, "r") as file:
return yaml.load(file, Loader=yaml.FullLoader)
mappings_data = load_xacro_args(xacro_config_file, locals())
robot_description_doc = xacro.process_file(xacro_file, mappings=mappings_data)
robot_description_content = robot_description_doc.toprettyxml(indent=" ")
robot_description = {"robot_description": robot_description_content}
# Parse robot and configure controller's file for ControllerManager
robot = URDF_parser.load_string(robot_description_content, ee_link_name="gripper_grasp_point")
ControllerManager.save_to_yaml(
robot, description_package_abs_path, "controllers.yaml"
)
rbs_robot_setup = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
@ -64,7 +109,7 @@ def launch_setup(context, *args, **kwargs):
launch_arguments={
"with_gripper": with_gripper_condition,
"gripper_name": gripper_name,
"controllers_file": initial_joint_controllers_file_path,
"controllers_file": simulation_controllers,
"robot_type": robot_type,
"description_package": description_package,
"description_file": description_file,
@ -76,13 +121,15 @@ def launch_setup(context, *args, **kwargs):
"hardware": hardware,
"use_controllers": "true",
"robot_description": robot_description_content,
"base_link_name": base_link_name,
"ee_link_name": ee_link_name
}.items(),
)
rbs_runtime = Node(
package="rbs_runtime",
executable="runtime",
parameters=[robot_description, {"use_sim_time": True}],
parameters=[robot_description, config_file, {"use_sim_time": True}],
)
clock_bridge = Node(
@ -109,13 +156,13 @@ def generate_launch_description():
)
)
# General arguments
declared_arguments.append(
DeclareLaunchArgument(
"controllers_file",
default_value="rbs_arm0_controllers.yaml",
description="YAML file with the controllers configuration.",
)
)
# declared_arguments.append(
# DeclareLaunchArgument(
# "controllers_file",
# default_value="controllers.yaml",
# description="YAML file with the controllers configuration.",
# )
# )
declared_arguments.append(
DeclareLaunchArgument(
"description_package",
@ -199,6 +246,27 @@ def generate_launch_description():
description="Launch controllers?",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"scene_config_file",
default_value="",
description="Path to a scene configuration file",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"ee_link_name",
default_value="",
description="End effector name of robot arm",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"base_link_name",
default_value="",
description="Base link name if robot arm",
)
)
return LaunchDescription(
declared_arguments + [OpaqueFunction(function=launch_setup)]