|
| 1 | +import os |
| 2 | +import yaml |
| 3 | +from launch import LaunchDescription |
| 4 | +from launch_ros.actions import Node |
| 5 | +from ament_index_python.packages import get_package_share_directory |
| 6 | +import xacro |
| 7 | + |
| 8 | +def load_file(package_name, file_path): |
| 9 | + package_path = get_package_share_directory(package_name) |
| 10 | + absolute_file_path = os.path.join(package_path, file_path) |
| 11 | + |
| 12 | + try: |
| 13 | + with open(absolute_file_path, 'r') as file: |
| 14 | + return file.read() |
| 15 | + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available |
| 16 | + return None |
| 17 | + |
| 18 | +def load_yaml(package_name, file_path): |
| 19 | + package_path = get_package_share_directory(package_name) |
| 20 | + absolute_file_path = os.path.join(package_path, file_path) |
| 21 | + |
| 22 | + try: |
| 23 | + with open(absolute_file_path, 'r') as file: |
| 24 | + return yaml.safe_load(file) |
| 25 | + except EnvironmentError: # parent of IOError, OSError *and* WindowsError where available |
| 26 | + return None |
| 27 | + |
| 28 | + |
| 29 | +def generate_launch_description(): |
| 30 | + |
| 31 | + # planning_context |
| 32 | + # set ur robot |
| 33 | + robot_name = 'ur5_e' |
| 34 | + |
| 35 | + # <robot_name> parameters files |
| 36 | + joint_limits_params = os.path.join(get_package_share_directory('ur_description'), 'config/' + |
| 37 | + robot_name.replace('_', ''), 'joint_limits.yaml') |
| 38 | + kinematics_params = os.path.join(get_package_share_directory('ur_description'), 'config/' + |
| 39 | + robot_name.replace('_', ''), 'default_kinematics.yaml') |
| 40 | + physical_params = os.path.join(get_package_share_directory('ur_description'), 'config/' + |
| 41 | + robot_name.replace('_', ''), 'physical_parameters.yaml') |
| 42 | + visual_params = os.path.join(get_package_share_directory('ur_description'), 'config/' + |
| 43 | + robot_name.replace('_', ''), 'visual_parameters.yaml') |
| 44 | + |
| 45 | + # common parameters |
| 46 | + # If True, enable the safety limits controller |
| 47 | + safety_limits = False |
| 48 | + # The lower/upper limits in the safety controller |
| 49 | + safety_pos_margin = 0.15 |
| 50 | + # Used to set k position in the safety controller |
| 51 | + safety_k_position = 20 |
| 52 | + |
| 53 | + # Get URDF via xacro |
| 54 | + robot_description_path = os.path.join(get_package_share_directory('ur_description'), 'urdf', 'ur.xacro') |
| 55 | + |
| 56 | + robot_description_config = xacro.process_file(robot_description_path, |
| 57 | + mappings={'joint_limit_params': joint_limits_params, |
| 58 | + 'kinematics_params': kinematics_params, |
| 59 | + 'physical_params': physical_params, |
| 60 | + 'visual_params': visual_params, |
| 61 | + 'safety_limits': str(safety_limits).lower(), |
| 62 | + 'safety_pos_margin': str(safety_pos_margin), |
| 63 | + 'safety_k_position': str(safety_k_position), |
| 64 | + 'name': robot_name.replace('_', '')} |
| 65 | + ) |
| 66 | + |
| 67 | + robot_description = {'robot_description': robot_description_config.toxml()} |
| 68 | + |
| 69 | + robot_description_semantic_config = load_file('ur5_e_moveit_config', 'config/ur5e.srdf') |
| 70 | + robot_description_semantic = {'robot_description_semantic' : robot_description_semantic_config} |
| 71 | + |
| 72 | + kinematics_yaml = load_yaml('ur5_e_moveit_config', 'config/kinematics.yaml') |
| 73 | + robot_description_kinematics = { 'robot_description_kinematics' : kinematics_yaml } |
| 74 | + |
| 75 | + # Planning Functionality |
| 76 | + ompl_planning_pipeline_config = { 'move_group' : { |
| 77 | + 'planning_plugin' : 'ompl_interface/OMPLPlanner', |
| 78 | + 'request_adapters' : """default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/FixWorkspaceBounds default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints""" , |
| 79 | + 'start_state_max_bounds_error' : 0.1 } } |
| 80 | + ompl_planning_yaml = load_yaml('ur5_e_moveit_config', 'config/ompl_planning.yaml') |
| 81 | + ompl_planning_pipeline_config['move_group'].update(ompl_planning_yaml) |
| 82 | + |
| 83 | + # Trajectory Execution Functionality |
| 84 | + controllers_yaml = load_yaml('run_move_group', 'config/controllers.yaml') |
| 85 | + moveit_controllers = { 'moveit_simple_controller_manager' : controllers_yaml, |
| 86 | + 'moveit_controller_manager': 'moveit_simple_controller_manager/MoveItSimpleControllerManager'} |
| 87 | + |
| 88 | + trajectory_execution = {'moveit_manage_controllers': True, |
| 89 | + 'trajectory_execution.allowed_execution_duration_scaling': 1.2, |
| 90 | + 'trajectory_execution.allowed_goal_duration_margin': 0.5, |
| 91 | + 'trajectory_execution.allowed_start_tolerance': 0.01} |
| 92 | + |
| 93 | + planning_scene_monitor_parameters = {"publish_planning_scene": True, |
| 94 | + "publish_geometry_updates": True, |
| 95 | + "publish_state_updates": True, |
| 96 | + "publish_transforms_updates": True} |
| 97 | + |
| 98 | + # Start the actual move_group node/action server |
| 99 | + run_move_group_node = Node(package='moveit_ros_move_group', |
| 100 | + executable='move_group', |
| 101 | + output='screen', |
| 102 | + parameters=[robot_description, |
| 103 | + robot_description_semantic, |
| 104 | + kinematics_yaml, |
| 105 | + ompl_planning_pipeline_config, |
| 106 | + trajectory_execution, |
| 107 | + moveit_controllers, |
| 108 | + planning_scene_monitor_parameters]) |
| 109 | + |
| 110 | + # RViz |
| 111 | + rviz_config_file = get_package_share_directory('ur_description') + "/config/rviz/view_robot.rviz" |
| 112 | + rviz_node = Node(package='rviz2', |
| 113 | + executable='rviz2', |
| 114 | + name='rviz2', |
| 115 | + output='log', |
| 116 | + arguments=['-d', rviz_config_file], |
| 117 | + parameters=[robot_description, |
| 118 | + robot_description_semantic, |
| 119 | + ompl_planning_pipeline_config, |
| 120 | + kinematics_yaml]) |
| 121 | + |
| 122 | + # Static TF |
| 123 | + static_tf = Node(package='tf2_ros', |
| 124 | + executable='static_transform_publisher', |
| 125 | + name='static_transform_publisher', |
| 126 | + output='log', |
| 127 | + arguments=['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', 'world', 'base_link']) |
| 128 | + |
| 129 | + # Publish TF |
| 130 | + robot_state_publisher = Node(package='robot_state_publisher', |
| 131 | + executable='robot_state_publisher', |
| 132 | + name='robot_state_publisher', |
| 133 | + output='both', |
| 134 | + parameters=[robot_description]) |
| 135 | + |
| 136 | +# TODO(andyz): fake_joint_driver conflicts with the current ros2_controller commits |
| 137 | +# # Fake joint driver |
| 138 | +# fake_joint_driver_node = Node(package='fake_joint_driver', |
| 139 | +# executable='fake_joint_driver_node', |
| 140 | +# parameters=[{'controller_name': 'panda_arm_controller'}, |
| 141 | +# os.path.join(get_package_share_directory("run_move_group"), "config", "panda_controllers.yaml"), |
| 142 | +# os.path.join(get_package_share_directory("run_move_group"), "config", "start_positions.yaml"), |
| 143 | +# robot_description] |
| 144 | +# ) |
| 145 | + |
| 146 | + return LaunchDescription([ rviz_node, static_tf, robot_state_publisher, run_move_group_node ]) |
0 commit comments