From 174e5bb3b0aa06419a5b4c783ef181105d31b5a4 Mon Sep 17 00:00:00 2001 From: urrsk <41109954+urrsk@users.noreply.github.com> Date: Thu, 7 Sep 2023 12:53:42 +0200 Subject: [PATCH 01/12] UR20 description and meshes The UR20 meshes are added under Universal Robots A/S' Terms and Conditions for Use of Graphical Documentation --- README.md | 3 +- universal_robots/package.xml | 1 + ur20_moveit_config/.setup_assistant | 11 + ur20_moveit_config/CHANGELOG.rst | 3 + ur20_moveit_config/CMakeLists.txt | 14 + ur20_moveit_config/config/chomp_planning.yaml | 18 + .../config/fake_controllers.yaml | 12 + ur20_moveit_config/config/joint_limits.yaml | 34 + ur20_moveit_config/config/kinematics.yaml | 5 + ur20_moveit_config/config/ompl_planning.yaml | 149 +++ .../config/ros_controllers.yaml | 11 + ur20_moveit_config/config/ur20.srdf | 46 + .../launch/chomp_planning_pipeline.launch.xml | 20 + .../launch/default_warehouse_db.launch | 15 + ur20_moveit_config/launch/demo.launch | 63 ++ .../fake_moveit_controller_manager.launch.xml | 9 + ur20_moveit_config/launch/move_group.launch | 82 ++ ur20_moveit_config/launch/moveit.rviz | 280 +++++ .../launch/moveit_planning_execution.launch | 12 + ur20_moveit_config/launch/moveit_rviz.launch | 15 + .../launch/ompl_planning_pipeline.launch.xml | 22 + .../launch/planning_context.launch | 25 + .../launch/planning_pipeline.launch.xml | 10 + .../launch/run_benchmark_ompl.launch | 22 + .../launch/sensor_manager.launch.xml | 14 + .../launch/setup_assistant.launch | 15 + .../launch/trajectory_execution.launch.xml | 18 + .../ur20_moveit_controller_manager.launch.xml | 6 + .../ur20_moveit_sensor_manager.launch.xml | 3 + ur20_moveit_config/launch/warehouse.launch | 15 + .../launch/warehouse_settings.launch.xml | 16 + ur20_moveit_config/package.xml | 41 + .../tests/moveit_planning_execution.xml | 16 + ur_description/CMakeLists.txt | 1 + .../config/ur20/default_kinematics.yaml | 44 + ur_description/config/ur20/joint_limits.yaml | 77 ++ .../config/ur20/physical_parameters.yaml | 78 ++ .../config/ur20/visual_parameters.yaml | 70 ++ ur_description/launch/load_ur20.launch | 18 + ur_description/launch/view_ur20.launch | 8 + ur_description/meshes/ur20/LICENSE.txt | 84 ++ ur_description/meshes/ur20/collision/base.stl | Bin 0 -> 21884 bytes .../meshes/ur20/collision/forearm.stl | Bin 0 -> 124384 bytes .../meshes/ur20/collision/shoulder.stl | Bin 0 -> 27084 bytes .../meshes/ur20/collision/upperarm.stl | Bin 0 -> 121484 bytes .../meshes/ur20/collision/wrist1.stl | Bin 0 -> 36484 bytes .../meshes/ur20/collision/wrist2.stl | Bin 0 -> 28084 bytes .../meshes/ur20/collision/wrist3.stl | Bin 0 -> 15784 bytes .../meshes/ur20/visual/UR20_DIFF_8bit_2K.png | Bin 0 -> 1561213 bytes ur_description/meshes/ur20/visual/base.dae | 521 +++++++++ ur_description/meshes/ur20/visual/forearm.dae | 871 ++++++++++++++ .../meshes/ur20/visual/shoulder.dae | 264 +++++ .../meshes/ur20/visual/upperarm.dae | 386 +++++++ ur_description/meshes/ur20/visual/wrist1.dae | 521 +++++++++ ur_description/meshes/ur20/visual/wrist2.dae | 264 +++++ ur_description/meshes/ur20/visual/wrist3.dae | 1003 +++++++++++++++++ ur_description/package.xml | 7 +- ur_description/tests/roslaunch_test_ur20.xml | 10 + ur_description/urdf/inc/ur20_macro.xacro | 47 + ur_description/urdf/inc/ur_macro.xacro | 2 +- ur_description/urdf/ur20.xacro | 22 + ur_gazebo/CMakeLists.txt | 1 + ur_gazebo/config/ur20_controllers.yaml | 36 + ur_gazebo/launch/inc/load_ur.launch.xml | 2 +- ur_gazebo/launch/inc/load_ur20.launch.xml | 19 + ur_gazebo/launch/ur20_bringup.launch | 75 ++ ur_gazebo/tests/roslaunch_test_ur20.xml | 10 + ur_kinematics/CMakeLists.txt | 13 +- ur_kinematics/src/ur_kin.cpp | 10 + ur_kinematics/ur_moveit_plugins.xml | 10 + 70 files changed, 5494 insertions(+), 6 deletions(-) create mode 100644 ur20_moveit_config/.setup_assistant create mode 100644 ur20_moveit_config/CHANGELOG.rst create mode 100644 ur20_moveit_config/CMakeLists.txt create mode 100644 ur20_moveit_config/config/chomp_planning.yaml create mode 100644 ur20_moveit_config/config/fake_controllers.yaml create mode 100644 ur20_moveit_config/config/joint_limits.yaml create mode 100644 ur20_moveit_config/config/kinematics.yaml create mode 100644 ur20_moveit_config/config/ompl_planning.yaml create mode 100644 ur20_moveit_config/config/ros_controllers.yaml create mode 100644 ur20_moveit_config/config/ur20.srdf create mode 100644 ur20_moveit_config/launch/chomp_planning_pipeline.launch.xml create mode 100644 ur20_moveit_config/launch/default_warehouse_db.launch create mode 100644 ur20_moveit_config/launch/demo.launch create mode 100644 ur20_moveit_config/launch/fake_moveit_controller_manager.launch.xml create mode 100644 ur20_moveit_config/launch/move_group.launch create mode 100644 ur20_moveit_config/launch/moveit.rviz create mode 100644 ur20_moveit_config/launch/moveit_planning_execution.launch create mode 100644 ur20_moveit_config/launch/moveit_rviz.launch create mode 100644 ur20_moveit_config/launch/ompl_planning_pipeline.launch.xml create mode 100644 ur20_moveit_config/launch/planning_context.launch create mode 100644 ur20_moveit_config/launch/planning_pipeline.launch.xml create mode 100644 ur20_moveit_config/launch/run_benchmark_ompl.launch create mode 100644 ur20_moveit_config/launch/sensor_manager.launch.xml create mode 100644 ur20_moveit_config/launch/setup_assistant.launch create mode 100644 ur20_moveit_config/launch/trajectory_execution.launch.xml create mode 100644 ur20_moveit_config/launch/ur20_moveit_controller_manager.launch.xml create mode 100644 ur20_moveit_config/launch/ur20_moveit_sensor_manager.launch.xml create mode 100644 ur20_moveit_config/launch/warehouse.launch create mode 100644 ur20_moveit_config/launch/warehouse_settings.launch.xml create mode 100644 ur20_moveit_config/package.xml create mode 100644 ur20_moveit_config/tests/moveit_planning_execution.xml create mode 100644 ur_description/config/ur20/default_kinematics.yaml create mode 100644 ur_description/config/ur20/joint_limits.yaml create mode 100644 ur_description/config/ur20/physical_parameters.yaml create mode 100644 ur_description/config/ur20/visual_parameters.yaml create mode 100644 ur_description/launch/load_ur20.launch create mode 100644 ur_description/launch/view_ur20.launch create mode 100644 ur_description/meshes/ur20/LICENSE.txt create mode 100644 ur_description/meshes/ur20/collision/base.stl create mode 100644 ur_description/meshes/ur20/collision/forearm.stl create mode 100644 ur_description/meshes/ur20/collision/shoulder.stl create mode 100644 ur_description/meshes/ur20/collision/upperarm.stl create mode 100644 ur_description/meshes/ur20/collision/wrist1.stl create mode 100644 ur_description/meshes/ur20/collision/wrist2.stl create mode 100644 ur_description/meshes/ur20/collision/wrist3.stl create mode 100644 ur_description/meshes/ur20/visual/UR20_DIFF_8bit_2K.png create mode 100644 ur_description/meshes/ur20/visual/base.dae create mode 100644 ur_description/meshes/ur20/visual/forearm.dae create mode 100644 ur_description/meshes/ur20/visual/shoulder.dae create mode 100644 ur_description/meshes/ur20/visual/upperarm.dae create mode 100644 ur_description/meshes/ur20/visual/wrist1.dae create mode 100644 ur_description/meshes/ur20/visual/wrist2.dae create mode 100644 ur_description/meshes/ur20/visual/wrist3.dae create mode 100644 ur_description/tests/roslaunch_test_ur20.xml create mode 100644 ur_description/urdf/inc/ur20_macro.xacro create mode 100644 ur_description/urdf/ur20.xacro create mode 100644 ur_gazebo/config/ur20_controllers.yaml create mode 100644 ur_gazebo/launch/inc/load_ur20.launch.xml create mode 100644 ur_gazebo/launch/ur20_bringup.launch create mode 100644 ur_gazebo/tests/roslaunch_test_ur20.xml diff --git a/README.md b/README.md index 22fde1b87..18cbf32ed 100644 --- a/README.md +++ b/README.md @@ -3,8 +3,9 @@ [![Build Status: Ubuntu Bionic (Actions)](https://github.com/ros-industrial/universal_robot/workflows/CI%20-%20Ubuntu%20Bionic/badge.svg?branch=melodic-devel)](https://github.com/ros-industrial/universal_robot/actions?query=workflow%3A%22CI+-+Ubuntu+Bionic%22) [![Build Status: Ubuntu Focal (Actions)](https://github.com/ros-industrial/universal_robot/workflows/CI%20-%20Ubuntu%20Focal/badge.svg?branch=melodic-devel)](https://github.com/ros-industrial/universal_robot/actions?query=workflow%3A%22CI+-+Ubuntu+Focal%22) -[![license - apache 2.0](https://img.shields.io/:license-Apache%202.0-yellowgreen.svg)](https://opensource.org/licenses/Apache-2.0) +[![License - apache 2.0](https://img.shields.io/:license-Apache%202.0-yellowgreen.svg)](https://opensource.org/licenses/Apache-2.0) [![License](https://img.shields.io/badge/License-BSD%203--Clause-blue.svg)](https://opensource.org/licenses/BSD-3-Clause) +[![License](https://img.shields.io/badge/License-Universal%20Robots%20A/S%E2%80%99%20Terms%20and%20Conditions%20for%20Use%20of%20Graphical%20Documentation-blue.svg)](https://www.universal-robots.com/legal/terms-and-conditions/terms_and_conditions_for_use_of_graphical_documentation.txt) [![support level: community](https://img.shields.io/badge/support%20level-community-lightgray.png)](http://rosindustrial.org/news/2016/10/7/better-supporting-a-growing-ros-industrial-software-platform) diff --git a/universal_robots/package.xml b/universal_robots/package.xml index 0d2e1ec76..5da09dd52 100644 --- a/universal_robots/package.xml +++ b/universal_robots/package.xml @@ -23,6 +23,7 @@ ur10e_moveit_config ur10_moveit_config ur16e_moveit_config + ur20_moveit_config ur3e_moveit_config ur3_moveit_config ur5e_moveit_config diff --git a/ur20_moveit_config/.setup_assistant b/ur20_moveit_config/.setup_assistant new file mode 100644 index 000000000..be1d4b332 --- /dev/null +++ b/ur20_moveit_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: ur_description + relative_path: urdf/ur20.xacro + xacro_args: "" + SRDF: + relative_path: config/ur20.srdf + CONFIG: + author_name: Felix Exner + author_email: felix@fexner.de + generated_timestamp: 1611154369 \ No newline at end of file diff --git a/ur20_moveit_config/CHANGELOG.rst b/ur20_moveit_config/CHANGELOG.rst new file mode 100644 index 000000000..16ee649bc --- /dev/null +++ b/ur20_moveit_config/CHANGELOG.rst @@ -0,0 +1,3 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package ur20_moveit_config +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ \ No newline at end of file diff --git a/ur20_moveit_config/CMakeLists.txt b/ur20_moveit_config/CMakeLists.txt new file mode 100644 index 000000000..ddd41b3e0 --- /dev/null +++ b/ur20_moveit_config/CMakeLists.txt @@ -0,0 +1,14 @@ +cmake_minimum_required(VERSION 2.8.3) +project(ur20_moveit_config) + +find_package(catkin REQUIRED) + +catkin_package() + +if (CATKIN_ENABLE_TESTING) + find_package(roslaunch REQUIRED) + roslaunch_add_file_check(tests/moveit_planning_execution.xml) +endif() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/ur20_moveit_config/config/chomp_planning.yaml b/ur20_moveit_config/config/chomp_planning.yaml new file mode 100644 index 000000000..75258e53e --- /dev/null +++ b/ur20_moveit_config/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.01 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearence: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: true +max_recovery_attempts: 5 \ No newline at end of file diff --git a/ur20_moveit_config/config/fake_controllers.yaml b/ur20_moveit_config/config/fake_controllers.yaml new file mode 100644 index 000000000..afbfa6e6c --- /dev/null +++ b/ur20_moveit_config/config/fake_controllers.yaml @@ -0,0 +1,12 @@ +controller_list: + - name: fake_manipulator_controller + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint +initial: # Define initial robot poses. + - group: manipulator + pose: home diff --git a/ur20_moveit_config/config/joint_limits.yaml b/ur20_moveit_config/config/joint_limits.yaml new file mode 100644 index 000000000..633b7bbce --- /dev/null +++ b/ur20_moveit_config/config/joint_limits.yaml @@ -0,0 +1,34 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] +# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] +joint_limits: + elbow_joint: + has_velocity_limits: true + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 + shoulder_lift_joint: + has_velocity_limits: true + max_velocity: 2.0943951023931953 + has_acceleration_limits: false + max_acceleration: 0 + shoulder_pan_joint: + has_velocity_limits: true + max_velocity: 2.0943951023931953 + has_acceleration_limits: false + max_acceleration: 0 + wrist_1_joint: + has_velocity_limits: true + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 + wrist_2_joint: + has_velocity_limits: true + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 + wrist_3_joint: + has_velocity_limits: true + max_velocity: 3.1415926535897931 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/ur20_moveit_config/config/kinematics.yaml b/ur20_moveit_config/config/kinematics.yaml new file mode 100644 index 000000000..7e7474f06 --- /dev/null +++ b/ur20_moveit_config/config/kinematics.yaml @@ -0,0 +1,5 @@ +manipulator: + kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin + solve_type: Distance + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 diff --git a/ur20_moveit_config/config/ompl_planning.yaml b/ur20_moveit_config/config/ompl_planning.yaml new file mode 100644 index 000000000..39ba9f166 --- /dev/null +++ b/ur20_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,149 @@ +planner_configs: + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRM: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRT: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +manipulator: + longest_valid_segment_fraction: 0.01 + default_planner_config: RRTConnect + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo diff --git a/ur20_moveit_config/config/ros_controllers.yaml b/ur20_moveit_config/config/ros_controllers.yaml new file mode 100644 index 000000000..bfc4186c4 --- /dev/null +++ b/ur20_moveit_config/config/ros_controllers.yaml @@ -0,0 +1,11 @@ +controller_list: +- name: "scaled_pos_joint_traj_controller" + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint diff --git a/ur20_moveit_config/config/ur20.srdf b/ur20_moveit_config/config/ur20.srdf new file mode 100644 index 000000000..2c3296d99 --- /dev/null +++ b/ur20_moveit_config/config/ur20.srdf @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/chomp_planning_pipeline.launch.xml b/ur20_moveit_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 000000000..104357b6e --- /dev/null +++ b/ur20_moveit_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/default_warehouse_db.launch b/ur20_moveit_config/launch/default_warehouse_db.launch new file mode 100644 index 000000000..c7c9d59d7 --- /dev/null +++ b/ur20_moveit_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/demo.launch b/ur20_moveit_config/launch/demo.launch new file mode 100644 index 000000000..261e95c66 --- /dev/null +++ b/ur20_moveit_config/launch/demo.launch @@ -0,0 +1,63 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/ur20_moveit_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 000000000..62b0f3e74 --- /dev/null +++ b/ur20_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/ur20_moveit_config/launch/move_group.launch b/ur20_moveit_config/launch/move_group.launch new file mode 100644 index 000000000..5561f3b50 --- /dev/null +++ b/ur20_moveit_config/launch/move_group.launch @@ -0,0 +1,82 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/moveit.rviz b/ur20_moveit_config/launch/moveit.rviz new file mode 100644 index 000000000..cfc2fec04 --- /dev/null +++ b/ur20_moveit_config/launch/moveit.rviz @@ -0,0 +1,280 @@ +Panels: + - Class: rviz/Displays + Help Height: 0 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.5175438523292542 + Tree Height: 259 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Acceleration_Scaling_Factor: 1 + Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Move Group Namespace: "" + MoveIt_Allow_Approximate_IK: false + MoveIt_Allow_External_Program: false + MoveIt_Allow_Replanning: false + MoveIt_Allow_Sensor_Positioning: false + MoveIt_Planning_Attempts: 10 + MoveIt_Planning_Time: 5 + MoveIt_Use_Cartesian_Path: false + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + MoveIt_Workspace: + Center: + X: 0 + Y: 0 + Z: 0 + Size: + X: 2 + Y: 2 + Z: 2 + Name: MotionPlanning + Planned Path: + Color Enabled: false + Interrupt Display: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link_inertia: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + flange: + Alpha: 1 + Show Axes: false + Show Trail: false + forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: false + Robot Alpha: 0.5 + Robot Color: 150; 50; 150 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trail Step Size: 1 + Trajectory Topic: move_group/display_planned_path + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + TextHeight: 0.07999999821186066 + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0 + Joint Violation Color: 255; 0; 255 + Planning Group: manipulator + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: move_group/monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.20000000298023224 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link_inertia: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + flange: + Alpha: 1 + Show Axes: false + Show Trail: false + forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + tool0: + Alpha: 1 + Show Axes: false + Show Trail: false + upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Value: true + Velocity_Scaling_Factor: 1 + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.996500015258789 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 1.1539382934570312 + Y: 0.5978575348854065 + Z: -2.5331917186122155e-7 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.45979705452919006 + Target Frame: base_link + Value: XYOrbit (rviz) + Yaw: 0.9717636108398438 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 783 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + MotionPlanning: + collapsed: false + MotionPlanning - Trajectory Slider: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000001ca000002b9fc0200000007fb000000100044006900730070006c006100790073010000003b0000013e000000c700fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a0056006900650077007300000003b0000000b0000000a000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e0067010000017f000001750000016a00ffffff000002ce000002b900000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1182 + X: 481 + Y: 253 diff --git a/ur20_moveit_config/launch/moveit_planning_execution.launch b/ur20_moveit_config/launch/moveit_planning_execution.launch new file mode 100644 index 000000000..0d4bb8586 --- /dev/null +++ b/ur20_moveit_config/launch/moveit_planning_execution.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/moveit_rviz.launch b/ur20_moveit_config/launch/moveit_rviz.launch new file mode 100644 index 000000000..fdfce5d71 --- /dev/null +++ b/ur20_moveit_config/launch/moveit_rviz.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/ompl_planning_pipeline.launch.xml b/ur20_moveit_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 000000000..d77c27744 --- /dev/null +++ b/ur20_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/planning_context.launch b/ur20_moveit_config/launch/planning_context.launch new file mode 100644 index 000000000..e9aebb223 --- /dev/null +++ b/ur20_moveit_config/launch/planning_context.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/planning_pipeline.launch.xml b/ur20_moveit_config/launch/planning_pipeline.launch.xml new file mode 100644 index 000000000..ba4ddc454 --- /dev/null +++ b/ur20_moveit_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/ur20_moveit_config/launch/run_benchmark_ompl.launch b/ur20_moveit_config/launch/run_benchmark_ompl.launch new file mode 100644 index 000000000..fa41c9936 --- /dev/null +++ b/ur20_moveit_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/sensor_manager.launch.xml b/ur20_moveit_config/launch/sensor_manager.launch.xml new file mode 100644 index 000000000..2a99dd9ea --- /dev/null +++ b/ur20_moveit_config/launch/sensor_manager.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/setup_assistant.launch b/ur20_moveit_config/launch/setup_assistant.launch new file mode 100644 index 000000000..5ce370450 --- /dev/null +++ b/ur20_moveit_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/trajectory_execution.launch.xml b/ur20_moveit_config/launch/trajectory_execution.launch.xml new file mode 100644 index 000000000..ced15e6ab --- /dev/null +++ b/ur20_moveit_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/ur20_moveit_controller_manager.launch.xml b/ur20_moveit_config/launch/ur20_moveit_controller_manager.launch.xml new file mode 100644 index 000000000..1f36c44a0 --- /dev/null +++ b/ur20_moveit_config/launch/ur20_moveit_controller_manager.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/ur20_moveit_config/launch/ur20_moveit_sensor_manager.launch.xml b/ur20_moveit_config/launch/ur20_moveit_sensor_manager.launch.xml new file mode 100644 index 000000000..5d02698d7 --- /dev/null +++ b/ur20_moveit_config/launch/ur20_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/ur20_moveit_config/launch/warehouse.launch b/ur20_moveit_config/launch/warehouse.launch new file mode 100644 index 000000000..cb4dc0761 --- /dev/null +++ b/ur20_moveit_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/launch/warehouse_settings.launch.xml b/ur20_moveit_config/launch/warehouse_settings.launch.xml new file mode 100644 index 000000000..e473b083b --- /dev/null +++ b/ur20_moveit_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/ur20_moveit_config/package.xml b/ur20_moveit_config/package.xml new file mode 100644 index 000000000..315e43222 --- /dev/null +++ b/ur20_moveit_config/package.xml @@ -0,0 +1,41 @@ + + + + ur20_moveit_config + 1.3.1 + + An automatically generated package with all the configuration and launch files for using the ur20 with the MoveIt Motion Planning Framework + + Felix Messmer + G.A. vd. Hoorn + Miguel Prada Sarasola + Nadia Hammoudeh Garcia + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit_setup_assistant/issues + https://github.com/ros-planning/moveit_setup_assistant + + joint_state_publisher + joint_state_publisher_gui + moveit_fake_controller_manager + moveit_planners_ompl + moveit_ros_benchmarks + moveit_ros_move_group + moveit_ros_visualization + moveit_ros_warehouse + warehouse_ros_mongo + moveit_setup_assistant + moveit_simple_controller_manager + robot_state_publisher + rviz + tf2_ros + trac_ik_kinematics_plugin + ur_description + xacro + + roslaunch + catkin + + diff --git a/ur20_moveit_config/tests/moveit_planning_execution.xml b/ur20_moveit_config/tests/moveit_planning_execution.xml new file mode 100644 index 000000000..8192dfc89 --- /dev/null +++ b/ur20_moveit_config/tests/moveit_planning_execution.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/ur_description/CMakeLists.txt b/ur_description/CMakeLists.txt index 0cc1bd625..f410f7e16 100644 --- a/ur_description/CMakeLists.txt +++ b/ur_description/CMakeLists.txt @@ -10,6 +10,7 @@ if (CATKIN_ENABLE_TESTING) roslaunch_add_file_check(tests/roslaunch_test_ur10e.xml) roslaunch_add_file_check(tests/roslaunch_test_ur10.xml) roslaunch_add_file_check(tests/roslaunch_test_ur16e.xml) + roslaunch_add_file_check(tests/roslaunch_test_ur20.xml) roslaunch_add_file_check(tests/roslaunch_test_ur3e.xml) roslaunch_add_file_check(tests/roslaunch_test_ur3.xml) roslaunch_add_file_check(tests/roslaunch_test_ur5e.xml) diff --git a/ur_description/config/ur20/default_kinematics.yaml b/ur_description/config/ur20/default_kinematics.yaml new file mode 100644 index 000000000..db20fd9da --- /dev/null +++ b/ur_description/config/ur20/default_kinematics.yaml @@ -0,0 +1,44 @@ +kinematics: + shoulder: + x: 0 + y: 0 + z: 0.23630000000000001 + roll: -0 + pitch: 0 + yaw: -0 + upper_arm: + x: 0 + y: 0 + z: 0 + roll: 1.570796327 + pitch: 0 + yaw: -0 + forearm: + x: -0.86199999999999999 + y: 0 + z: 0 + roll: -0 + pitch: 0 + yaw: -0 + wrist_1: + x: -0.72870000000000001 + y: 0 + z: 0.20100000000000001 + roll: -0 + pitch: 0 + yaw: -0 + wrist_2: + x: 0 + y: -0.1593 + z: -3.2672976162492252e-11 + roll: 1.570796327 + pitch: 0 + yaw: -0 + wrist_3: + x: 0 + y: 0.15429999999999999 + z: -3.1647459019915597e-11 + roll: 1.5707963265897931 + pitch: 3.1415926535897931 + yaw: 3.1415926535897931 + hash: calib_4890363623803256388 diff --git a/ur_description/config/ur20/joint_limits.yaml b/ur_description/config/ur20/joint_limits.yaml new file mode 100644 index 000000000..8319755b5 --- /dev/null +++ b/ur_description/config/ur20/joint_limits.yaml @@ -0,0 +1,77 @@ +# Joints limits +# +# Sources: +# +# - Universal Robots e-Series, User Manual, UR20, Version 5.14 +# https://s3-eu-west-1.amazonaws.com/ur-support-site/203281/706-276-00_UR20_User_Manual_en_Global.pdf +joint_limits: + shoulder_pan: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 730.0 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 + shoulder_lift: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 730.0 + max_position: !degrees 360.0 + max_velocity: !degrees 120.0 + min_position: !degrees -360.0 + elbow_joint: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 430.0 + # we artificially limit this joint to half its actual joint position limit + # to avoid (MoveIt/OMPL) planning problems, as due to the physical + # construction of the robot, it's impossible to rotate the 'elbow_joint' + # over more than approx +- 1 pi (the shoulder lift joint gets in the way). + # + # This leads to planning problems as the search space will be divided into + # two sections, with no connections from one to the other. + # + # Refer to https://github.com/ros-industrial/universal_robot/issues/265 for + # more information. + max_position: !degrees 180.0 + max_velocity: !degrees 150.0 + min_position: !degrees -180.0 + wrist_1: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 100.0 + max_position: !degrees 360.0 + max_velocity: !degrees 210.0 + min_position: !degrees -360.0 + wrist_2: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 100.0 + max_position: !degrees 360.0 + max_velocity: !degrees 210.0 + min_position: !degrees -360.0 + wrist_3: + # acceleration limits are not publicly available + has_acceleration_limits: false + has_effort_limits: true + has_position_limits: true + has_velocity_limits: true + max_effort: 100.0 + max_position: !degrees 360.0 + max_velocity: !degrees 210.0 + min_position: !degrees -360.0 \ No newline at end of file diff --git a/ur_description/config/ur20/physical_parameters.yaml b/ur_description/config/ur20/physical_parameters.yaml new file mode 100644 index 000000000..17aaaee8d --- /dev/null +++ b/ur_description/config/ur20/physical_parameters.yaml @@ -0,0 +1,78 @@ +# Physical parameters +# from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/ +dh_parameters: + d1: 0.2363 + a2: -0.8620 + a3: -0.7287 + d4: 0.201 + d5: 0.1593 + d6: 0.1543 +offsets: + shoulder_offset: 0.260 # measured from model + elbow_offset: 0.043 # measured from model +inertia_parameters: + # taken from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/ + base_mass: 4.0 # This mass might be incorrect + shoulder_mass: 16.343 + upper_arm_mass: 29.632 + upper_arm_inertia_offset: 0.275 # measured from model + forearm_mass: 7.879 + wrist_1_mass: 3.054 + wrist_2_mass: 3.126 + wrist_3_mass: 0.846 + + shoulder_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE + upper_arm_radius: x0.054 # FROM UR5 CURRENTLY NOT USED ANYMORE + elbow_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE + forearm_radius: x0.040 # FROM UR5 CURRENTLY NOT USED ANYMORE + wrist_radius: x0.045 # FROM UR5 CURRENTLY NOT USED ANYMORE + + links: + base: + radius: 0.075 + length: 0.038 + shoulder: + radius: 0.075 + length: 0.178 + upperarm: + radius: 0.075 + length: 0.852 + forearm: + radius: 0.075 + length: 0.7287 + wrist_1: + radius: 0.075 + length: 0.12 + wrist_2: + radius: 0.075 + length: 0.12 + wrist_3: + radius: 0.045 + length: 0.05 + + center_of_mass: # Adjusted manually + shoulder_cog: + x: 0.0 + y: 0.00244 + z: -0.037 + upper_arm_cog: + x: 0.00001 + y: 0.15061 + z: 0.48757 + forearm_cog: + x: -0.00012 + y: 0.06112 + z: 0.2984 + wrist_1_cog: + x: -0.00021 + y: -0.00112 + z: 0.02269 + wrist_2_cog: + x: -0.00021 + y: 0.00112 + z: 0.002269 + wrist_3_cog: + x: 0.0 + y: -0.001156 + z: -0.00149 + diff --git a/ur_description/config/ur20/visual_parameters.yaml b/ur_description/config/ur20/visual_parameters.yaml new file mode 100644 index 000000000..ada871ba9 --- /dev/null +++ b/ur_description/config/ur20/visual_parameters.yaml @@ -0,0 +1,70 @@ +# Visualisation + +mesh_files: + base: + visual: + mesh: "package://ur_description/meshes/ur20/visual/base.dae" + material: + name: "LightGrey" + color: "0.7 0.7 0.7 1.0" + collision: + mesh: "package://ur_description/meshes/ur20/collision/base.stl" + + shoulder: + visual: + mesh: "package://ur_description/meshes/ur20/visual/shoulder.dae" + material: + name: "LightGrey" + color: "0.7 0.7 0.7 1.0" + collision: + mesh: "package://ur_description/meshes/ur20/collision/shoulder.stl" + + upper_arm: + visual: + mesh: "package://ur_description/meshes/ur20/visual/upperarm.dae" + material: + name: "LightGrey" + color: "0.7 0.7 0.7 1.0" + collision: + mesh: "package://ur_description/meshes/ur20/collision/upperarm.stl" + mesh_files: + + forearm: + visual: + mesh: "package://ur_description/meshes/ur20/visual/forearm.dae" + material: + name: "LightGrey" + color: "0.7 0.7 0.7 1.0" + collision: + mesh: "package://ur_description/meshes/ur20/collision/forearm.stl" + + wrist_1: + visual: + mesh: "package://ur_description/meshes/ur20/visual/wrist1.dae" + material: + name: "LightGrey" + color: "0.7 0.7 0.7 1.0" + collision: + mesh: "package://ur_description/meshes/ur20/collision/wrist1.stl" + visual_offset: -0.0775 + + wrist_2: + visual: + mesh: "package://ur_description/meshes/ur20/visual/wrist2.dae" + material: + name: "LightGrey" + color: "0.7 0.7 0.7 1.0" + collision: + mesh: "package://ur_description/meshes/ur20/collision/wrist2.stl" + visual_offset: -0.0749 + + wrist_3: + visual: + mesh: "package://ur_description/meshes/ur20/visual/wrist3.dae" + material: + name: "LightGrey" + color: "0.7 0.7 0.7 1.0" + collision: + mesh: "package://ur_description/meshes/ur20/collision/wrist3.stl" + visual_offset: -0.07 + diff --git a/ur_description/launch/load_ur20.launch b/ur_description/launch/load_ur20.launch new file mode 100644 index 000000000..fb5740c0e --- /dev/null +++ b/ur_description/launch/load_ur20.launch @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/ur_description/launch/view_ur20.launch b/ur_description/launch/view_ur20.launch new file mode 100644 index 000000000..0da9d2df9 --- /dev/null +++ b/ur_description/launch/view_ur20.launch @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/ur_description/meshes/ur20/LICENSE.txt b/ur_description/meshes/ur20/LICENSE.txt new file mode 100644 index 000000000..7e7279039 --- /dev/null +++ b/ur_description/meshes/ur20/LICENSE.txt @@ -0,0 +1,84 @@ +TERMS AND CONDITIONS FOR USE OF GRAPHICAL DOCUMENTATION + +Version: 1.0 / release date: 2023-09-01 + +These Terms and Conditions for Use of Graphical Documentation (the “T&Cs”) govern your use of Graphical files and documents*, including the contents hereof, (the “Graphical Documentation”) provided or made available to you by Universal Robots A/S (“Universal Robots”) for the purposes of creating simulations, visualizations, digital representations, path planning, collision avoidance and algorithms of or for Universal Robots’ products. The T&Cs constitute a binding agreement between you and Universal Robots. By accessing, storing, copying, sharing, opening, or otherwise using or disposing of the Graphical Documentation, you acknowledge that you are bound by the T&Cs. + +1. PERMITTED USE OF THE GRAPHICAL DOCUMENTATION + +1.1. You may use the Graphical Documentation for the purposes of creating simulations, visualizations, digital representations, path planning, collision avoidance and algorithms of or for Universal Robots’ products, provided that your use does not constitute comparative advertising and is not otherwise unfair, disloyal, or disparaging to Universal Robots. + +1.2. Hobbyists, students and/or researchers are allowed to use the Graphical Documentation to create models or similar solely for non-commercial purposes as part of their hobby, academic studies, or research. However, no one is allowed to use the Graphical Documentation to create a physical model or similar for commercial purposes, nor to create or improve a product that is capable of competing, either directly or indirectly, with any of Universal Robots’ or its affiliates’ current or future robots. + +1.3. You are permitted to create a product or solution that simulates, visualizes, or digitally represents a Universal Robots product, regardless of the origin of the underlying software, and regardless of whether Universal Robots or its affiliates have released a product that competes with the underlying software. However, you may not in any way use the Graphical Documentation to create a product or solution that simulates, visualizes or represents a product that is capable of competing, either directly or indirectly, with any of Universal Robots’ or its affiliates’ current or future products without Universal Robots’ prior written permission. + +1.4. You may share the Graphical Documentation or any whole or partial copies thereof with a third party (i) if and to the extent it is necessary for you to do so in order for you to engage in use permitted pursuant to this Section 1, and (ii) you provide the recipient with a copy of the T&Cs. However, you may only make the Graphical Documentation or any whole or partial copies thereof available to the public via download if it is part of a downloadable software package that includes a copy of the T&Cs. If you download a software package that includes the Graphical Documentation, your use of the Graphical Documentation will be subject to and governed by the latest version of the T&Cs, which can be found here: https://www.universal-robots.com/legal/terms-and-conditions/terms_and_conditions_for_use_of_graphical_documentation.txt , regardless of whether they are included in the software package or not. + +1.4.1. You are not allowed to alter, obscure, remove or replace any copyright or other legal notices, trademarks, business names and/or logos embedded in, superimposed on, affixed to, or otherwise included in, the Graphical Documentation without Universal Robots’ prior written permission. + +1.4.2. You may show the Graphical Documentation in whole or in part to a third party or the public in the course of you engaging in the use permitted pursuant to this Section 1, provided that you display any copyright notice already contained in the Graphical Documentation, cf. also Section 1.4.1. + +1.4.3. You may show graphical representations of Universal Robots’ products based on the Graphical Documentation to a third party or the public in the course of you engaging in the use permitted pursuant to this Section 1, if you, to the extent possible, display the following copyright notice in connection with such use: “© 2023 Universal Robots A/S. Use hereof is subject to Universal Robots A/S’ Terms and Conditions for Use of Graphical Documentation.” If the medium that you use limits or does not support the possibility of displaying the copyright notice, you may in good faith disregard this requirement. + +1.5. You may under no circumstances use the Graphical Documentation for planning, construction, maintenance, operation, or use, directly or indirectly, in nuclear power plants, missile technology, chemical or biological weapons applications or flight, navigation, or communication of aircraft or ground support equipment. + +1.6. Any use of the Graphical Documentation that is not expressly permitted pursuant to this Section 1 constitutes a material breach of the T&Cs. + +1.7. If your intended use of the Graphical Documentation is not permitted pursuant to the T&Cs, you may contact Universal Robots via email at legal@universal-robots.com and request a special permission to engage in your particular intended use. + + +2. INTELLECTUAL PROPERTY RIGHTS + +2.1. You acknowledge and agree that the Graphical Documentation and all intellectual property rights contained and/or embodied therein, including, but not limited to, rights under the Danish Marketing Practices Act or under similar rules of law, patents, utility models, copyrights and related rights, software, trademarks, semiconductors, designs, know-how, rights in databases, trade secrets, and all applications or pending applications for such in all cases, whether or not registrable in any country, and all rights and forms of protection of a similar nature or having equivalent or similar effect anywhere in the world, shall be and remain the sole property of Universal Robots. Nothing in the T&Cs shall be construed as granting you any license to such rights, including, without limitation, any licenses to use Universal Robots’ trademarks, patents, or designs, except as strictly necessary in order for you to engage in the use permitted pursuant to Section 1. + +2.2. If you create any derivative works based on the Graphical Documentation, Universal Robots shall own the intellectual property rights in and to such derivative works. The foregoing notwithstanding, you may use such derivative works in connection with your use of the Graphical Documentation in accordance with Section 1. + + +3. NO WARRANTIES, LIMITATIONS OF LIABILITY + +3.1. THE GRAPHICAL DOCUMENTATION IS PROVIDED ON AN “AS IS” BASIS AND UNIVERSAL ROBOTS MAKES NO WARRANTY OF ANY KIND WITH RESPECT TO THE GRAPHICAL DOCUMENTATION AND WE HEREBY EXPRESSLY EXCLUDE ANY WARRANTIES WITH RESPECT THERETO, WHETHER EXPRESS, IMPLIED, STATUTORY OR OTHERWISE, INCLUDING BUT NOT LIMITED TO ANY IMPLIED WARRANTIES OF MERCHANTABILITY, SATISFACTORY QUALITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE, NONINFRINGEMENT, ACCURACY OR ANY OTHER WARRANTIES OR GUARANTEES THAT MAY ARISE FROM COURSE OF DEALING, USAGE, OR TRADE PRACTICE. NEITHER UNIVERSAL ROBOTS NOR ITS SUPPLIERS, INCLUDING – WITHOUT LIMITATION – ITS LICENSORS, MAKE ANY REPRESENTATION, WARRANTY, OR OTHER COMMITMENT REGARDING (1) THE USE OR INABILITY TO USE THE GRAPHICAL DOCUMENTATION; OR (2) ANY RESULTS OF SUCH USE IN TERMS OF CORRECTNESS, ACCURACY, OR RELIABILITY. YOU UNDERSTAND AND AGREE THAT YOU ASSUME THE ENTIRE RISK AS TO YOUR USE OF THE GRAPHICAL DOCUMENTATION. + +3.2. TO THE EXTENT PERMITTED BY LAW, IN NO EVENT WILL UNIVERSAL ROBOTS BE LIABLE FOR ANY LOSSES OR DAMAGES INCURRED BY YOU, WHETHER DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY OR CONSEQUENTIAL, INCLUDING LOST OR ANTICIPATED PROFITS, SAVINGS, INTERRUPTION TO BUSINESS, LOSS OF BUSINESS OPPORTUNITIES, LOSS OF BUSINESS INFORMATION OR OTHER DATA, THE COST OF RECOVERING SUCH LOST INFORMATION OR DATA, THE COST OF SUBSTITUTE INTELLECTUAL PROPERTY OR ANY OTHER PECUNIARY LOSS ARISING FROM THE USE OF, OR THE INABILITY TO USE, THE GRAPHICAL DOCUMENTATION REGARDLESS OF WHETHER UNIVERSAL ROBOTS HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. THE FOREGOING LIMITATIONS APPLY REGARDLESS OF THE CAUSE OR CIRCUMSTANCES GIVING RISE TO SUCH LOSS, DAMAGE OR LIABILITY, EVEN IF SUCH LOSS, DAMAGE OR LIABILITY IS BASED ON NEGLIGENCE OR OTHER TORTS OR BREACH OF CONTRACT. + + +4. INDEMNIFICATION + +4.1. You shall defend, indemnify, and hold Universal Robots and its affiliates, employees, and agents harmless, from and against all sums, claims, costs, duties, liabilities, losses, obligations, suits, actions, damages, penalties, awards, fines, interest, and other expenses (including investigation expenses and attorneys’ fees) that Universal Robots may incur or be obligated to pay as a result of your unauthorized use, modification, resale, transfer, shipment, or export of the Graphical Documentation. + + +5. MISCELLANEOUS + +5.1. Entire Agreement. Except as otherwise explicitly provided for herein, the T&Cs constitute the entire agreement and supersedes all prior negotiations, promises, understandings, and agreements between the parties with respect to the subject matter hereof. + +5.2. Changes to the T&Cs. Universal Robots reserves the right, in its sole and absolute discretion, to change the terms of the T&Cs by providing you with ninety (90) days’ notice. + +5.3. Obligations on Legal Successors. The parties undertake to impose the obligations under the T&Cs on their statutory or contractual legal successors, if any. + +5.4. Export Laws. You agree to comply with all applicable laws and regulations, including export laws of the United States and any other applicable country or jurisdiction. You agree that the Graphical Documentation will not be shipped, transferred, or exported into any country or used in any manner prohibited by the United States Export Administration Act or any other country’s export laws, restrictions, or regulations (collectively the “Export Laws”). In addition, if the Graphical Documentation are identified as export controlled items under the Export Laws, you represent and warrant that you are not a citizen, or otherwise located within, an embargoed nation and that you are not otherwise prohibited under the Export Laws from receiving the Graphical Documentation. + +5.5. No Agency. The parties are independent contractors and nothing in the T&Cs shall be construed as to create an agency, joint venture, partnership, or other form of business association between the parties. + +5.6. Survival. If the contents of individual provisions of the T&Cs are intended to survive the termination or expiration of the T&Cs, such provisions, including but not limited to provisions governing warranties and representations and the transfer of rights, title and interest to Universal Robots, shall to this extent remain in effect and be fully enforceable also after the termination or expiration of the T&Cs for whatever reason. + + +6. TERM AND TERMINATION + +6.1. The T&Cs shall enter into force upon your receipt of, or you accessing, the Graphical Documentation and continue to be in force until terminated in accordance with this Section 6. The T&Cs shall automatically expire at such time as you are no longer permitted to use the Graphical Documentation in accordance with Section 1. + +6.2. You may terminate the T&Cs for convenience at any time by deleting all copies of the Graphical Documentation in your possession. Universal Robots may terminate the T&Cs for convenience by providing you with ninety (90) days’ notice. + +6.3. Universal Robots may terminate the T&Cs for cause with immediate effect in case of your material breach of the T&Cs. + + +7. EFFECTS OF TERMINATION + +7.1. Upon expiration or termination of the T&Cs, for whatever reason, you must immediately cease use of the Graphical Documentation and delete all copies of the Graphical Documentation in your possession. + +8. GOVERNING LAW AND VENUE + +8.1. The T&Cs shall be governed by and construed in accordance with the laws of Denmark, without giving effect to conflict of law provisions thereof. The parties expressly disclaim the applicability of the United Nations Convention on Contracts for the International Sale of Goods. + +8.2. Any and all disputes arising out of or in connection with the T&Cs shall be submitted to the International Chamber of Commerce and shall be settled under the Rules of Arbitration of the International Chamber of Commerce by one (1) arbitrator appointed in accordance with said Rules. The place of arbitration shall be Copenhagen, Denmark. The arbitration shall be conducted in the English language. The foregoing notwithstanding, Universal Robots may seek preliminary, temporary, or permanent injunctive relief and other equitable remedies in any court of competent jurisdiction prior to or during arbitration and may enforce the award of the arbitrator in any court of competent jurisdiction. + + +* E.g., STEP-Files (ISO 10303-21), Collada (.dae), STL files (.stl), GLB files (.glb), GLFT files (.glft) , CAD files, and drawings. “Software”, as defined in Universal Robots End User Software License Agreement, does not constitute “Technical Documentation” and your use thereof is, unless otherwise agreed with Universal Robots in writing, governed by Universal Robots’ End User Software License Agreement. diff --git a/ur_description/meshes/ur20/collision/base.stl b/ur_description/meshes/ur20/collision/base.stl new file mode 100644 index 0000000000000000000000000000000000000000..c8940241e63506f90a5cd39a7f557764e6bbd5f1 GIT binary patch literal 21884 zcmb7scT`o!_Wwr3hGK~|u^SK-V`4!r_s$utfE`7VSQ0_dr!+A(FrwIE)TmJ-mS;g@ z4<&l7oIA$e5=-<2)SxjcvBZ|B*nj(8zl-&mHQ&dluD`!oC8j=j3~ z>LXH9QycVXAJ(}~Nc--t|Kt1*&cFZf|Lt%iDpe-f-pBpicA_b2bY8M~%a$)_eu!mO zUb6U&|2<_~h-J(6bhDbXWh!|uSt88hx z|KWfC{?|71xA51t>HKe^>{=Cf_nG0g)5-8*bjY76xzYbXHR`$BT-tTMCCbG}ZIjhD zxk|;hPR1I)*S2R*wh5;Vd@kA}8qm;3?WxdS?fI}(Kw?(9ng8O5Ik3V?TaPh0rr^K8 zhH3v8NAI~o_D)OAyGDM6N6I5MDM=qKz6GL|Jrd-EZkguLrP;>At53!I(|NS#Hrd>Q zcZ=mO#_j3F9_n6=@A#qJt?+l34VhacD!fX|rT7p_ztBhGk4tVQC4^YeHqnTmQ`+2= znXb1x*)uJ7)DXKF$Irz#jc`qz#VjwCwb)NZK^;q*W*V|3_JG#wf-!i+L zZx?NhIyQ4p49~-;f7m0+=(%!t-{_rwPDc13yBSy^%@)HboHevZ)Uk!!_4)cCt~vkk z+G?}GC+%FT1U=CiC3>Xnns+VfUkpUy>LGfztEwsa@AB4E)ri;UGG3>&LZ3mLesDE5BU-dFTD^?9=7?yqard(Wg{Jk5G*`W|($<{+eebn2iM<*bm~Ym& zoNO8{#)J;Je%~B^&ov+0pUo9byNwbE?5jW;^3m?+20g%H4b3G518c>f@GWw49%8E_{_|*8eKQ_TC|BHb^NnKbf0h8`REX z&Wc!V#`BnnUe5GU$F>KmHJj^OTSn%XJ^1f%RXtu|93#3sK2Qxm>7yPW*BQ8$aE%eo z=_QnM_f}7i`WtAYy>E^g#DB5#Gi=BvnoO0{-F{)}(YlWUzIdE$j_99nQk^sldZMrP z52t&o=9|ORH+Py_k+J_$vUywPo5w4!v>}^lVDjnQ3E#9fAMo2n20j<(hUnhr<2y&r ztmBGTm$Kr_ZfEA23H%oEjbdCOy5JUSpE0_+bG54O+pYDZ+Bg}7 zm)t}+do^W}e%7Krq9CtX;{DO7vWm5Qz@leqwi>&N#3_EGh{7=u6}gYL4=9`JidSB| zH!8o8VhYDZjBwxa-uPqn*R7q=j$>l4f%gBze)BH|`i^X(B_9Uc?Y63}9d(q)5fS>x zoRSt|!Ci#2NmT1<7yE^E_gyxSfhhePT=Q$yc7I%N-#n3$ir^dWdYI zhD+S#(ptf?$5Y(~dWCGFGrJRIVrH@#8MW2uHUGKD4L#C!23yA*<#b$;xPB%rckU9W zR~>65%9tq=%q4d+H3nuf$R_ggOq8FNo+KW7W@!xfkwv1^*)&@}wufw@nTuj&rJgoN z|CFu9ma>mT=ngk?52Mf%-A2aHR9P|PE7P3YB;c97NKAc}mfMJ9B4$qRrCx|oYqp)r zrt#WscU;A1Q+LOtl6Z6E_tc>3^ZV9PP5ha{-@ zN!iBw8ELr{EPsMmbsu;g1VTjGZ2M2Bhi6VS!Vkl z394bL&Oj8}BN9OgDmx}yH2TJsQ=3hvr`b+&PK}u*W}HMHbXhO9jZILK`(+z_XQbKQ zs`HMJtC>dcX?bQ`iDYxYsZBP_eK$`kGz&N*c;<=>e?JaVi3i+OJC7`l zfgU28=wl!2?#4eQxX!^F{k}8DyFJhSlw%^I^bGmXlY@3y@_SdLzGKTbM{$iaWo3v3 zGfO?TCm6l$4cEM_ijaXQ%xa0YEsRzlEV|}6+~w>ZWMIaM_K3P)2veIoc&d+EmfVXB zd@jxn(Z2jJRo3RIrZzjH*+3N9;|NzSQUzZta3mGAHhy`NXa2e{+5GzJ3>)UxI>YLpIU6Dg)H1KhHZRMt-L;aQ>0ar-2Ao?_76Rj|S-soO5Jz^qC#1 z7Q0taFYfB&K;Q8#u#Fy}>cT@0)z)Uwyh0S(BU;rZ*sS9op8J?HvOLaj8*-i-*dR^I z8T1(psgHqb+SZ$v)h0%gRHKC1*h1E=ovkqt zrDuK3Gg`vtah`$nvHRonZ&vWv2AlWbvp8erwESKIBDX89+! zUHvZxqVycD^uob1X8B&@(8DaF^OKvRbbl!h@W|1IJ|EX>M#y1~pN#&wIs;KSn?%0t zK9*&>9XGz2lC9Z56x!q1zN4XE*z3iv+Q9olO75xob}{-NwE-#!LP$o>11Ged_hQGt7>LrVi58_(j4hXk%Y&72jJT0*Vo~Zt@x_r% zHqOT%uZ^A8xgY}Z#2Mf&#yxLKvz*?PXTtb1vzILd(SjNy8m`x&^72%?*j?bP%tN2z; z_Mi={?)8ek^2BS7f~C=FWC>p@GSCxb6NU0=(~(b|u$s*^8~9w*XNZPQSnuc(pQK8b zkI-x&DmBl|{J7^MvlPD(-seG9$Abp3YFyh)BX*>l$unp!=NZI&SI=IzmQ8V-xjbAo z_RP^3h{EigsJ!uDwbyuZ6FHYG|``>f*rOhDaw7*0PB3Nh^p->GS6_GfxhFI z_&n#hevjjO)?eiVkbx-FwTQa#*}*!4TGT;jAPTE{qVM+3G)pC=s&3!5(`+DWTdkO# z%dR{(o7Hf>-HK}~s2?tbsz<%Njf9!$=BqefuzM>SPmud|IIhqKL2 z{8#btCL1bKdTmg{=L2;!$4kY(qcaeN_J}CLTSd%jp1tXF}D8$m$+!EUJ zS~Lct&_mW59LE2~vz_Ql$#2{CN}K3XCXj(BtfP742?fT~ zwL@iQ1;hA(wZy##3&lNNS9r>xGDWm}!g^z6e3Cqz{=EemxDs*oa86x5!>DpGUheGI zQnP_5oK2!KMQe?}o5afp^>wchg&q=Z3aI^kxts4h&vUh5d%CFMc2v;V5DO|gx>6)o zuCX<^GS{|~l_F$d#)@pB2c1%6#*JxW(R6=f>80o5V*KJAKk>=JS#hyOhWZ?l`t4dBc&lI%Oyh0S(BdRtc zR=((Lb9@=Q&8W&*OesDKtMEC9DxR*~)u|CHYq;ASo+49YAPUzQR}`9$-0k`Q03enWS}RkQh+Y{-<5eg%WbIU%G-BRtob-?o^alVVNQ)1 zIZ@i+nSutVsMBtKMvFS-cMe?q+}yV)!-g?&{OL4Xhv*`6*&L^4xw~MB*mo~c)hf3| zV;~AuL!$hQ>E;u*ks)*&m^q<6zW=y8-L$q!QL%R{nhneokBHF=RslVGbU9nu07M7n)`JCN6}&i zp2(OWWOf$cI8{3O*APPMs3K^NCUd>>XEkrrhQdBNSpM+<+4IBsBBbq;G zyefaPlf$+~w}H<^HqqheVJbLyg(Kk8t;S)lh)#@fGl#K4j|`lD9{KesHMjN(M`^!I zje#hA&I?+MP$NRdIi7Ouj5ZL3x*sRVjbhcSN>;}fn{ES9I5(UjXT+*sj#(W~y6WRV z6po1~VQhW*xtpKt*I=WOI5S;v#UdiOV!@j~RCI`{-}jO-O2|1U{51xmPzmGSk7=dl zl6oOBQR+4@r$T#N73GJ?+g4Bc_+mpVYr5j|o$2C#Tn}QbMTL#%{P;kbaMDLszN0e` zrF*rcmyqY&y=CALe*wlg%PQTT{#kGaWqCM;FtY#Ohc&Gspy_g*; z7r0lDFW)NL#S9z=+9v9GJxY$Qy}~HZ>*^rqB|naE6Yjhc@wvKEG|_j2Tse50(XMii z#y}KmXGEVgij_uXt1+6_71}@)ubAR|jwroaiae--j7lj9)_HtuxvwbA)|K};o|dRH z5;f|aB0su0O*Eh4Zy*Doi`gJ&OG&BHv-V7}u4sm415tXOcpx!V$_BHgOztfhZgk*R^-!#;ehNTN;t9 zoX4<&UUET(4Rt2ePKat0t#y3l6R)1VYiJDAVUSI*wA6B|H!Qx0~H-)6Mgl! z)p2ZDtO_5kGcadBHj!JiPL9aC<5c$>7R?4`7RV;@tkl`@_rURL&rp5jI9g;Ajha?k zCDsd38G##}-3eyh@FV73?q@)KMpsx4q`RxNb%NF2d{=iuF#}O}2hADT=JG1ELnrmw z7p@M7Vg{mgEo1GGdg}RuHfm67-3Fpi2_Xs_TVD-v^W*y>eH@6wG4b8qn~sjvOUFw~ zhvvqgtOC~W@kqo~T4`I)D`r3It=&0x^?#g}duS{7AyjngS6ymnIKFjHkPC+BjEP)5 z1aTFyh${$W6XnIOcPvXxk~ixAX+ayK_6e1HEJA18b(nz_@~JqUHzII~qhL$vMr+ z@A->6F`II|=IkBBS;O~6^lt6%?WdRRcIgbrKosgsTpRG+dFH}sS@Tsz%?6^-9xL=! zRtcZ91Q{EfZEWHw&7B-#2#*{UHhtui&SZ#M@d+|yvCcpgYI1xt>Xt3u<9_FD+%1AO z5QX-LoHqcEi>?|UWYpQiRkhiQ0>!7iCt|sWaOPv~%kfUr^fIF9i(*x^o;G91+YTW! zY=@hu&5;_jd;MlKC^}xbmB}!Et7vid6csbBaA(Cnz7uT0w!>-F`+BHxngw+~RPl($ZqLcxKQqpj&6O}R5QSsnT8*{WuRT-L`A4@c_gQLkJD@iwicPO9A&Ud)oae|gxSJ3HdQsdbSVHCh(dd; z`~1|!xY-~@P3^5S5QW|nCH{Tc@3Z*IuKtqnsCMGv)zzl6=MMEmR1JxaP0sKuacz`K zfxL2buGp|M&W!wr>WFNjsN4eM*{Pv&?8g@4z@=nySLTZ~oV}t_h`BGHA00ephYMk{ zyTiT*8K}wW%H5o&9`Zy`sO-jfUdX`bVm?o_tXB)WJ#W6NGt+}r&c@DtK2h(?ME#Pp zr334Y+8h~LA8ft{8HmC$5p`v)WCQQ>H|aYy270KEqr=2&#yjcJ()U^uje*ZaHqq;u zKJxJPKxwS4Z%xWd7yK23Xu@AXVBU`UC7+xPeWY2Tz4UqTQ2;U!g>RbckFMUbgO4GT zJ-rQN;2TAIoR_SvATuw7%7LLe1ARv}QQzsFGJJEGTpFi)g`OarC`(34dFG1aQhqa| zV!M2C>*r+iUCzQ$-z)JvPkcHr*{sHAJ5l@Scv-qkhNH8m#o+iMb{v-G8NQo91}cR_ zcl?LR#dTLWN{-#8F%X4%DbY8FhRT}v3mnhO={C?4w8x#~2c=kDVs-8j&H#q~S}6Xg z7HB$q5>e|zHIk@>Z?xRud);w-gjWDE@GT&ld!5Hc%QkPWIcjD5TakgDAe-+dMkdJ_ z^VU0#zR(${cp{tE)z&0=xAHp2QF9Ha_5;bmOIaofzL%YQPbvbyDpWnxOCB9;@g=+FRym#qNtH# zy~AtQEmhq2N>qO*XBzdEbg>tdd~W)l*knVER987W-bkq^HTXM?fzL%Y_e?|&lVyTe7_%a`Iy=wAXzo7A z=Pou};i!u6ZCXaGoOsM?bnKxs5QWt}(GR2I<A;P*|T1T z5yQGDdWDez*<7Cw8ZYag>|_|Mav}rO7G!fwd_7LyF4xKUh&35xpzp}$armxq*sn&( z4DJ!GengtNe1@FmRf0PeD+{6(lU6vkIflu;eK%_iMClczgSCu%G4XOufxpH;lwKQ% z+tWqERw=UlJ&Td}z^hHv;^)G_Hzt^?W8KDC_?qdWU~r0T5$LBe5QQ}y-*evR=t!M2 zURE3LYm7OamfJD9NM!Nt3s!XKA)ji$Pch@}CCVk`w`dHk+t6Fi+h9fqwj&RS!NPXmp z!neTPxFvpfbl~%Lt@f&pmtLxSh>-7Wvlx&0JAgSH zt-J89#pmLiCi>7`Pi4JqBLh2RY79i-NzGqQE-a@`RqiaW4b0XUh{AK8^WBZ%s@t6N zMx{Tp41;gtKH@&hI(!rNXiA)Zdj}bpoi>L#sF34j|;|xUYj)rqI9n+kKmi1&Nd_CZFhoMhI=g&-*zVy z>jAoIP`i4p3N2+b96W=ZpBFO_rGI0x15xu=5DnL@9m88AE(WsIY1|8Uxh` zWb^Hk?+RnX)hKn4PiM4I^9c7av0C&k?|EeN_qA_28t0adSHnefV*}?stOA?OdF`Uw zqU$A(Z*(-$=Zsh8XTBN(M~iGCIm>GJmW)%Mb>6Ho&_iT%pZ=s3#%;$il@qEna2&|y z?>VQJlc(P6tg7;N6HhsFoy}i7mEzH&4uk3r(deD^r2FeOs&6 zh-~hmpS9gTWSl7_!qi4nd zdAIO_L-yXRF;JP{NL0+`aoh`*QC_9h-hVLALu3=3D;+F*?sivIf6dfvpeM+7b%m*b z!<~%p-*$zWioeaM%o+gJZF;T7U193hiB87^?(tGLS+Q-MKFHbQRm{Nn zsK>lvcgsriZBJ1#15s#?&%qi$I?g0S$gt;G#*+ThY{FlSl;lhXDcTN%thb!EFtUV*{;L*3>5k;3Zn-28cz=2jN(m7C&oQuege);(gT_DA zy+Wj&R|(oclzv8ie9B#Qx)&rXRnF2Fh(Zs!R?7=g%QD<$Eca8d5q5Sr3^wC{!h8={E4W7$1o$v$h+=8gIu@ zjRF!`4Iaa)aGMs4 zkXIt2^vKY!hmcR-c&XY_XCMmS8~7E6H6mx z&j`4d}?d+W4_HEt~grczf;wYl;Z$j?%yd|b~_avWYc#!8TeSb}& zh=xUHZS8f7y@$=A8kxo8*W0Q@tWzAhe78upXDUeZ#JrE^GmdrmV51WEH^md%v3~N` z9=AkD^Tg{+fBZdepSZhkt|VS!xzCBt@;Y`?B=r)+sWZk2YT7$LUd(JhPADtYj%8dU>%7@^kvJu;l|KfXU|o8d+Dgtjk#{kT z)5jWV{Qv0ps^PXbvD-WW!QC+$-`##%tMTujFn`&D= zLINZ7|3W~OE?w5z&%C%QF8Na*^60jL(*!3{gSAmzdIu|eOFa*}jT>FacI|sayu2zd zVnoYV^U`!Gm4GUf%4I|)ZELTZq}aqQDap{bM9`|kdxZ*P9pZ@{`=VhP?}W+CVo3|_ z*X?p8A@dNap>6FcVI9RrEh0!b`wMJKJh6D}17%A~H(ISz(j@4+5%QGGg)Mn_`5P z7~b26wjS0?+jdJLN?BTc67pGShfs4yJo)<8`pZ8Es48JkGGlp!cNi}t6ruM;dNS8X`{vE+ zychbg_H&MvSC>{>hIdX!@mDze;w+6&Fe9G-g@7tu+Jue42<3mjN_=K{*?6#i_&qjQ zR%hF+!w)NJED=qGt^^ zD<2L=k&~NE$n**sV$sSdvN6vOuRYF){QRS2R@$0$ok|_`p^E$=kha&F z6>0D!KZTVKq0&%iF|)LhpxPz6v}%`-rmi9y(IrbwBlLd}P^C+&PeSOOQ7%bhy-Cdj z+Ej3M)}_^18=8iQ<4sJX1I0C9N*$Af+ZrTy9%H|9uHn2T?5M`nr+jZl4^H%TV6gC>T&5b2+ zzCvivkSt}S)Sj9+@B~!B*$$!K^L_DyLoX%u3%EL%iC#wwv@KDWR$E`K*^=0(BtcMn zFhaK&5q9|B1XStLYX3)Q)BYvO!AU+;?2{|$W=pmGz*Yk51|hFqOO)f|eCWclJONew ze171thW_}GCw|zzCS6+KL^9j86x6;3`yK3$2yJ0RtKWIrJ_re@(*1i`KQ}OJVNhh%`p1C4&T1>HfW}236&&3JF@9T6Q!LOV`&DQ&~yE z3ZDzj_L^$be5vaDRkJ-)aYLH=t)NP0O{(@MPw0QHmYLvl$4VWupbEBjp73aNC*wY` z%T)8wl~=7nU0eG1w=z$wnz6BFeeHWdRYd#vvCi#qZ&_~@7OED?7$4|YyefAOhh7#UneC0 zt5nukr(_&#x=Nb|RKf9s&*NcW$I*`%%>lQAsBODY zCER)@L|ru{YLDWHjJ8MY+7F+dRmyr4RJkVA73a6At(^^c;;M^mcW7gZmVhdq2TJW9 zJkkGr5dPJ6nRY(c)vem^;Mk>0m)VKk88O=A|0YzG?nz~>q(+4p`%OE?WPM@p5&owo zs(HY1moL?&4MBLt;3_sL&dU|J!aDsVPVCJrne6B%aymSi=79-*Djp$g82Vp zq$QvV&eS{+QNLP7$mk{7QbAQo<(6`zB~DsvfG2W8J7+wde@B}KR6(B%Pc+{VkP$`u zY4d<8*p7K(@F5M3^}9$qTwY@hYYo;W9Agj~$%wwb7nvQ)R$*Xe0#&+yFKbt!mli3D zhI!K#LA(V3XMLSDSY`ptJGV%g=iyDiMDYYvK}(j|S1tAJjUHy%m9Vh{w$a=_b7F1Q zc6Fm@S*gyL#w(`GhrIpJy)^iBVcqcd)kj7c{qZ_O0;+WXUN)9YnvyFX$kgCB-VYDM zu@8=F&>CR=?>~h8oz9%62&&+`i_n+bpQPDek7G_I@4?n!0Dfoe{8EH%{HiO}lPwQ$wm)uqc?yHwo?A5;wS(*skj z|3;`P*jL!sePN6B_3BeS3#z=E8zojTH6<^Xr*pn(=(A>ihDMe+D7X%NAA6T0peiQH zQ>?PZL+e#V$a8BOI;qe?n*ai-c_J44Eo4;uYuFjdh{M6=I!DMsM2|a%e-pJ z-kP=(dhfDTtv>jMaMXqtCqg?N6Kpnlw9#6YPz9|_o)|OMHKR?3QX4f7Xcfb@1Zjj` zzgR21{9`A=eJ5R7-L-BMGsM4iXPccG`%YTs^=au=8q16X%MqRpW^m$kA zi!|sz2vwzfQduimFx&`tb1d`F!x2ZPQf*OPx{R2}2oFa57-?z!H$qjxkqDtiY|qQ> z&z{$ph&Zyg%MS_8dq=2Ev?EO#*^(k2mvEGhz-S)R6%aP^J6#vJvjvY)@tU z0CU>Kr89*dLAX}{eKiP~Tp6KMaW|*ehVTSb@%B~yA|HGAt;e&zt3B$^9Hr(C>xTcj z?-#pg)Ei&sXMm#&d~;Yg%$ls_oUwmSoYpe|38>P|YGuA~TDeF=D8FA}B2vwzf zQrX^Jm#8sx?YcKw`$}g=slEm1bI_&BO4XMUR{ue$D&3RH?5mi`$3*uf{xqOot^_^X z(3`FE$(8K_I1WE1b`JKZZKm)9RO!aYvOW4^Kl{*8`mOLMuPN!e@~U+JXKH?SKE;R; zj8I!UB%n(7?`3bEU;m4O)~~d=7vaOTcDT<8_dgNZ)$oh*tkEg!k$)jn8&};WRr}3d zw&s+WCmo?Py^ZLZp=F~eT;1vVo%&9?bXloJ_A#PPj2QjplJ(yRRi*yB&U4GW&Y6mM zyq_O+4!)~Eixt|ty02RnGchSc5kETk(O+zKh6GgU>ZZ*1I=rBUz2|)wTjpn=a7_kh zQQikIS98sF`mOwb&Cbv+fiyyKZ_C?vpJ4s3JmAQ{6Qle0&3xdZdTgV(*%{V3-v`&P zADh{jTKtQEEd$aBJ$(BpquX+$e-W@xKpLTwHAZDcM*94VfU6WpBV=Cjb5`5*aoRVB zRtDT@fHXo&>fOo=`pxXhC~zH14ng0lfnMBmtK*XNBkrien7 z&H_~TPkG{mNgtc8Zrjy;HO@N-$9bOUac!c_<;RUwKLa-#Ks$jawng|^m$x&}z6Vsn zufP+VSMJSxRy9G}5+MOCB%NQQ%-45+?NVE_;!0U+so!~ z{R}*D{=Q|#uX5SinG;5v!I&AigUQ-%LnZy*?2cMb5mdpwG@dXG?ritg?xb2O45N4C zP){*@orgA>h9|DBTVNZIIYdi9)%ICYVrUc7zYyVV*JRz%8==-YhN{^1apJI?XR;cl z#pm&La-{tg8&|Cd5~>PP;>D=@0rJ0N?i@~87s5{#OH`N7h%wZSoKoX3dv z!+8R#bZgwQ-SFHqJ~-NWkrL7`S4tffCz{rMF860K9vyGSi%vFyvKr|EONh{&)6Bwf zTcqrB;R&dM@5f?TRyUwNB^LBnQm&+1VX4tHur^^^V0E6 zrMMSf^vu4yN+^9N1hfr9B^^r++h7#zFAW#uE2Hymlg5l{uaZ3x|C@uEAA zl*Nm}cBMtX2=Xgr=$|O0rccVz z)Sk_7?KGZ%Dj36rP}QK57V7Ah_^V?YjNX8LQMfilsBoJj9VnKq)nF8ot{15u4_&&f zM@27nq=QDaq}wXD&Hfvqs@7yik)1nCNEy*(eLcK+UROGN{#^yOS6!{C^$hDDp=TTF z;rVmA(p3w20;*s;W^oy>t?9H12J}{Jt^{+3Wrw2#Le8(OsY68rI(j)zKoyK)X7O-u zO{nMls#I{POyOt%#}epgLTJ_1c64lE75buLC60h981IEp!`h;y+OE=kFCKw42))^` zHW8}R-v}p;PP6{qzZcifVc&){Lb;3x-nYVL++PTt$Gig@W7PD0eKpRq^9_GXwO!Tu zQk)J;)jKsx8zCe+w-fn120EFB8mO1aXF3(P9Z(ny?oOs~GW8re2 zTjJ^WQDUbjZME^uFn*i)^bL?ruWlc;yGu|7BcgfY?&j_p3#W`rSKkGyU_3QXoL$u{ z*d*hh_}xC29$%f<9fIa5G+!u{5!bwp36BJ;FS3wNA(Mq&Mqq z)Nchjk16$I9~BYhiyYLoYG6Q@o-SJpivYFcwj23XAgM7{YqTM zyW2liTNFdpxEHac+0Ey|+J6xv2b*VPeXne*z6Vr!1jLij{6OL2zlihiEHh$$t<=Ud zK$Z0b7OUGd+V07Ppnx zoB44Uj?N3;ry?o;44pd5>J_5-Xm7DxJ+(=5J55 zj*&X(`A`F9w?h^5e(7w+GXK>p+Zahx)rTH+;0dVW^Qe8K0XFz*L7xuFmEd{+z6X3i z=6gNV0N?*^LDSf`f&^6Q=Jqm+ERjXYp1X2@v`NpEPH$qpXh5``+OA;hgRK&w^^CZ6 z?Ev|a#uHEl`y)GJP&^LrnzlfC;gTk$UXK%h)hH5F`vcA;{8+NoXEY9XnkUtFWGfax zKovY=gwPWf9c^^wD4P)xf@O#Aq)V4-cLAO)%S3UG<{J-ws)ss(b|C|x3dcFAyd#HkE0eIpwBii=6Z{4B7N-d!~R{+l&@Wh%E z5!iSU5i1286`=}#AD*zcikBYk8f?>Do=KCyPCnd^;B8Sa%XlevJF*%37eci~)YxO* z_IVp#AoZ!%kDiOXt3Z2D*Ams$gs!!#s~3cBOfQgTmh`1ZSo9|(pbD_1Wso>{~9&8s-64MR2uLrdNsACZE$F0ab8k z{C`AFn_w$QKo#6qFC)}%rKTVORb67PWUA*))}Lf2694=cg+spQAAtl^!E=89Bh(Zm zpbDN6{2x)-a5(oKPz7!6{}D;)8#7=YPzCMz{}E~m5>N$e7NNuJUF>9bEBQw7*!SQP7(4_fP(tk<)KDmXLn z#G2PJ+Q`qTzNwi|1>+uh!f$esb}WfX$xDYS7&XZgb6;DslW|cv#y{Nxs^FXR#ENb0 zuxI6}v~Gh+6t*Q8Ed)Il?9EL~aaLhfTCs6uj({rYpF^nGAU7QM{xvV>s5r zJ`d+BgaQ_s(xLuUaPwwWI0CBR8V(`f>Dkh?*6rzu$|e+gBjCKt&$a7UrArf6wWoMH zPe2v4CD@QtXOvW6Wlk@(=*(Fekl;P3p#eiBWs*5P6U7ry1#J|BP86&lbL&{sqg5@m z=Q&j?Og*;=cQ9ex0sB@StI6}K)^yZA2&jUw4G5iouvqjQWrZW}T3~W$hER|7)Ju2b zML2)Jl|DOh=(0lGSH}wXuVu**PzAjS%(s+3OnMjJ6*m;R;7lVHTgg1w>#xU(Fh8F7 z)oP^ls8Ls(KaeM&3i>$MF2Id+sZUBfJTTT2!Sc-UaU22P9MTBQ?LCRk3X7AjypQAR16uv?i?Drzhm)y(>=Nllg(aM& z@BKPnJ0ojWj1zd`@Pr83?L)5Eul_|5s^HhW|>PqiN;ok_AJ9^@-EmWy#wMYG(C>>RS?Nqao=r1aDUCWp1 z#u~ef)w^D6_gP@efGc|FZ9&Mdk3~l5;04+}VU7UjVBuOFp>JONeEUSaXH20`@r7>Dd1Usoy6x`S3zyA z6=8%28}q}p#Qyma*vC7M9J_mx=zL`AnzN+m|85P?t>{%tmf4~^m=9ps8S?caB~S%@ z4m=@wFDEsISmE%C78uTCa2*A`(Fpy#vV?e>S>cjumK*_9aE2?pJ3(!Q8g>)HKTDkTP%_JsrPUX^J-}&{l_gH#~8+br4>9VhTk`Y_}gHTnvCmCw%V|@#v_2+xizzn#WfHoXl>9aE?ZJ-LaC7!TuxmcS=*w_u3Pz6UKo=EEcQQODWT7)V% zKJvuDZ^s<=lt$uJ-J0e=6&$H~;^|s%yo{YecYJ(^TdP5foUe~IFDK!Ki{q5%YnF2T z9JVo@_)&c_j%^;NtZTNEI~fLRjVHFOaKz2VN7>BxXvwW6;0l6Yt2JYUk?AIDv!Ofz zRd8HEC}!&i?G9OuiFr1#4??RCT58NgKW(LU<>mK4u!AaS!|}wiLmIkvE3(n=eUZRA zhjR(6S!Mw+Vp8>Y*5&^}!0`&sE6mTp2(^X8IsZEk-5dq;L+J5{2zuP$D*0%dN8odz zzm?A;?`i}+TK*{6o100XN;i|Kvl>qvDw<5ITSqHD#6=3s1CA^3NeE3YH;F#&v_k3i zEtVtT*bZrC^(_jZv5)2}tIN;jJQHxd;)%uVgxg$?vJ-A_MAoHMzp<`WmhI6mWJKGc z|0bYHmo6K98XnQ$>aE^nRlS!-Dy~e_`eCZ+M`x*NkJ6=LgO*~JYka);X2$|C{C5DG zqrM#0;1?^NWnC-c38+%jYHda?naYUSMH*_e|7O<1z6z-soS?NuBF>GI)pVz)3&daD z#>(DZlSo0AXtDgp3^wkJWrXXH{H$Grcmk@_w3>%L+l64OqKI5Fn=Z)tl%b(M1!-C8 zU-n%|Br^)rvhFS$DRzoUB%$WB<)3>;i6cYR+b>Sd≪u7vy~X2LV-TT76P~q7t8D z;-!~*b8@78Gii2*V&ND2OW}i9lEl)J9*z-5ro@tuhXRH6>qm(j*d88>jam{f9a|Zd zbMqerRH+%{h9}g zzZ2ESfnVhv@rWB{ISnfF1XLw4LVXXZ!7xTdEb*nwI{wanzVW3ZM$FOHRH2UvQPZxk zL&S*JZAqHNGIHuvlvuj-F>58hi+$;nTIF(#xA6p2sp*r!2Ssso5hG3xey6PHvWfT_ zkERb&Kga|2UlAG~j3z^!KgvD}eR8(-T}X1bbRwwjeY^2#(^#o?&i<;zvKy1$O&G-y zP*u>fGx^0%OecqgF+%F_m=rgNCWEd;&=H5yvhwRtp}+N760$HYYe2V`Ii+t`kW>pmti@D?G}?C>4Cz#otJU~YOi3#_(6%%8hHVEoyrqX6?7z!y~7D% zpR1aOUg1xvQ^$Fvq2ov@8k>o?-#-;L?3_(9?{^T9+cZ1pku$jb5VC&%RT{TEnADvy ziX&jDU}@Q#r#RzRk1ff&;mzqb)|U3JHxLU}w6`kla5rLX2`xcW8Xc zm6dApA}5?2U`oQywcrS-iisZ~zNt`Nl-jv7;zX7&&J3zbD))M!^r;ai)|zS}7WOWZ zx3P5iwe^C1zgsfQkF9H#`r;=cl}LTPmmC3Au(SwmNDjhHM(>w*eOji(v60O6gdqOB z;3wZ;>0vH~!cWKkTz&{0SP+Cq_T4Sti(k$WuvDKT)$ z?*yKJDp*?P{je?|j*cPpTf$Uj>bBIZ={@I@UzSzKxQ2VO7M@*BN*h&_VSWgijxQkB zdWX&5B2!zP zcKGoqU0`|i2%(qKqm+P=QRGRhW#sn8?efoidG;_5m^YiF4BY4|HfY(7(pPGDc#{gP zx)S-uLb=4*oAlb#hm=0v><~0=4lyfgL}rJIED!Ob8O_kxP?K5~3TzErD*-e@wJUa{ zcYE5<^-*Kbi_7S4e9wFALS>LqQsr% zM&wt+y5hFDC~@)uQ=-`sA}00p6mO>tCHKWZmPf%|N8C2gkTyN|fg_;GtGuVUc<&%m zI2tkH%|u^%?a@o+!;KW#z55(u`@1zsy;WDtY&eJLKQJLp%ZG{$Zp4x0t)9vk&qXmJ z#=;l(-S$fPmXj&h?;a=W=M>7Cs%=H%(Q)GK1JC3Z%cHmwB4lXhi?ffuQf`RZ90A`0 zz8^wg7Y5O!XCR;C^PQ{ za|A3EEG_ek=4z;S`_tsgdZU~)=LE8|`*6AWJVC73Ie|>5Gf{r?WPxa2BZ;5~dbWMq zN3%DdeNRI#Ha$izT${%cQ1!V!BWBLD&p$MX5v@-K(Kj8JDP!k5%lp2?k#}$NW$)i@ zxjbOrZ04NoL_M1u(%5H(@}yEPvNmEMAyvzX!eK8mIg_0Sj}7GNhDB2aJJD=?L%QL{ z1CD?-2y2!_V9z(EC5?MhuW8jtKpGogJBE_5F-1bhnVrahtr28H)C4X+gl5Xdw9ktk zv|v#Uj)0|trA6pL=~u-`8AaXW4T+SocGjrf*0LPMW z=eNRvI&q{xOVFP2QkATkwEB_#9064&m1hWY(*&YuiSenSw0z|X%6JPGMeMkYJUGzI zA#&C}Io4zuF|`upuep8YHUJfwq%efp z4B-tTu|c36IZJo~s%|8)d!4uS79z{(v-ddNH57*~tE@b0KUjf(fy9#rapL8Ip7O69 zgBh{EQz-s0r?RqZ3Qs`Q={j+uk8wGN*#i$V;=nC`yvAm;UY zZtY}5%9@GzOYRt@=9%3b0af(|MTrLjKjysHT%91)@8d-JbhMXp;Qnr9d+;36t=99L z=3A>0Sm&@UF#oQL70u6XNYnjKDlW@Ak#Duyk^u$n37kdwc`z{EoJIvUrQePo=Lo23 z741#JUsoW#6RWaP6~%|rt@&=sriJAdSQ2Or@D{*}s&zhU z1z8twPhiXFos=lPbIEd$_8%5bZH^ZgA4l?UOFMyC`i#(HM74c90adX65xQ$O2wS)Q zqI^G?qQE+U)){YK-7Ow~uRi&rq*mF&5m5E{I$M7fl_zmA)!4U^4}KsWzI)IWJ1W!h z4hOPq=@26J7(t+w$=iu~dp?jDMi~EtfT~Zw!sHq=`xE8$5SB+w;!{yD97@;G%JloA zKp``;KN)4|PD;K83i)&A5b>EFmmiCPoc>g-+F~e;InEQXRIs!Ny{u7#hOe`tE9N~` zQt?N*-Z@M})7}Ky(XfrNQmw5`Z#FTf%#Ps*sDdq&-93M6uQKw)7-f{zL<-lk5%p)w zQTt0|JaRtCtMNgOa(yH>j|)~?V&hC@br|jKeye@4%X+3wI0@r|WM1}dW z^Mkp;*zdpM31@4x$NS^WES_LfF1uGMwS~Icf+aQb+EWO`h@uR8?Z$!A_dGV(FPG zY*ve2*N%QG?xEBRvZK(~Gu5&)L0!}2EpLXA$e!M0>dA09y}UK6^V^0UXk2#(Wk8%Q zM?jSj=1m^#R2+Uk>c@!S@#n;&2@&+wh2tcx##G_vOSVcG_BIEuIiMBA?)R0>idzyR zXtU8LI0CBR8W*7kfyv6??bGSxQ(4>!8`@OR8f3dy4T zDo)i#(sO#d3H%Ercsuc0@lR#h4R89$bq_~C6OW11-^}U=;BED3SApuozb&rtCT@7yNca+>-+*Q7xoG3nc z+0;S#QA>>8ktjw@u(yBrV4w)sa0qp}s=*06kCXI4E*t?>Y1`w)=Yz0pU;8ebouku( z@PKP^O6iIpGW-i9_|@IC<3YH1X`CWg|I86kRkKx`*vR^#Og^n;d8D%Y=N>Gy&9NVm ztKDhP?Jhv?7w^BCkgmaV;@jnf)Gga-&=F7tcO4K)v__?6-Pi-arHPcbxD+ncdC(@26XF#KAwOo=&fhJH_<2pv(5K7$kUihWOSkK7lSi-M38;cQ8*IgL{kT~D_a3?DSq+7MfdurbBUE$IadF0^ zJ+kvTo`5R2r^C(yByLs~Y}Ck~(x+3ncLROwaCd;s=jRfYffsV+!Hs5e1XS79{U}!} z?<;odsouj96ndPLBu%GAHIkM8>+XbzQ-(6KaU#@Dy(MkNpyQlAo{5xo84;*bvFySs(5tR*UZ8j7n0JW~9B@&r^BuMoun zy_4h%TEcFeKW%;|Mw%`qEAU2;eRl+sY_d+sV5(wsCldPHP@87aA}6QgAI@pw>MF?! zyrBi&;!<+PMMPD)WR>M{i4m*()5HWlo`9;0ZJkBiqm6_zVzJ>we6#;zY4nSA3cR5O z=EoDZW)rc`h{aOjDxQF#TuOtXr+Ber!lW5wRMs(Jjb;|#Be@XMo9mv@?1#%hj zzOqDX%8lp>(`1f-s({;d$bsBiq^v&DCpM#Ll^tl4y2%Q>7X#+U6Wb>>qi?_3(}LkV z0aXsEPvqOg^iLi|tzIa{n|M$c*JS1Yx`%@&o;H1%4!O8a+3<<#yz6aTtnD!BMf77bcBYST4Z*B6I0a>SmAn+0ijL(z6fAJ*D~T@$5i zg;6=@yYU26scA3vr0c^~qGI72squ#`WKq;;+<53_VS*SV+%fNik8Id198Ig0ld1H^ zCmdf0sQPKU*v-8d(RS%q>EN?y5}w z9f6}b0+tGvmRSJrjpo;+LgcibTploQ=Ii_JOh+VHlJv*TaBA1~ z#H-~gA#hH2{D!69b*LyfT6f0}Z0nGyoKOdBq~8AMB>U1`8>^CByBAXIMuGeaD->Q1 z!uTRf+uj)>T&jsVnw^h|^`&HMCDPz4Pry82-t1=Xlpvbnyw$;P;H@MTYxB5#FA*@v! zwIq+jG5$Guv(U?|3$YmGfWwcx5OS+EC+@rL+1K4UOb=VkcBc*O2XF*bkz+4}Mzkh* zxmsexy1LiMmVgkNx^k){mNu84U+zF!>vzKuHCo7x1`6ci6$iXbf2W;(%Wi~zc3{L} zn``6*Bm5Tg1XL|MvCHoAtj^?{*o_g@Y8Qy}`h`#*mp3nZ-KO@(1C1akh8n#YSC z1>y_m5c=JpC!k8$VJb}6(19e>RP$IjrX00e??D6121-^-i{#5;waB;i5NEJ9CxxP~ff8#8orYSiV zD{OI#7tZ2B8P?S zz9IJO5gkKt^>K5QIoC8I%pH~r=EqJ!;1GQ3LX`5(Gm0ai3YM1L6;{y=$0r-m3jOq@ z(li4xH2bAIa_WHWqpxeYD; zU@pO)1A7$AkA2e1d ziJW}Glq`AC1NeP@@NcP3SK8OXO!o8uN9PQ+(gQ#o>GXWTMe zAeP71%6A{ArJ7rFjL+NZX55KcLZ zmoL|nkLQ@<(oN1{m(s@aguu=?d;;rH2Y%by|L(-{7{h+`q)q-Y5^n0w5l|JbVLd8W zu%CTNt#kF41dexDt~_3AC%|vQeJhY3+y6Mq*3P|_DOuUh905xOON&r_2PZt*(~y?@ zC=}MsHV`u(RwHe!tgx4}f%wg{7U`Vag{w_A8%%VVvt|m6}W^>UxBhu}f6_zW#5WWef#OYZVEqigj;a`IzV5wkfnaxm| zDE)dmgU;E~Ni6MbD&!mYA`ezuvwHwdgy+8;iA~S0_-D~3!RxdGd19!3-Q1MRVu`9XenJc2tI1TOJ!G^7wfpl6N4r8huu^sH=#CR6tWl=EekVPTWA)+MR{qwe z2X=a9ARa&muYao+F@&WSNOmDyty3Jo9m3d)+Ng|hQ`Y`3VY#_x6S3fN2-!< z%p#9?*j#pMzf-Q1)SHzmYRO0O!lJ5l#0httWS?rc^LDCSe7!eL4BumiYSbhbcl5+o z>867IqN?O)fNF)u7(N%3@zv;paXbN4joP#mj(*-D2Waycwxt%{l>Sh$Y-@>UeqcT4 z$Qn8NS}&~3*(@xsT`K=R*#j%4F9aX`eEHt~?ktbJ60;(nG^7(6pOoNV;4I3|gDVG` z<3*2}(wVNuIRdI+%V&0?c_cRPxrDqw*g=G?584U5U4ktm@y`W|$ z%8L=6&im#4k9h*BG@D&TdE*ITsI5AG6ns5THm{1Hujd{Y;aWCg0-JX|dJ(gDYYgXk z7E@H=ED2c~K{HEEa0FDr6)Qp`n*Nkh>W`#>_jieKOZDzcOBcKYdED)NXUYkz3QmEuTvY>E38}7dI`{xPs_38cZ_m#7kcmk^6ek7X> z+L+*kO5LegxJrb%!&33~l~Jq-4%*g@F59_=BcKYdcUY8ngRb=Awd2aY7R@Q#+k_>7 zC1m^O$Ia=H{1eK_$4xi_s`!YMzRAuwrCM{E+-{l(bBCqkZBgIv&Nwrs87;0K#1T*h z*M=+xvU)IHdL~AxUgNp|*Rs$e=WXg$cER}Ov}k4ji~Ae_Rd9{V&SnfesCXBYqpS4# zQW*6B<2_*gGfz=kmQv@!FNF@_38;dt2chE+HCR}ykZL_YIl$ausrdCrm)9B`_A;CF zyj?|r1XMwP0K4(sHIi;Uv4&K=(O8&W!G#>1k#E0$qa}uGDt;aH>LWYLK=+eIC!cWy zRP8fxB2mUabA)Q@y7pK5ugbf#Q*x}j`cSx+;?=4%2^&5^EI<)NO{*tH3gk zUzN9;Cg)5t|2LsisZUbV`xmOaG8K#5@Z6Qn6q}?v)ThM=(Mb~}pBrw&oiX5JCT2$W z!-tL-C~x!FoyCBFDj0Erkp0&t_}iteQks`Ng(qC#*_@7E9mK8s(#1kqJuzZ-s0j{T zu~#y=X3G&!<={75OSG_5BZMZ6z9t$>456;Me6%`@5P}f}Z11kmHSr!J2A<*xsNy3B z2G2916{>raIXilC@eDAAp@hXVyxCJ;Oqnv6m8$k^6Kd=lN)k)DaRgNHXJw9z8HAf{?+0*0;)c<9bUCvg+;z#JG^z;hT^vahbUtk zS5{!WAdF9gaceA!)hHAJzlSI1z_@p|tG_={8eMk=HSWL@Pz7U6*sRv7Ej@FoJH1AdMCjRs-XZAM zVz(h)ZcBZgy3>XEYd8X`pyw8$5_Wp7&ahmP=6=WlMs}xNi66^U=|;)?j=x+s7$7BVL@Rp@~iHxOi%)f|1f}ALn2jd|~B) z9P4YnDBSOd=Lg}~#qPjPZG*+`gLA@e{+m$0u6p_qj(qI4Y17Tp+Lx2)obTflI7Z#} zC>AUmPbU%P#WHNi2xS*-lE(a)MEj-l1XRJX3!!>@jd0$Dp7dCD9nxuznfScPEb?Ra zV*#G7fTu3l?7Yhezs&1N-L~)qRQ<{{6VC={$jH7EMD{yBpFS#yFOy}NowbB}|8P{} zTgkVAuZmH!B4@qg&ksTsobA}&-5Y1R)k8^j(^B1XRH>nC-FHSEXBDdns;j2XMA1wBcaX8`}l2`JqfW-%E+e zAI=d_#Ybi~cRQfiblFSJ`2=#YoKOY7A+z-Tw<&L&5{Sp*X&eDnFh&ERzFmT7r%|VK zJi4rsy1#NH%Z$xM@7f}UyKnq%UoE#FI@hNtC(UmqM?h6gwu9+5w1e1lqPkZUzWa&f zm7FTY9~{h`uZ1UMy~AG%>U^C6rQ&x+haMb5_b6TDPM3KCsyed0+h2OdVwWVWDkrx)AHxD$A8##5 zJrb4aZc#aLJ^oGTY%2b|^OoxFG|(wQnQZe;folV3-9Mc=hyCtamK?VD7@IjuEQZhu z2J4i{47QG_o05zjkxn_aO~no zpVzscr6_kFdTBXNKovZp!n|r-jOfUfG4gh=URYpp0Hxy$#i;0>TucBT2XF=%(K`i; z<+%%Z0;=wHFOma}H4zuJRehH3=Zx{`ljBLlMLoD!XLx29#*`tnRnrEaem#inj_Jh_ zPzBHPvN>vsh=2S{mT2$B-1&1j%kUQR`~m@AnXpYNlpAscRC%7)Xl?2ZyNp?{9a8tR zvLrfL?vUYw;Tv*q4q`$OT9oxksUDLk7hd8C7>kkhJy}lf*-*^zRQ*?Det(j_k4uyb zWFPK?G>o8wk#)=ucleWZV?wgrxy{Oo8bT&K!Y~yAJB&9t#D_9iFioweM<5w zAC7=3c;19Xi#$0_y0qUbS2?S}2_}$OLF$u;ig_Z0accdFJ?+d(#2yWK_xC8 zQ08>$N8g$w3jJbm?F3I(A@pO}A*Df&essp?Qts>$RKb%^?3V=Ee^H)?_|UAr208GA zY?Jlx+=&7=Wq$8!Wc)ykhs zy-+DpDegCu-W@fQBcKYFkge!la>Wsu8d}*mg*%rD&!WO}un0AkPm7@}mbzZma~uIx z{0eg1o>a-bq#ynK`?mtmtHH4ruJqWwIP>>Qb4K-}^M@nugd0@Bbt1FE>-bXtsjn5; zKf@lLeurnOv$sZ(*HSyuRr@ z=22z*p;i>m8F0pdK0p?E*2o$+tan`#j%kt8^bv2X?-pR6*A`0;=FiP4?U57LnBW)MBC}m=Sm)6W;p(&-1dqBFjkH z?#yD6;n9I3po%}w89dF6dMq_i0CS9|A1Ydxr^w64k%PzBe!Y|Z&x zLk;$H%sKa5Ca2grFPD>|7*Wql?!-=N-M>6o{B7fI5ASzEXu(qr?Yg05PV!R15l{v1 zkYc{qd=0L=<0$Dg;!F-aACvc$-R_=L*{;RzePU|o1ToXkUw*^V?0yDzR%T%02{PP1 zpCh0Oo`PYPjNx|aYh!<9VUz z2^Jde93-^*;E4z}f804G?q3j1G?qL8Rq)gW^Y8X_qehYeeV?zdz_trd7Q=STA{uK2 z)1dt^%IKEYW!PTf90gB4v3MUbn4WTvRtB~%;0UOKr=XZ;yGsc5?>9%;`B=lSP9S^3G$fU!OY0ho9f~7FHBG9hzXf4`dA{~H+-7WU$`Md?IC-kp&mbwQ z3ERymkrfZm4tRboW1N42^<4I>_0_|~eIA|2`PvcUJ~pb|4}UM;aEley-z8+@?zJ@K z(729Rd27TGP?dkaSXQ6(HbK2%!zaBh?mMVEZFwt^#11eMdp({)es#CbhO1(JU0d6@ zEv|B_JALbwz!6Xd*SIWJZNeD3%lws;QgavSxOX*q!o2cfvnFeAd(-+8+0AeK-EHpU z{peY{yHe!-Y>t4cQ|l76R?WLY^(IT}3qvGy!V15V%&`5JSHf!chMnI>i$?RN3Xc!5 zI=Hu5ta@p>@N`eS_?y`%2t`izmLgYM;>#C#0;(L2y%99KVnx+wjZnLUa`lB>!D5+TB;3e^2#`scCh`_4V)e z+8z}?Q{A;3GPh9aYkyPneA162pbF;4*5_jy&|7-fr5?Y#QutiBE7K%=7^%-nRWd@| z=X7?_!vgey~cqagFQ4|1aIDvpzTtI@K6 zfGX%IWO3nVrsGqm)=3X{XAroH_@p#J>reW*VZI%_8I#@C^L-``HHnc-E1%{FsDitT z2xVRzPEUS)Db1)cPl01184#nbgCFisWd3f$^u&?0q0t>Fa@8D;fGT*GCfh5@4Wf}| zo3e%a%M?|myIB!hNIdc5LJ;lllag)G^xuTqO4K_#VSemev0u|6E8{cTY~7U&&+Wq7 zLgC#2%=gNOBB#b#4!%`$;0*#C4eps?BXzhR9w*&azP!9ipzj5))%n$SQf* z+VBKaL63zR5r0_PFux<7HNzN(Uv96Rw@d71i*PRCXM^@)w)7>T1MZ)|6HpcL)=b>f zLnC(9&L6j&gV{YuyX9ey(F*j#z&j409n9`Xu?(iWL$}GnMLYpj?wl8AES*SerR`NZ zH5kE-)Npj>R}(hpC(@(S_bRJ9@&r`zzNH!~ZSaEZdep%5lmgdLaGZxXtS~=ZZ)-fC z{VKGc*GZ0mDmaU>dxY!dkQU5_yTR^#g%&H^AA)Cl**%c@d1Tk{J+i}2o`5R;obZCL z3q-vgc6dWbXAJEG=#7A03U&uwOpG|j&JLfw$rDfo?FV*i#F6ndZR-ufGW6dV-Z4(*zc^ zdw6pP%#SA?Gh*9>?Y56Af3%19dqA2en9WX`9XXfrY>|H^TxW7LTYvuV=Hc>7+T)db zdMdrxy&v#)7`TH0ts2(a=a^#W6RwI)jvYrp74$ipTTfxAq*e%wz8!@k z|Kp?2bM~H@9jjL;>6!f!@;^=(aQ(b;7gtC}l_$zR&`dv-pDS4|wx?!BEp_Rap(Hf# zm3k-l6UV?PT9`Wj(2D8_O#&`7=`6h$oUDe zQbrX=lS_X^>9ExiTO+ZC1W&%VqOsO}Ldp^sEYV{&&v@2vzK7Pst$q8XEPQifHqRK4 z|EovUsCjvA_NA9LvUMEoSo!tvcW%QVVXNcJlh197! zXr6P(_o^eZFaz7gF&jJ$ZD#7%|HoKks%BsY zjqGEzAbcMcEMaQ`WI-(cDPJqyh}_s#m*97TpO%+o!rPT0w@)@8qs#IPj5<5GpHw-e zwi^nh@5buq6aySO#1-GW7YE594SG%;p*C#m>ea)q6gBAHjZL z%;p(>GnN|r-8HIce*}ArF`H*R8rRymcAqS1cmziqVm8k(AO6DFb)iLSUIx}CFq>yI zc)uiDTZ!`*?99SC2WImOt7jvLG$B-b!Ue+#pDMiq-{hRZOk#w%Lt@vJbLXLPrWX4-lz zw|bYP%=D+rpw@%`Cy{7>uh^Mp{5#IjnJ(U*CQV(eU zYBtPP*9bB}rF0v`1?FC;d3eFwtJSYqVC_dXyYKhVs$%RKr1@+Ansk9+-hEdhj(l`m8!Dy?0tBl+^veY^boY{H$bAu+VVge=tgBg5Ls2uM3Bgg+0m``Y(B-;@$%|0vA_Rf~?;~ zL&>bwr3@kSc?L$|8c9&If8cp(&M7*a^@(#v>;3HMk&@Dd{>tZk|NN5l4Qk4k z)i2^07&UuH6VZQ^|8GW!<5OBa*_6F{*^|ov#JPPq^9gd?Up%41x0o{N1<$}JoLvQ$ zqJN_qvmc=h8cjX09F1#*@sYCKPp@&)&Jw3~MMvbRk81Ngs(i^1=*W*<(@hZV= zo&lv*jEvUqlU*?iuY5cnM9`&%voTdysWt~ZxYdqVIF20#-^8mJW6vdnypB7P9X->ZGY ztS5AFi{8wBM|mQlY9zR72wwRh`}BB1mpb=mKezG>jKZ0-5IYFko!3Gy*NL|*IX@s? z`Pd@>S-e~!k}Mz8_jZ_56Q z^c(}DaEu0Ixb0sktu(VCz7bG8VnY*gWp{sR?eM0=_f;>C_2FHl?ZcXqqK}fh*TyvI z>fGtcg zfYGA?|1|~S)Zs=MniRg`@q9OoDqgfn=>UvVy?y@}3S@!Co1Bu0X7sg+FVP=U~`!FS!0xSJmvy)nULn z^|+=2i~`ez!7^OQ|}B>XB~4P0q-3-21fCg ziLR|a%azYfFod@pOmIA<_P3@LiB=tq@t6Ns;jg3HXW4PpIK#!}JOk?-SgL`z@WFP* zm6+h=L%KkGyS5T{t@0+?8LWLl?WD%%F-Uza8?)6X?|Y7o^ZpN`k3!&fSwi$ z56Zj0bz&b2cm_uCb=8VqMv+bTkI;b^^a_q##TEE*wP2|41C_bghi1^c=h++sqi{qk z_zg_5<%m_?)bIzRxY{DPMk8L8g3vNDUCzxIsP;NBnqy!TUisjO>vupNH+CP5x1UHb z3Xg%Ke<4GmVyZm-#b313*U20Mqp++EaZ5uY*>m#?(#)p$5|*Q|d^ON~Ep^`#Dn=P2 zYh12Ivh4K+sls$c!YG`h$TLR%bRf6uw^LX4cPF?a(ANjmrABw=>gt<&|548}xSIp% zu*zGVnaeY9J92mYA|~-+D3}&5t9`aKt9WWi)*%`7SVJ z3B^1Eqj0{WAb5-)Vcdf`=J#ano|rX!oKYgfw-0}RRN87w%2);JhTZWYST4a*4L&6x zkHxAnJPp*~N%7_w7^VHvMi^U@gCGmyRe*6;2Wrf}kN23PW@z}3y z4(%*?@7RI64X~sJu~F4Ot5f>E^Q__iUq*@4$DcmOzwecoFo9K>+L?<4#F4W2O+!4x z+k^7lJ*8OBypB8r^@YG+QxLq(T#Zj|`LzvqBjfXtKj98f3pKu7pBFD=F~>>LPUP21 zy@)2yb%r;pNqtzh11rv)p``8FKDr4T-u#DAA}3<`5o(^9R5#A5dR#Z|bk;I$O5Qa8 zu7VGR8yS(uSISu4!E20PR}20QXXP53crI)FUq*?Zz{}Lu7B`LGeBP~*+;{#{8Yuai zP+ja>Q{%fD+uX~z5=&NG!}HaR@692KU!j6f`p_x*abXm@@UN?cYlUIk60S@l2yWha z^ep7?mYL_qF)#{OKM{n{mSN=lkiX=SwmA~Ey<&UoHZ?&SH}!zzZ8{R{yI*^Slf+@m zqyX;kN*BGH*V} z?ehmSo7y=BoYl5*c5^A{T$C}F2zOKho6PklV%0~x!RxIJtpmM-9i@u_FZh*!Zs_cS%95-$ysUEgaVH~VBf_IjNwD85kT-$9Cafz4@{hGiuuOpFbvWcNPoLoq28_Zr$$7@eSCM34_I^n*KT0u*UhOCaz>^m_ zy8khTPwOs54{ywdLN|=sdq9@P1H(7pgs0X#HOUw79Nl#K*{lQq$JvaLsFy?i#*JIR?vd@ejfsLh{ z|6p|byPp0dFtV2}(_@s-J4H-LO_PHEhByJvE3>OGAscLQBs1Sqk5Sk<#53~s^Yl-E z@ovmfJw{>M63^H&Db`bqB^$KE$`hlGI@u^IQqrWD%74ykRQVa6pMWv3mWd}u{c|l@ znUj_#Z9exW!=66yybp}?%@=xN)OzKyau%#OD^31Mb$&HlpLw9BnbGQnQCQyP86A2>vg3}sX|?ljrI)DzR45AcxPHfh za-h#bBNVsY zGC9$-8gwz=tC;p`M{Z=9({{RMifP;S@Z@E`c4OTSq^OB^c?L$|3U*L~u5AFD)v-W! zSb0Upkpnmb5U(CVxW1+(K)R!!v@7{%9IK9IjzjV?8g z^`19e##O~}Jv!{=0Bcm0E$WG)v8>ZEo`F%gUL*9|F27zK&?Ssnk2{}%z0;n*GY+dl zoCKfS*BBVRfic={F~`6t?6roN?Gq2Btat0E-+@SiEkan2<~89ynWv$<>leF$#4H;HmM3ah>H(E($W_TO_)-;O}3Asda7KH50U)1yJK=$Cs9Th3BnWd3r-kW^s z&FvfsOWRlqFUdrkV2qRLdnA-N_i$HkK6);nEkz{D-1}mV8zGuJCvSI@%5^0~)8S;V z#!}sdTHTLtXG6*Dc`cN6%XkJxy*UP2UxSn4$Z;B@%+fB*wTrcSJFW)7CjdSf_+Aj_ z&jvErCFbg`xfUD)qxcG#C+3uKe_~qK=x4dQc8-*M-`Gmh#R+n^#s^^h=(EW6e=#%^*219r#l#UTEcKJVTlsrjm76~;MI{y_u;PH1+V$Bw zb>*_zqUAP;`mbMS+-tbXJFfmN2tLp;B(LWx^xHZ5i>9fzY*x^ZQ;sJ zOJ0WeAKGx$Vg9rfX|vLNI*>8aY9e`FG+%ZpJzK_S6t**b|CS)RkC`A2g!cxuah0KD zTIOr@QhbUYSCYp)s&MZr=uFx;l-Sz5Qny!JosAh7g)8L?Lc12j$&t?A^#9mCGHR(M z=OET`v8E69E8B1~b7h=*t7Sz4{w+L4OyiEymo`>P8Snx^d`VPfpM`+fL~*1EX*s0?3J58A%dGQYq*A1x~NUowKm^3cWdQj3;r6qve3(%ej7D zSYzcGBSAmEo3=f>RnjU+)3&8~9#Z`U|JBb+^mb!pKPmIo*0tk(OFd@bDx_F%2Ps@T z*@o8k?7OIx0i*EK@{C+yY;QQ%^T#e*14iL@#WPy{G-b*4+?b8>kn2Q)*)UZp|9Kd%`g=YEkM##o6VZa9M+pU&Se{EG7bVcbzR zz{mr}xrH$t1EX+W07NbaM=_e2FL@3gDB)gh`OQG{QrmlIJ=~7ehrjC)kM_pZ{@0l) z%**0{c=Hq)nOE_Zp|~=7e%uMhc4+ax7#ja6xQx|M$DNpq^hz+o-lDO zx7u-+IlS^A{%YQ6(k(4UHb2UDmc!lTc!tw8=V0rF#SDzX z76d_f?A{@>%i?E7*$3bYTe#IDRYKb^{9AYoY!3oU>g1iO*`)g9*eiFAfl(v>Nm6Pr79}g=tZKYAb@PfG zo~6ZFVvP=Kdi<=8^ck<#@6?FI#>))<79IoJwIG`6QwO!~TPxCkw-?92sM!~+l;_L* zr5OHX=R2R)_a|GX>bL!0Qxbv7g*+lS%b!ee0j9OSFr zn@ul$w3@!FX~*NizKXBLg&vaoUH3(gaV zILkMbIvu3)nYH6M21emrbU}!F6;7log$C;uD>&`00BY+;IDHp;-uWdzl*kfL@%?T% zu^#)tuxu62z!C?33s7~a!;;LI5xtGy9LIa$@6WHqQmsGB(RZtnm68KH zrM;fWMkJ=I9h!HiSSrT7q;R!y@Oc%FVC^EVs<{dGCCtDmEG-Ly!{z>&ew%9>t(cE5w}na4~X7*9BS z*5YbL{H(^F>cGzLzAn!e->X#{IMCUP?~5Jb&cIzfn#7f0kfe-%B;~WcSx)pC~xF?%i>#xXS_^_WY?UsrL;NcDgIr2 zUtu=%^E$LzE=(WA)5$`nCLNuJNRvxMsEd^w20~S}~Dh zV3grVikSCS_q%iN*;^86@~sYQP$f|vu)zZIJ*rYoYlt0aAw7HYtJf>;unV%!C5fb! zt;?!b;u#o)H6%f>PisQbKU5;)uaqM=qXy?=VT%RC6y0e?3Wk`HDO1XF42;5-7eV;) z4f=nW?xn>aA1TUj9r^9FrUc6j_)WtqDTrdnZXc!9eWNlk18dk=wu2{!-qG# zSi%g9!s9_*XBcB1j4}L1f)4-g3TKd5?f1L)D$|nlAwVA7#AxO|Ycc&%Az6n}xLW}p z52~aUMzgPd4=8uGF4kcb?sdR3rb4DgScO5#N1quwjKaNyc!m?myG7*|7+&=1pu;HK ziHK*Yzz|*6>l?jns>3KO`|^y2ef`PGPve#3AS;4xdf3*7ZL)%JdzL>5zcWnv(S&DU zR4jyPZxd`)O^MKACb1O=~Pc;d>Y4lChWEU0;ndW(49I061!r zKdEC~qsfJ4EosK&MO;@a+{p^}%7H5XZqej*pO&;=O`d^KxE~K#iq7s)0M3 z;zeVfMtS@T@uHZ4Q8?ZUEJd(Cq}NwGu7%}$;+zkh;e=!HpuP{pkqzuI!q5fc$nXls zv19xg3rS;Q-9E_BYa!3TDDCh6s}`C%%A6e7b4M-xqYc+b4cn=){Tlpgx{k8`k`=ig z?MbudfP_J51KV1hyIm028TladO_$NZ^vrf^Jc;Gs!7;4 zfjg7po(&Miy3UR{7kIPvX*>g?a9;>miRC-8)I$x}jG`#6Gbu*lt`dT<`HeqIxYB@K ze-guJyC=X6vZnt5`5S=`ACpO1ntsK}n3%J5a~&UuF1%!a-h!0_+ntPh&? zQIESbVf!V|82LDg_YPpF%#(JWd14^9+o_mUP%3!~3{hH_6d-PKL(_ zoDTg<1M4a~{umGJSD(||UVSa?3SW|8)VU@dCHJFsL~T}hh7bw((#L&A=xxpJ!!Qc7 zu?;o*)CN2MeWjsec~BdSI2BY2;99+e8dX%^FQzmtgB11ye=fG%w4(R0AgpjCHpnL%rP(u z-_(L|B>!Xfxze4r$|?-c1kVurDZq(D*m0NF))foJQcgd+S9!M%xXcT zg?sl2w#Hdu6t*q!V+@}7FeCT*AmbPqg)I|2W7m^&ZpSumH9iMMi7$J4C|$bHWB-{| zYG3C}8ga$Qz^KR*R*K-}Z?t&uV`yi3!6`@MtT3v-b+WR@RfG-#e}0cO_xEK!yzgOT zV3cm}W90_5r`kEsk1_B1%B-dy`-}{XnsB2UO+Wj~!ooA`u3pWm?MjWS1fv?1ccgi5 z?kd^;8KZa8B_2;AcDrj|5TjazNHnkSI%W5N7_}Byl3s5;SwrhYRs5X;UKQ*<_-o>| z0Cgr-SdyGqo-E6RXJ8bzAVH;&_ff3g%vXlt@mUmCU&HmtaGf%U7AcHk*#{pQhHcE| z7#M}?0}8^l7nh`^P$MNcY0Dv;?}}|?IMZJcVu7(37}~eT42;52{$ODNNhbBwa)ZnB zAOp@g+qQPSH0hMTIK8$cmP9&fHMc=4g3N*X!%x!0t><+(dIQ^MussOksq>>)#c3xf z*>#$;;$RyP&sfkooHfZiWeA+fcZ0$`m~g%cd_l-cdDpeEAwG8{7nzAsI7$R)<+PF z+(30f@6s~vG>&_0>P?Ts=!%R}WW+ zhD^PGtB|0`wrqRne>et4;Vdz*)=uB9X4M<54g-%hw$|W^F!WLb#r*6dL%pq9p75uow+r~z$lzi2{tmw$Dt6b)@@cNPrQq8&5{7{ zS)_o^;#U-_$$2{x`N*3sFfZg77}dXHb?Hk#GukrI8P-+bUL%O@*UfT|r|V^0Q4H4# z!}}ki^e&sRW$SOLN()zlEgm>FhX3ZZXI5t)``l5Z6IyW$jKaGBs&cjWW5==@G2i4` zp4d)_eRq1~(-Q>0DWUA3?uDv+tSMou6Sn(cdl2LO7!X1(aNt-q&P+WPI_X#I`IVPFCSZKKZ2Lq#Ut#U!w zWNGcOIJmU2_8^W=eDk|Ps21JGpS%0tN0BKPUm0#L&EopFW7~;>?BY ze|0v;z$koQL6zp-qcd&mW@?fp!FAQ}eZ|k}?aAG8NQL^OzTTZ--ICK9IVf~MZIs2~v)9O;XkghBb zXvgJqLoPsKE3)+aF*X0RCC9)wC$%_E|qs>x3Y-=XZ>N@JHK{4?IPHX#XVH@ zYdLw~5s@DC9iluP>PeFJiBwoGD9=uc20)$U|nK*sG@Coj)75; zX8!a-(RPFXHg{l{*7jqa_G~r`d)WaSafNlR56kI{w?-&=@L(;5!4Oa11Qe z#vO0RERuz4M-b7};fZQV)a`rl zrDC5aud%FuIGR-)zEo8Q@C=N?x`-eoS6r#CYA~8PyxOSN9h$7%m@m?@pnqVU3TtH0 z$K7_B8QZB5Q`hDja7|)dtC)|cK0VrxEMM4&ZTkL@V_+1{J{5#+&!(^% z$!T75=ybv_uITyo8`k{J;_8(So@$J~Yk8`-;?A#kpZY)mL5BiR{y=NK4;Wfbs#{6$#B3(bso?f;UHwfnW?7S-M%=$tc}vsuMQ)#Po~1k37J zhR0cA;42#A%6g7HsY?2q90Q~9y$jukmNh1+onn+39^M2;o?w4H?{WY8P-F6{?Gj~Z zZJvQqxVtBGyO|nJnvGqpuI_r0tB#MOP5B7ZPATE!nENXAYrt2Ifl++aeY8VU!pwTm zmIY|VR#GtRJIm0wr!FVkc) zdn}7~9xi_yw?*`Ea;9wt=}6>s@O9fYq7P?7{@`|danvS9y0%I?SXa8;Y4X73W7)UD zVH^Xaa6MB&2!1!34Rsl=_L{L*#_}hYmT+DnNHSx`u;^t2)rsaj1EUhRgCu)B%To%} zR(t#7dNk>L0e9QQ5=+g1%D+8&Sndw_kp!nk?BkZQ zo>#plDc!KcfGfP=J%Kx9f*$pJo%|fC0&8PniN54_H4UQV z?_XmyhdRO!fN?!0!R3E3G}LUaYIg50(PSr?tW4;)h?^DmA>bK8Eu`gsto^`7>_cSd z4E&v=erH~5Yl+Xob_K?KU|gFla}12)SIL??0qjtPTk`hcD=Mx+smZ&?p`N}p#1C5!ZR=mSG@&KgRdPM(%Xlnw~<`&+;3NUqS%*dW{fcY27gzEzkj{m z&mHVo3NUKSuAPAy7=@on5bR!tvqth;gM<4D6-)QnKZLu1L5HI|;p_yvZy2|pXJ8bT z`USx(Ih@5nM()g$;ThQbf;F#_y{YYBLHHMPc;4I@n1NCFO+z)o1$z)mHtrqwq|yPG0i&uUX{-qZu&T#hyCyzZe<{&k(91 zLPuyzs9Rg>)JGR=d&3qlzQ4gSVAT8nm2RhsO8vD|^Dbdj$uIrN4Zra4Q>NFNUsaT` zCZtF9R{oAEYQ0vCcH64x7Kf4BUlWyx%geI#c-Bj1@xWq9q3R{W= zVa&McBtCU69h?~@V-FwB^yhQ+-NU96T74c(ZOJn*ijUtd<@iZ8kASs%r$#2ukHOY2 z-r`ja7?pt0a@g4n%)qF6sIxhoqFEhDp}z|?acjVN`>zVjr*q1~WTM)4ZUz#%8;@$t)P#Wql98+i_Kr5L`}i~r*j)N#*pTDC3Ez$m*os7!i7#M{kr3Il%+8DBD@*4SBsaP3TKfwMk z-sg1yZk)$A2D8A#y*m6`cntoezBuoLdg#Sq<`9^{F)#{OJQ9SJ&rH|`T?1m;qz=K^ z4qV(b>JAOQRQpnF$Tll7rhsSQY(TynRR8ItNz#TGH5l@vaJ>W^S%u@WAW9Dyt>ReJHT}UCqlF!*mGeSHltqwuC?hvxB2qVobVfnmdSNU=+5az}l@9PM+$v>D?d3aj^!thp_hd zo9zpw**_;JpwZV3CmX+P(a*p8Uq%TE_eTd~7c|VqjZtj32uii(mfjMql>O#uyp9n>w~1&vK?3(=y*!;1Z@z9YPidf}n?Y|lG#<~`v~oTz{br>4JU@bCVAP7Gr#(h} zX{aPQ`oS0u8T09-I?n3bt+PmE6TP9G;%_iOUpqV=&&WB~pMFbfqE>aC%`q@4Id{27 zihC==yJ^}O`WGWQy|1 zU9r07d$cj0*xIP~{EO+XGc!py&$fy%bAT=;7{);3y)Sde;D5im*kr%P*cKNo6}?TQ zu}`B&wKMiek0N8uphZnFgT;pa8I${MUC;sBv5L6JejWfgMm@} ztoq#CFWtMnS-o>_GCAAbOx$t%pi2B_3weCZn zfl+wHKvnr;SER-Jud83Tjv(KU)Da`-BPDZC2W~u`QL~<28oA_w+GOi6j)76}^*lTW zA1_kQ59t6;uDmKI-*$Cn*ETtm3#5s-rj`}$_r5*3eal+h@za!E?(Rbljq2_xUNNV8 zgMEPEa{sCHbeWFTyzIy^FpA%UVTZpoJwd&#U(0;dp2Ixsw;i<{8dD=cTSg zLzvRN9LK;Yyyw9;VZTJSFdM~e-*1@NkV$;9s>*tLP?OOJr z2S>Ld0aiMte?cIv{JIS}JWo`@T>a==%Qi5pdviyqSL*j*i{vs4Gcf8~&4+qtivXIl zp*1j?C-!GGKDU(y4Jkz;mwi?C9NeVTsN+o*m3yRIST|M4cJ?6!rZ1KIh3%ByOv@&J zIH*7SoYP7Q1s4fsVARt(0`*_IKsk`5ouU&h1KH@IXQbc*;8DcCo0O;6Z*Qb@Y|?=w z)x4nGUw_vy=b*MqEG`AIn6~Godnq+I21eoWKq8x5NnV_ASGIl>O1gMl%060ohIo$o zkpmwO>7FecDZbw3MP&vbiFey-yVgD?OG>jWmX9V4;20RStf`lNPt$ecKp%}E zc6uNmey~BlGbM!k-S6vMMCYOP#4Wx2$iLT{i0&7siv2!nCw2MSC**{oZ)M+%&Kv`y z@OV&v_qjEB*fd7=i1r}(celKoCpN0lN!R|iFZqx@P0ZR@Mclne8{^y`oI^ z)>gZ4XBrtcQ&639cm_tTa5j@hJ=ZG*NtzF`=N&?7JZUGNnPEdByX+KGaz+}~Rre*4 zcm5U!H{WTn{p3TEUvCrJjacUye@;6~UYuwvz3VuH{ad$4&0C+Td!-AejicKTypH*` zdoVCgI#RALTlUz5VFpIMy?ja6KddvIt=Cq2sd*b^h4g0DV;`%D)hCKU`p&dg^R@)D zc}AXUpEY0caQH1doG zDO;&X%o=7#$!1rQKgm=ozFCdt1$hADo6}fw*zUACZ<7PPQMrmVc!?R^)Kesw%`=|A zm_+g>?N;3{dT|VlYEi42q_~!*U7zY;j5;5}NWHATRFeT6B-yU26mqyU-C`pXJRZ-m zPo735R9dWt*Y@Wa7!~jk;*giWQerbC7~}55>11z>f$Fr@m1Vq^@OV69;qC|`*7a4h zJgRUEjKXUSs*#-QL(XK*lx}Y*OCHbpM;zRBm=fLJheRZO71!)vuQc@YCWhXE^kL>4 zrOSQo^vOIMLf-aE7i*WVz%ekYOX6eEzSu_T?4X@KldN1>Le-6QS3zr5In0h;NVusG z(+RXejm9*q<`pIB;CR}9zXeTC+M?`>oeTcy+vmHn_p#m8oM#o7>xR}e{h|qdw4*nT zA0kovzh>aJ#AD=iJKHIK&6$XCWr_LmZO522|^tuCM`g$+%U*2x zVZt#uRQe+^aAPceaS3E2VMyKtHSzEimNsXA?C*C_iMYOw_D;5vOubW;yvm8xbZsT6 zS=&2?8*fwS+;{arcUI%4tA%^Q+3p7x90Q{QN0wLitWKuYnmYr-xl)px)$gJjT)sb> zQr}rDC-;;FkCUm@F1_M3Bv`VK?n-An^?>JCsth1EI=ol+?rz92Fv??1M`_sN zL3H`9F~F$fDbbhjB3SRzW7OII{xoEbilbI$>B@S&sps9LanyE)K{?U7jAsjB4gJav z0b}zM2-PEznFF05kw$_Bkr!J%W zZr@erY`?5592z&Q5_ z;&)d+rV*q8>$kQI_1RULCZFj=@jAvU6e49W-jaK#{FH0HZ^tn(ieHKS{}Gt5I)r^J zYNLKHysx-UkEPd|byq5F|E%N{t)Pv+z zRC4DSVuxBZZ%RL9QCbw$*?m_gbz5hMs=W*teTNJrkNV$LUz81#15?UNHOxxUs;2D- zKCkdO1~$I?Hcanw(qJ0hfg1z=E^YNi89dib*|YJz5Wp2WNJuHIF;0sn^Fd{1$(>vD^^hT<^x6eyQ+9=KpdSMwTC!OD0!dT>$Vd|`!`;;E3v2>PJb=hw{N9T79O{&#dwe_5fTw=INcd+mJKS~+ZL%O$4g1!W z#`I`F4?5PP-)r}zF$XJB`wmrUgAajp-MmlAfVXzQ7}aqyt2=!ioqTc|$G|8o)j*ug zf*ctXPqF*4apY@fH?fh$B3-3^egx|{SoaZx4{s9W$A>RTo7+q!t`pAaj(%(`o&Y-x zMqy1)5Ps}4Nba8>s7VWkvFx1o`eL;T9W;D7#S#ZEWys4iq-lu{)x%Ca1EZ#m9j~uY z+J*LkcmY9}V17Wpd)JZKoNLM&J}oPaYU)a*T_N;vM^oulhn{p%DK}bM=_4+v8%Dhw zdjq4WTDE+`q9rqzZ8!!-jV$gXPO8;|cG#|+qW!O=sBPmWLI!~?cXJls+oo)*A4fme zX`!Ur8k9oMHMHHJrXclQXnsIl5IUa4TUl@njKViH+|G8xq}`=bX<5kMo*nQ;SJ>jD zE_p#BEgt8S74+n_uH}j(x^Q<>kNaig#J2vMU{>$zw3nP)?xlmy@C=OVxXE5@v}dds zzb6S8t#;O8m#bK?zqeYj3O*e`^Jzi z$iAeaevvX~#9dFb!@gv|tewiyzRL~oerOt`i`_%EVd??K7YsezGu)#ET zRL?UoDrx&pvGDL(8da_U?#{U7gwl^DBe z8mYLXr|PrQiDO_CmgiufH+ZkUos_1Y&*{dn{E2lOtTTXQ8TeQ|vT&2yYnFV<6?3wlKY{9O2ZZ-=#PIy$+_t(MP1z)#&~sWyc~IJBFoNN z$Vrwq?GK9UVq<9^x1CB-%3N`gNgUNzSp=)(aVsxbYCV;Gz8b|bI24j(AtrU;7}BR- zJ7w2D`6?bg!^TUB_?e^FMYre9NANq>97B4jrK!oLa~uPoqWE+L{XGAq95-t$>(*o# z#a}I8fw?s8@(TKOG8LmP+!d8w33P1UNBDv)cegBOOkx-0aU27q@YjU<{AVC*vA-r; z)qRn)4g6mrm&St4B14z-4^+9?F@pvl>Y%&Qx&=KRJ)gecwHL<7vlztue-x_u2dc=J zfl>3_UFd!LX|#IYDPY{~+J;;&j;6k)T^YXnJWH8LPRlkZRgcf3MayeTA(uxgZdW4V z3x)-Y4TfRiWl0`_6>NzPdg_d#rBo2*C)d^%XJ(FG^-fnz&N5$h}G@IAO zf?@_nVY?sr4d(qVXJ6hc4Qx1udA?aCPHGt}jvBd^V%c!b2Pe@yZ--dAeIh)^uAW8m z%4N>-`^Ez}21ZSDj2GaHz6ohyy*hRFm{q_}3t(>X&8@n%Z)5JC^#6>)T03%QmL_ z3Y>w_s(dv<$5&?=4{LD@jKbduy6|~VQHM+zs9u-|dC$nEhi!e>NyZ3n9#W^`9y zwg}@G7=>*d;6)xbmE1Uxtj-)2Wx%%30k8T4 zyx3a@D-s$XBx9)vOG`W>FH>U2tgK1g$cZwRSTUPt)T$f6+#c5^x3e}$Sgyrvo>Avc zXSU)^9di81F$vEdvw22qpDeY)G=Wyhn85I@kKaPmU5gd-?%`rs*$wdI`!*%X!`A7%j8@vU>qP5K)_ix;<%6nCdRex^(T|fX@%e$z6+!T- zk*MYue^ak1K^z04uyqGg!?!uBh4T)n+qaHo_`QEltf{2WTPVJK3L52(T1rZEwCLJX z)3yiPKSP^LjAEZJcuTW4JvJ0H4yJwPyOHAQZw(c!gK5%WH}Ye$sUd4$Pul;Q7O`ch zSY2JDPG^qqf>ms9!*)0<`$DCV12$^FzhUgl#R!gpQCM<@{c+q{4t?cAqN5vU?@#uI~*dGZo z6Kx-;Kd*+e8lImxX%eHb%n0?CiigmtZNl065vx>e!N!(tyz*gI87lRNoWd5HC2