19from launch
import LaunchDescription
20from launch.actions
import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction
21from launch.launch_description_sources
import PythonLaunchDescriptionSource
22from launch.substitutions
import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
23from launch_ros.actions
import Node
24from launch_ros.substitutions
import FindPackageShare
28from ament_index_python.packages
import get_package_share_directory
34 """utility function to construct radian values from yaml."""
35 value = loader.construct_scalar(node)
39 raise Exception(
"invalid expression: %s" % value)
43 """utility function for converting degrees into radians from yaml."""
48 package_path = get_package_share_directory(package_name)
49 absolute_file_path = os.path.join(package_path, file_path)
52 yaml.SafeLoader.add_constructor(
"!radians", construct_angle_radians)
53 yaml.SafeLoader.add_constructor(
"!degrees", construct_angle_degrees)
55 raise Exception(
"yaml support not available; install python-yaml")
58 with open(absolute_file_path)
as file:
59 return yaml.safe_load(file)
72 runtime_config_package = LaunchConfiguration(
"runtime_config_package")
73 controllers_file = LaunchConfiguration(
"controllers_file")
74 description_package = LaunchConfiguration(
"description_package")
75 description_file = LaunchConfiguration(
"description_file")
76 moveit_config_package = LaunchConfiguration(
"moveit_config_package")
77 moveit_config_file = LaunchConfiguration(
"moveit_config_file")
78 prefix = LaunchConfiguration(
"prefix")
80 robot_description_content = Command(
82 PathJoinSubstitution([FindExecutable(name=
"xacro")]),
85 [FindPackageShare(description_package),
"urdf", description_file]
99 robot_description = {
"robot_description": robot_description_content}
102 robot_description_semantic_content = Command(
104 PathJoinSubstitution([FindExecutable(name=
"xacro")]),
106 PathJoinSubstitution(
107 [FindPackageShare(moveit_config_package),
"srdf", moveit_config_file]
121 robot_description_semantic = {
"robot_description_semantic": robot_description_semantic_content}
123 kinematics_yaml =
load_yaml(
"ur_moveit_config",
"config/kinematics.yaml")
124 robot_description_kinematics = {
"robot_description_kinematics": kinematics_yaml}
126 smacc2_sm_config = PathJoinSubstitution(
128 FindPackageShare(
"sm_test_moveit_ur5_sim"),
130 "sm_test_moveit_ur5_sim_config.yaml",
134 sm_test_moveit_ur5_sim_node = Node(
135 package=
"sm_test_moveit_ur5_sim",
136 executable=
"sm_test_moveit_ur5_sim_node",
137 prefix=
"xterm -xrm 'XTerm*scrollBar: true' -xrm 'xterm*rightScrollBar: true' -hold -sl 10000 -geometry 1000x600 -e",
140 robot_description_semantic,
141 robot_description_kinematics,
144 arguments=[
"--log-level",
"smacc2:=DEBUG"],
147 ur_control_launch = IncludeLaunchDescription(
148 PythonLaunchDescriptionSource(
149 [FindPackageShare(
"ur_bringup"),
"/launch",
"/ur_control.launch.py"]
152 "robot_ip":
"xxx.yyy.zzz.www",
154 "runtime_config_package": runtime_config_package,
155 "controllers_file": controllers_file,
156 "description_package": description_package,
157 "description_file": description_file,
158 "robot_controller":
"scaled_joint_trajectory_controller",
159 "use_fake_hardware":
"true",
161 "launch_rviz":
"false",
162 "initial_joint_controller":
"joint_trajectory_controller",
166 ur_moveit_launch = IncludeLaunchDescription(
167 PythonLaunchDescriptionSource(
168 [FindPackageShare(
"ur_moveit_config"),
"/launch",
"/ur_moveit.launch.py"]
172 "description_package": description_package,
173 "description_file": description_file,
174 "moveit_config_package": moveit_config_package,
175 "moveit_config_file": moveit_config_file,
176 "use_sim_time":
"false",
178 "launch_rviz":
"true",
185 sm_test_moveit_ur5_sim_node,
188 return nodes_to_launch
192 declared_arguments = []
194 declared_arguments.append(
195 DeclareLaunchArgument(
196 "runtime_config_package",
197 default_value=
"ur_bringup",
198 description=
'Package with the controller\'s configuration in "config" folder. \
199 Usually the argument is not set, it enables use of a custom setup.',
202 declared_arguments.append(
203 DeclareLaunchArgument(
205 default_value=
"ur_controllers.yaml",
206 description=
"YAML file with the controllers configuration.",
209 declared_arguments.append(
210 DeclareLaunchArgument(
211 "description_package",
212 default_value=
"ur_description",
213 description=
"Description package with robot URDF/XACRO files. Usually the argument \
214 is not set, it enables use of a custom description.",
217 declared_arguments.append(
218 DeclareLaunchArgument(
220 default_value=
"ur.urdf.xacro",
221 description=
"URDF/XACRO description file with the robot.",
224 declared_arguments.append(
225 DeclareLaunchArgument(
226 "moveit_config_package",
227 default_value=
"ur_moveit_config",
228 description=
"MoveIt config package with robot SRDF/XACRO files. Usually the argument \
229 is not set, it enables use of a custom moveit config.",
232 declared_arguments.append(
233 DeclareLaunchArgument(
234 "moveit_config_file",
235 default_value=
"ur.srdf.xacro",
236 description=
"MoveIt SRDF/XACRO description file with the robot.",
239 declared_arguments.append(
240 DeclareLaunchArgument(
243 description=
"Prefix of the joint names, useful for \
244 multi-robot setup. If changed than also joint names in the controllers' configuration \
245 have to be updated.",
248 declared_arguments.append(
249 DeclareLaunchArgument(
"launch_rviz", default_value=
"true", description=
"Launch RViz?")
252 return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])
def generate_launch_description()
def load_yaml(package_name, file_path)
def launch_setup(context, *args, **kwargs)
def construct_angle_radians(loader, node)
def construct_angle_degrees(loader, node)