|
1 | | -# Copyright (c) 2021, PickNik, Inc. |
| 1 | +# Copyright (c) 2021 PickNik, Inc. |
2 | 2 | # |
3 | 3 | # Licensed under the Apache License, Version 2.0 (the "License"); |
4 | 4 | # you may not use this file except in compliance with the License. |
|
10 | 10 | # distributed under the License is distributed on an "AS IS" BASIS, |
11 | 11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
12 | 12 | # See the License for the specific language governing permissions and |
13 | | -# limitations under the License.v |
14 | | - |
15 | | -import os |
| 13 | +# limitations under the License. |
| 14 | +# |
| 15 | +# Author: Denis Stogl |
16 | 16 |
|
17 | | -import xacro |
18 | | -import yaml |
19 | | -from ament_index_python.packages import get_package_share_directory |
20 | 17 | from launch import LaunchDescription |
| 18 | +from launch.actions import DeclareLaunchArgument |
| 19 | +from launch.conditions import IfCondition |
| 20 | +from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution |
21 | 21 | from launch_ros.actions import Node |
22 | | - |
23 | | - |
24 | | -def load_file(package_name, file_path): |
25 | | - package_path = get_package_share_directory(package_name) |
26 | | - absolute_file_path = os.path.join(package_path, file_path) |
27 | | - |
28 | | - try: |
29 | | - with open(absolute_file_path, "r") as file: |
30 | | - return file.read() |
31 | | - except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available |
32 | | - return None |
| 22 | +from launch_ros.substitutions import FindPackageShare |
33 | 23 |
|
34 | 24 |
|
35 | 25 | def generate_launch_description(): |
36 | | - |
37 | | - # set ur robot |
38 | | - robot_name = "ur5_e" |
39 | | - |
40 | | - # <robot_name> parameters files |
41 | | - joint_limits_params = os.path.join( |
42 | | - get_package_share_directory("ur_description"), |
43 | | - "config/" + robot_name.replace("_", ""), |
44 | | - "joint_limits.yaml", |
45 | | - ) |
46 | | - kinematics_params = os.path.join( |
47 | | - get_package_share_directory("ur_description"), |
48 | | - "config/" + robot_name.replace("_", ""), |
49 | | - "default_kinematics.yaml", |
50 | | - ) |
51 | | - physical_params = os.path.join( |
52 | | - get_package_share_directory("ur_description"), |
53 | | - "config/" + robot_name.replace("_", ""), |
54 | | - "physical_parameters.yaml", |
55 | | - ) |
56 | | - visual_params = os.path.join( |
57 | | - get_package_share_directory("ur_description"), |
58 | | - "config/" + robot_name.replace("_", ""), |
59 | | - "visual_parameters.yaml", |
| 26 | + declared_arguments = [] |
| 27 | + # UR specific arguments |
| 28 | + declared_arguments.append( |
| 29 | + DeclareLaunchArgument("ur_type", description="Type/series of used UR robot.") |
60 | 30 | ) |
61 | | - |
62 | | - # common parameters |
63 | | - # If True, enable the safety limits controller |
64 | | - safety_limits = False |
65 | | - # The lower/upper limits in the safety controller |
66 | | - safety_pos_margin = 0.15 |
67 | | - # Used to set k position in the safety controller |
68 | | - safety_k_position = 20 |
69 | | - |
70 | | - # Get URDF via xacro |
71 | | - robot_description_path = os.path.join( |
72 | | - get_package_share_directory("ur_description"), "urdf", "ur.xacro" |
| 31 | + # TODO(anyone): enable this when added into ROS2-foxy |
| 32 | + # choices=['ur3', 'ur3e', 'ur5', 'ur5e', 'ur10', 'ur10e', 'ur16e'])) |
| 33 | + declared_arguments.append( |
| 34 | + DeclareLaunchArgument( |
| 35 | + "safety_limits", |
| 36 | + default_value="true", |
| 37 | + description="Enables the safety limits controller if true.", |
| 38 | + ) |
73 | 39 | ) |
74 | | - |
75 | | - robot_description_config = xacro.process_file( |
76 | | - robot_description_path, |
77 | | - mappings={ |
78 | | - "joint_limit_params": joint_limits_params, |
79 | | - "kinematics_params": kinematics_params, |
80 | | - "physical_params": physical_params, |
81 | | - "visual_params": visual_params, |
82 | | - "safety_limits": str(safety_limits).lower(), |
83 | | - "safety_pos_margin": str(safety_pos_margin), |
84 | | - "safety_k_position": str(safety_k_position), |
85 | | - "name": robot_name.replace("_", ""), |
86 | | - }, |
| 40 | + declared_arguments.append( |
| 41 | + DeclareLaunchArgument( |
| 42 | + "safety_pos_margin", |
| 43 | + default_value="0.15", |
| 44 | + description="The margin to lower and upper limits in the safety controller.", |
| 45 | + ) |
| 46 | + ) |
| 47 | + declared_arguments.append( |
| 48 | + DeclareLaunchArgument( |
| 49 | + "safety_k_position", |
| 50 | + default_value="20", |
| 51 | + description="k-position factor in the safety controller.", |
| 52 | + ) |
| 53 | + ) |
| 54 | + # General arguments |
| 55 | + declared_arguments.append( |
| 56 | + DeclareLaunchArgument( |
| 57 | + "runtime_config_package", |
| 58 | + default_value="ur_bringup", |
| 59 | + description='Package with the controller\'s configuration in "config" folder. \ |
| 60 | + Usually the argument is not set, it enables use of a custom setup.', |
| 61 | + ) |
| 62 | + ) |
| 63 | + declared_arguments.append( |
| 64 | + DeclareLaunchArgument( |
| 65 | + "controllers_file", |
| 66 | + default_value="ur_controllers.yaml", |
| 67 | + description="YAML file with the controllers configuration.", |
| 68 | + ) |
| 69 | + ) |
| 70 | + declared_arguments.append( |
| 71 | + DeclareLaunchArgument( |
| 72 | + "description_package", |
| 73 | + default_value="ur_description", |
| 74 | + description="Description package with robot URDF/XACRO files. Usually the argument \ |
| 75 | + is not set, it enables use of a custom description.", |
| 76 | + ) |
| 77 | + ) |
| 78 | + declared_arguments.append( |
| 79 | + DeclareLaunchArgument( |
| 80 | + "description_file", |
| 81 | + default_value="ur.urdf.xacro", |
| 82 | + description="URDF/XACRO description file with the robot.", |
| 83 | + ) |
| 84 | + ) |
| 85 | + declared_arguments.append( |
| 86 | + DeclareLaunchArgument( |
| 87 | + "prefix", |
| 88 | + default_value='""', |
| 89 | + description="Prefix of the joint names, useful for \ |
| 90 | + multi-robot setup. If changed than also joint names in the controllers' configuration \ |
| 91 | + have to be updated.", |
| 92 | + ) |
87 | 93 | ) |
88 | 94 |
|
89 | | - robot_description = {"robot_description": robot_description_config.toxml()} |
| 95 | + # Initialize Arguments |
| 96 | + ur_type = LaunchConfiguration("ur_type") |
| 97 | + safety_limits = LaunchConfiguration("safety_limits") |
| 98 | + safety_pos_margin = LaunchConfiguration("safety_pos_margin") |
| 99 | + safety_k_position = LaunchConfiguration("safety_k_position") |
| 100 | + # General arguments |
| 101 | + runtime_config_package = LaunchConfiguration("runtime_config_package") |
| 102 | + controllers_file = LaunchConfiguration("controllers_file") |
| 103 | + description_package = LaunchConfiguration("description_package") |
| 104 | + description_file = LaunchConfiguration("description_file") |
| 105 | + prefix = LaunchConfiguration("prefix") |
| 106 | + |
| 107 | + joint_limit_params = PathJoinSubstitution( |
| 108 | + [FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"] |
| 109 | + ) |
| 110 | + kinematics_params = PathJoinSubstitution( |
| 111 | + [FindPackageShare(description_package), "config", ur_type, "default_kinematics.yaml"] |
| 112 | + ) |
| 113 | + physical_params = PathJoinSubstitution( |
| 114 | + [FindPackageShare(description_package), "config", ur_type, "physical_parameters.yaml"] |
| 115 | + ) |
| 116 | + visual_params = PathJoinSubstitution( |
| 117 | + [FindPackageShare(description_package), "config", ur_type, "visual_parameters.yaml"] |
| 118 | + ) |
| 119 | + script_filename = PathJoinSubstitution( |
| 120 | + [FindPackageShare("ur_robot_driver"), "resources", "ros_control.urscript"] |
| 121 | + ) |
| 122 | + input_recipe_filename = PathJoinSubstitution( |
| 123 | + [FindPackageShare("ur_robot_driver"), "resources", "rtde_input_recipe.txt"] |
| 124 | + ) |
| 125 | + output_recipe_filename = PathJoinSubstitution( |
| 126 | + [FindPackageShare("ur_robot_driver"), "resources", "rtde_output_recipe.txt"] |
| 127 | + ) |
90 | 128 |
|
91 | | - robot_description_semantic_config = load_file( |
92 | | - robot_name + "_moveit_config", "config/" + robot_name.replace("_", "") + ".srdf" |
| 129 | + robot_description_content = Command( |
| 130 | + [ |
| 131 | + PathJoinSubstitution([FindExecutable(name="xacro")]), |
| 132 | + " ", |
| 133 | + PathJoinSubstitution([FindPackageShare(description_package), "urdf", description_file]), |
| 134 | + " ", |
| 135 | + "joint_limit_params:=", |
| 136 | + joint_limit_params, |
| 137 | + " ", |
| 138 | + "kinematics_params:=", |
| 139 | + kinematics_params, |
| 140 | + " ", |
| 141 | + "physical_params:=", |
| 142 | + physical_params, |
| 143 | + " ", |
| 144 | + "visual_params:=", |
| 145 | + visual_params, |
| 146 | + " ", |
| 147 | + "safety_limits:=", |
| 148 | + safety_limits, |
| 149 | + " ", |
| 150 | + "safety_pos_margin:=", |
| 151 | + safety_pos_margin, |
| 152 | + " ", |
| 153 | + "safety_k_position:=", |
| 154 | + safety_k_position, |
| 155 | + " ", |
| 156 | + "name:=", |
| 157 | + ur_type, |
| 158 | + " ", |
| 159 | + "script_filename:=", |
| 160 | + script_filename, |
| 161 | + " ", |
| 162 | + "input_recipe_filename:=", |
| 163 | + input_recipe_filename, |
| 164 | + " ", |
| 165 | + "output_recipe_filename:=", |
| 166 | + output_recipe_filename, |
| 167 | + " ", |
| 168 | + "prefix:=", |
| 169 | + prefix, |
| 170 | + ] |
93 | 171 | ) |
94 | | - robot_description_semantic = {"robot_description_semantic": robot_description_semantic_config} |
| 172 | + robot_description = {"robot_description": robot_description_content} |
95 | 173 |
|
96 | | - # We do not have a robot connected, so publish fake joint states |
97 | | - joint_state_pub_node = Node(package="joint_state_publisher", executable="joint_state_publisher") |
| 174 | + rviz_config_file = PathJoinSubstitution( |
| 175 | + [FindPackageShare(description_package), "rviz", "view_robot.rviz"] |
| 176 | + ) |
98 | 177 |
|
99 | | - # Publishes tf's for the robot |
100 | | - robot_state_pub_node = Node( |
| 178 | + joint_state_publisher_node = Node( |
| 179 | + package="joint_state_publisher_gui", |
| 180 | + executable="joint_state_publisher_gui", |
| 181 | + ) |
| 182 | + robot_state_publisher_node = Node( |
101 | 183 | package="robot_state_publisher", |
102 | 184 | executable="robot_state_publisher", |
103 | | - output="screen", |
| 185 | + output="both", |
104 | 186 | parameters=[robot_description], |
105 | 187 | ) |
106 | | - |
107 | | - # RViz |
108 | | - rviz_config_file = ( |
109 | | - get_package_share_directory("ur_description") + "/config/rviz/view_robot.rviz" |
110 | | - ) |
111 | 188 | rviz_node = Node( |
112 | 189 | package="rviz2", |
113 | 190 | executable="rviz2", |
114 | 191 | name="rviz2", |
115 | 192 | output="log", |
116 | 193 | arguments=["-d", rviz_config_file], |
117 | | - parameters=[robot_description, robot_description_semantic], |
118 | 194 | ) |
119 | 195 |
|
120 | | - return LaunchDescription([rviz_node, robot_state_pub_node, joint_state_pub_node]) |
| 196 | + nodes_to_start = [ |
| 197 | + joint_state_publisher_node, |
| 198 | + robot_state_publisher_node, |
| 199 | + rviz_node, |
| 200 | + ] |
| 201 | + |
| 202 | + return LaunchDescription(declared_arguments + nodes_to_start) |
0 commit comments