refactor launch files for enhanced MoveIt integration and cleanup
- **RBS Bringup Launch File:** - Enabled MoveIt by default (`use_moveit: true`). - Removed unused arguments (`gripper_name`, `hardware`) for cleaner configuration. - Updated `robot_description_kinematics` to use the new kinematics file path handling. - **RBS Robot Launch File:** - Streamlined robot description setup, removing unnecessary parameters like `gripper_name`, `hardware`, and pose arguments (`x`, `y`, `z`, `roll`, etc.). - Updated robot description and semantic description to use launch configurations. - Refactored kinematics file handling for clarity. - **Skills Launch File:** - Updated kinematics YAML loading to use `load_yaml_abs` for absolute path resolution. - Standardized `robot_description`, `robot_description_semantic`, and `kinematics` parameters. - **General Improvements:** - Consolidated redundant logic across launch files. - Improved maintainability by removing hardcoded and unused configurations.
This commit is contained in:
parent
fbddca1b8b
commit
d0788041e9
3 changed files with 33 additions and 107 deletions
|
@ -21,16 +21,14 @@ def launch_setup(context, *args, **kwargs):
|
||||||
),
|
),
|
||||||
launch_arguments={
|
launch_arguments={
|
||||||
"with_gripper": "true",
|
"with_gripper": "true",
|
||||||
"gripper_name": "rbs_gripper",
|
|
||||||
"robot_type": "rbs_arm",
|
"robot_type": "rbs_arm",
|
||||||
"description_package": "rbs_arm",
|
"description_package": "rbs_arm",
|
||||||
"description_file": "rbs_arm_modular.xacro",
|
"description_file": "rbs_arm_modular.xacro",
|
||||||
"robot_name": "rbs_arm",
|
"robot_name": "rbs_arm",
|
||||||
"use_moveit": "false",
|
"use_moveit": "true",
|
||||||
"moveit_config_package": "rbs_arm",
|
"moveit_config_package": "rbs_arm",
|
||||||
"moveit_config_file": "rbs_arm.srdf.xacro",
|
"moveit_config_file": "rbs_arm.srdf.xacro",
|
||||||
"use_sim_time": "true",
|
"use_sim_time": "true",
|
||||||
"hardware": "gazebo",
|
|
||||||
"use_controllers": "true",
|
"use_controllers": "true",
|
||||||
"scene_config_file": "",
|
"scene_config_file": "",
|
||||||
"base_link_name": "base_link",
|
"base_link_name": "base_link",
|
||||||
|
|
|
@ -23,23 +23,13 @@ from launch_ros.substitutions import FindPackageShare
|
||||||
def launch_setup(context, *args, **kwargs):
|
def launch_setup(context, *args, **kwargs):
|
||||||
robot_type = LaunchConfiguration("robot_type")
|
robot_type = LaunchConfiguration("robot_type")
|
||||||
with_gripper_condition = LaunchConfiguration("with_gripper")
|
with_gripper_condition = LaunchConfiguration("with_gripper")
|
||||||
controllers_file = LaunchConfiguration("controllers_file")
|
|
||||||
description_package = LaunchConfiguration("description_package")
|
description_package = LaunchConfiguration("description_package")
|
||||||
description_file = LaunchConfiguration("description_file")
|
description_file = LaunchConfiguration("description_file")
|
||||||
robot_name = LaunchConfiguration("robot_name")
|
robot_name = LaunchConfiguration("robot_name")
|
||||||
use_moveit = LaunchConfiguration("use_moveit")
|
use_moveit = LaunchConfiguration("use_moveit")
|
||||||
moveit_config_package = LaunchConfiguration("moveit_config_package")
|
moveit_config_package = LaunchConfiguration("moveit_config_package")
|
||||||
moveit_config_file = LaunchConfiguration("moveit_config_file")
|
|
||||||
use_sim_time = LaunchConfiguration("use_sim_time")
|
use_sim_time = LaunchConfiguration("use_sim_time")
|
||||||
hardware = LaunchConfiguration("hardware")
|
|
||||||
use_controllers = LaunchConfiguration("use_controllers")
|
use_controllers = LaunchConfiguration("use_controllers")
|
||||||
gripper_name = LaunchConfiguration("gripper_name")
|
|
||||||
x_pos = LaunchConfiguration("x")
|
|
||||||
y_pos = LaunchConfiguration("y")
|
|
||||||
z_pos = LaunchConfiguration("z")
|
|
||||||
roll = LaunchConfiguration("roll")
|
|
||||||
pitch = LaunchConfiguration("pitch")
|
|
||||||
yaw = LaunchConfiguration("yaw")
|
|
||||||
namespace = LaunchConfiguration("namespace")
|
namespace = LaunchConfiguration("namespace")
|
||||||
multi_robot = LaunchConfiguration("multi_robot")
|
multi_robot = LaunchConfiguration("multi_robot")
|
||||||
robot_name = robot_name.perform(context)
|
robot_name = robot_name.perform(context)
|
||||||
|
@ -47,10 +37,11 @@ def launch_setup(context, *args, **kwargs):
|
||||||
robot_type = robot_type.perform(context)
|
robot_type = robot_type.perform(context)
|
||||||
description_package = description_package.perform(context)
|
description_package = description_package.perform(context)
|
||||||
description_file = description_file.perform(context)
|
description_file = description_file.perform(context)
|
||||||
controllers_file = controllers_file.perform(context)
|
|
||||||
multi_robot = multi_robot.perform(context)
|
multi_robot = multi_robot.perform(context)
|
||||||
robot_description = LaunchConfiguration("robot_description")
|
robot_description_content = LaunchConfiguration("robot_description")
|
||||||
robot_description_semantic = LaunchConfiguration("robot_description_semantic")
|
robot_description_semantic_content = LaunchConfiguration(
|
||||||
|
"robot_description_semantic"
|
||||||
|
)
|
||||||
control_space = LaunchConfiguration("control_space")
|
control_space = LaunchConfiguration("control_space")
|
||||||
control_strategy = LaunchConfiguration("control_strategy")
|
control_strategy = LaunchConfiguration("control_strategy")
|
||||||
ee_link_name = LaunchConfiguration("ee_link_name").perform(context)
|
ee_link_name = LaunchConfiguration("ee_link_name").perform(context)
|
||||||
|
@ -60,74 +51,19 @@ def launch_setup(context, *args, **kwargs):
|
||||||
if multi_robot == "true":
|
if multi_robot == "true":
|
||||||
remappings.append([("/tf", "tf"), ("/tf_static", "tf_static")])
|
remappings.append([("/tf", "tf"), ("/tf_static", "tf_static")])
|
||||||
|
|
||||||
controllers_file = os.path.join(
|
robot_description = {
|
||||||
get_package_share_directory(description_package), "config", controllers_file
|
"robot_description": robot_description_content.perform(context)
|
||||||
)
|
|
||||||
|
|
||||||
if not robot_description.perform(context):
|
|
||||||
xacro_file = os.path.join(
|
|
||||||
get_package_share_directory(description_package), "urdf", description_file
|
|
||||||
)
|
|
||||||
robot_description_doc = xacro.process_file(
|
|
||||||
xacro_file,
|
|
||||||
mappings={
|
|
||||||
"gripper_name": gripper_name.perform(context),
|
|
||||||
"hardware": hardware.perform(context),
|
|
||||||
"simulation_controllers": controllers_file,
|
|
||||||
"namespace": namespace,
|
|
||||||
"x": x_pos.perform(context),
|
|
||||||
"y": y_pos.perform(context),
|
|
||||||
"z": z_pos.perform(context),
|
|
||||||
"roll": roll.perform(context),
|
|
||||||
"pitch": pitch.perform(context),
|
|
||||||
"yaw": yaw.perform(context),
|
|
||||||
},
|
|
||||||
)
|
|
||||||
|
|
||||||
robot_description_content = robot_description_doc.toprettyxml(indent=" ")
|
|
||||||
else:
|
|
||||||
robot_description_content = robot_description.perform(context)
|
|
||||||
|
|
||||||
robot_description = {"robot_description": robot_description_content}
|
|
||||||
|
|
||||||
if not robot_description_semantic.perform(context):
|
|
||||||
robot_description_semantic_content = Command(
|
|
||||||
[
|
|
||||||
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
|
||||||
" ",
|
|
||||||
PathJoinSubstitution(
|
|
||||||
[
|
|
||||||
FindPackageShare(moveit_config_package),
|
|
||||||
"config/moveit",
|
|
||||||
"rbs_arm.srdf.xacro",
|
|
||||||
]
|
|
||||||
),
|
|
||||||
" ",
|
|
||||||
"name:=",
|
|
||||||
robot_type,
|
|
||||||
" ",
|
|
||||||
"with_gripper:=",
|
|
||||||
with_gripper_condition,
|
|
||||||
" ",
|
|
||||||
"gripper_name:=",
|
|
||||||
gripper_name,
|
|
||||||
" ",
|
|
||||||
]
|
|
||||||
)
|
|
||||||
else:
|
|
||||||
robot_description_semantic_content = robot_description_semantic
|
|
||||||
|
|
||||||
robot_description_semantic = {
|
|
||||||
"robot_description_semantic": robot_description_semantic_content
|
|
||||||
}
|
}
|
||||||
|
|
||||||
robot_description_kinematics = PathJoinSubstitution(
|
robot_description_kinematics_filepath = os.path.join(
|
||||||
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
|
get_package_share_directory(moveit_config_package.perform(context)),
|
||||||
|
"config",
|
||||||
|
"kinematics.yaml",
|
||||||
)
|
)
|
||||||
|
|
||||||
robot_description_kinematics = {
|
# robot_description_kinematics = {
|
||||||
"robot_description_kinematics": robot_description_kinematics
|
# "robot_description_kinematics": robot_description_kinematics
|
||||||
}
|
# }
|
||||||
|
|
||||||
robot_state_publisher = Node(
|
robot_state_publisher = Node(
|
||||||
package="robot_state_publisher",
|
package="robot_state_publisher",
|
||||||
|
@ -172,13 +108,14 @@ def launch_setup(context, *args, **kwargs):
|
||||||
]
|
]
|
||||||
),
|
),
|
||||||
launch_arguments={
|
launch_arguments={
|
||||||
"robot_description": robot_description_content,
|
|
||||||
"moveit_config_package": moveit_config_package,
|
"moveit_config_package": moveit_config_package,
|
||||||
"moveit_config_file": moveit_config_file,
|
# "moveit_config_file": moveit_config_file,
|
||||||
"use_sim_time": use_sim_time,
|
"use_sim_time": use_sim_time,
|
||||||
"tf_prefix": robot_name,
|
"tf_prefix": robot_name,
|
||||||
"with_gripper": with_gripper_condition,
|
"with_gripper": with_gripper_condition,
|
||||||
|
"robot_description": robot_description_content,
|
||||||
"robot_description_semantic": robot_description_semantic_content,
|
"robot_description_semantic": robot_description_semantic_content,
|
||||||
|
"robot_description_kinematics": robot_description_kinematics_filepath,
|
||||||
"namespace": namespace,
|
"namespace": namespace,
|
||||||
}.items(),
|
}.items(),
|
||||||
condition=IfCondition(use_moveit),
|
condition=IfCondition(use_moveit),
|
||||||
|
@ -199,7 +136,7 @@ def launch_setup(context, *args, **kwargs):
|
||||||
launch_arguments={
|
launch_arguments={
|
||||||
"robot_description": robot_description_content,
|
"robot_description": robot_description_content,
|
||||||
"robot_description_semantic": robot_description_semantic_content,
|
"robot_description_semantic": robot_description_semantic_content,
|
||||||
"robot_description_kinematics": robot_description_kinematics,
|
"robot_description_kinematics": robot_description_kinematics_filepath,
|
||||||
"use_sim_time": use_sim_time,
|
"use_sim_time": use_sim_time,
|
||||||
"with_gripper_condition": with_gripper_condition,
|
"with_gripper_condition": with_gripper_condition,
|
||||||
"namespace": namespace,
|
"namespace": namespace,
|
||||||
|
@ -288,14 +225,14 @@ def generate_launch_description():
|
||||||
description="Enables simulation time in MoveIt, needed for trajectory planning in simulation.",
|
description="Enables simulation time in MoveIt, needed for trajectory planning in simulation.",
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
declared_arguments.append(
|
# declared_arguments.append(
|
||||||
DeclareLaunchArgument(
|
# DeclareLaunchArgument(
|
||||||
"gripper_name",
|
# "gripper_name",
|
||||||
default_value="",
|
# default_value="",
|
||||||
choices=["rbs_gripper", ""],
|
# choices=["rbs_gripper", ""],
|
||||||
description="Specify gripper name (leave empty if none).",
|
# description="Specify gripper name (leave empty if none).",
|
||||||
)
|
# )
|
||||||
)
|
# )
|
||||||
declared_arguments.append(
|
declared_arguments.append(
|
||||||
DeclareLaunchArgument(
|
DeclareLaunchArgument(
|
||||||
"with_gripper",
|
"with_gripper",
|
||||||
|
@ -310,14 +247,6 @@ def generate_launch_description():
|
||||||
description="Specify if MoveIt should be launched.",
|
description="Specify if MoveIt should be launched.",
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
declared_arguments.append(
|
|
||||||
DeclareLaunchArgument(
|
|
||||||
"hardware",
|
|
||||||
choices=["gazebo", "mock"],
|
|
||||||
default_value="gazebo",
|
|
||||||
description="Specify the hardware interface to use (e.g., Gazebo or mock).",
|
|
||||||
)
|
|
||||||
)
|
|
||||||
declared_arguments.append(
|
declared_arguments.append(
|
||||||
DeclareLaunchArgument(
|
DeclareLaunchArgument(
|
||||||
"use_controllers",
|
"use_controllers",
|
||||||
|
|
|
@ -4,27 +4,26 @@ from launch.conditions import IfCondition
|
||||||
from launch.substitutions import LaunchConfiguration
|
from launch.substitutions import LaunchConfiguration
|
||||||
from launch_ros.actions import ComposableNodeContainer, Node
|
from launch_ros.actions import ComposableNodeContainer, Node
|
||||||
from launch_ros.actions.composable_node_container import ComposableNode
|
from launch_ros.actions.composable_node_container import ComposableNode
|
||||||
from rbs_launch_utils.launch_common import load_yaml
|
from rbs_launch_utils.launch_common import load_yaml, load_yaml_abs
|
||||||
|
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
def launch_setup(context, *args, **kwargs):
|
||||||
robot_description_decl = LaunchConfiguration("robot_description")
|
robot_description_content = LaunchConfiguration("robot_description")
|
||||||
robot_description_semantic_decl = LaunchConfiguration("robot_description_semantic")
|
robot_description_semantic_content = LaunchConfiguration("robot_description_semantic")
|
||||||
robot_description_kinematics = LaunchConfiguration("robot_description_kinematics")
|
robot_description_kinematics_filepath = LaunchConfiguration("robot_description_kinematics")
|
||||||
use_sim_time = LaunchConfiguration("use_sim_time")
|
use_sim_time = LaunchConfiguration("use_sim_time")
|
||||||
use_moveit = LaunchConfiguration("use_moveit")
|
use_moveit = LaunchConfiguration("use_moveit")
|
||||||
ee_link_name = LaunchConfiguration("ee_link_name").perform(context)
|
ee_link_name = LaunchConfiguration("ee_link_name").perform(context)
|
||||||
base_link_name = LaunchConfiguration("base_link_name").perform(context)
|
base_link_name = LaunchConfiguration("base_link_name").perform(context)
|
||||||
# with_gripper_condition = LaunchConfiguration("with_gripper_condition")
|
# with_gripper_condition = LaunchConfiguration("with_gripper_condition")
|
||||||
|
|
||||||
robot_description = {"robot_description": robot_description_decl}
|
robot_description = {"robot_description": robot_description_content}
|
||||||
robot_description_semantic = {
|
robot_description_semantic = {
|
||||||
"robot_description_semantic": robot_description_semantic_decl
|
"robot_description_semantic": robot_description_semantic_content
|
||||||
}
|
}
|
||||||
namespace = LaunchConfiguration("namespace")
|
namespace = LaunchConfiguration("namespace")
|
||||||
|
|
||||||
kinematics_yaml = load_yaml("rbs_arm", "config/kinematics.yaml")
|
kinematics_yaml = load_yaml_abs(robot_description_kinematics_filepath.perform(context))
|
||||||
|
|
||||||
robot_description_kinematics = {"robot_description_kinematics": kinematics_yaml}
|
robot_description_kinematics = {"robot_description_kinematics": kinematics_yaml}
|
||||||
|
|
||||||
skills_container = ComposableNodeContainer(
|
skills_container = ComposableNodeContainer(
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue