From ccea5f973285c311656cc697433bb7d42f24af08 Mon Sep 17 00:00:00 2001 From: ohno_atsushi Date: Mon, 2 Oct 2023 15:07:56 +0900 Subject: [PATCH 1/3] add rs030n --- .../config/rs030n_controllers.yaml | 58 + .../launch/rs030n_bringup.launch | 58 + khi_robot_test/CMakeLists.txt | 1 + khi_robot_test/package.xml | 1 + .../test_khi_robot_control_rs030n.xml | 22 + khi_rs030n_moveit_config/.setup_assistant | 11 + khi_rs030n_moveit_config/CMakeLists.txt | 15 + .../config/cartesian_limits.yaml | 5 + .../config/chomp_planning.yaml | 18 + .../config/controllers.yaml | 11 + .../config/fake_controllers.yaml | 17 + .../config/gazebo_controllers.yaml | 4 + .../config/gazebo_khi_rs030n.urdf | 305 + .../config/khi_rs030n.srdf | 44 + .../config/kinematics.yaml | 7 + .../config/ompl_planning.yaml | 227 + .../config/ros_controllers.yaml | 11 + .../config/sensors_3d.yaml | 2 + .../config/simple_moveit_controllers.yaml | 2 + .../config/stomp_planning.yaml | 78 + .../launch/chomp_planning_pipeline.launch.xml | 21 + .../launch/default_warehouse_db.launch | 15 + khi_rs030n_moveit_config/launch/demo.launch | 66 + .../launch/demo_gazebo.launch | 21 + .../fake_moveit_controller_manager.launch.xml | 12 + khi_rs030n_moveit_config/launch/gazebo.launch | 34 + .../launch/joystick_control.launch | 17 + ...s030n_moveit_controller_manager.launch.xml | 6 + ...hi_rs030n_moveit_sensor_manager.launch.xml | 3 + .../launch/move_group.launch | 108 + khi_rs030n_moveit_config/launch/moveit.rviz | 131 + .../launch/moveit_planning_execution.launch | 49 + .../launch/moveit_rviz.launch | 15 + .../ompl-chomp_planning_pipeline.launch.xml | 20 + .../launch/ompl_planning_pipeline.launch.xml | 24 + ...otion_planner_planning_pipeline.launch.xml | 15 + .../launch/planning_context.launch | 25 + .../launch/planning_pipeline.launch.xml | 10 + ...ntrol_moveit_controller_manager.launch.xml | 4 + .../launch/ros_controllers.launch | 11 + .../launch/run_benchmark_ompl.launch | 21 + .../launch/sensor_manager.launch.xml | 17 + .../launch/setup_assistant.launch | 16 + ...imple_moveit_controller_manager.launch.xml | 8 + .../launch/stomp_planning_pipeline.launch.xml | 23 + .../launch/trajectory_execution.launch.xml | 23 + .../launch/warehouse.launch | 15 + .../launch/warehouse_settings.launch.xml | 16 + khi_rs030n_moveit_config/package.xml | 41 + .../tests/roslaunch_test_moveit_rs030n.xml | 10 + khi_rs_description/CMakeLists.txt | 1 + .../config/rs030n_joint_limits.yaml | 58 + khi_rs_description/meshes/RS030N_J0.stl | Bin 0 -> 195584 bytes khi_rs_description/meshes/RS030N_J1.stl | Bin 0 -> 394984 bytes khi_rs_description/meshes/RS030N_J2.stl | Bin 0 -> 297784 bytes khi_rs_description/meshes/RS030N_J3.stl | Bin 0 -> 430484 bytes khi_rs_description/meshes/RS030N_J4.stl | Bin 0 -> 388484 bytes khi_rs_description/meshes/RS030N_J5.stl | Bin 0 -> 125384 bytes khi_rs_description/meshes/RS030N_J6.stl | Bin 0 -> 10484 bytes .../tests/roslaunch_test_rs030n.xml | 6 + khi_rs_description/urdf/rs030n.urdf.xacro | 17 + khi_rs_description/urdf/rs030n_macro.xacro | 17 + .../config/rs030n_gazebo_control.yaml | 51 + .../launch/rs030n_gazebo_control.launch | 18 + khi_rs_gazebo/launch/rs030n_world.launch | 27 + khi_rs_ikfast_plugin/CMakeLists.txt | 15 + ...lator_moveit_ikfast_plugin_description.xml | 6 + khi_rs_ikfast_plugin/package.xml | 1 + ...s030n_manipulator_ikfast_moveit_plugin.cpp | 1400 ++ .../khi_rs030n_manipulator_ikfast_solver.cpp | 12847 ++++++++++++++++ 70 files changed, 16158 insertions(+) create mode 100644 khi_robot_bringup/config/rs030n_controllers.yaml create mode 100644 khi_robot_bringup/launch/rs030n_bringup.launch create mode 100644 khi_robot_test/tests/khi_robot_control/test_khi_robot_control_rs030n.xml create mode 100644 khi_rs030n_moveit_config/.setup_assistant create mode 100644 khi_rs030n_moveit_config/CMakeLists.txt create mode 100644 khi_rs030n_moveit_config/config/cartesian_limits.yaml create mode 100644 khi_rs030n_moveit_config/config/chomp_planning.yaml create mode 100644 khi_rs030n_moveit_config/config/controllers.yaml create mode 100644 khi_rs030n_moveit_config/config/fake_controllers.yaml create mode 100644 khi_rs030n_moveit_config/config/gazebo_controllers.yaml create mode 100644 khi_rs030n_moveit_config/config/gazebo_khi_rs030n.urdf create mode 100644 khi_rs030n_moveit_config/config/khi_rs030n.srdf create mode 100644 khi_rs030n_moveit_config/config/kinematics.yaml create mode 100644 khi_rs030n_moveit_config/config/ompl_planning.yaml create mode 100644 khi_rs030n_moveit_config/config/ros_controllers.yaml create mode 100644 khi_rs030n_moveit_config/config/sensors_3d.yaml create mode 100644 khi_rs030n_moveit_config/config/simple_moveit_controllers.yaml create mode 100644 khi_rs030n_moveit_config/config/stomp_planning.yaml create mode 100644 khi_rs030n_moveit_config/launch/chomp_planning_pipeline.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/default_warehouse_db.launch create mode 100644 khi_rs030n_moveit_config/launch/demo.launch create mode 100644 khi_rs030n_moveit_config/launch/demo_gazebo.launch create mode 100644 khi_rs030n_moveit_config/launch/fake_moveit_controller_manager.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/gazebo.launch create mode 100644 khi_rs030n_moveit_config/launch/joystick_control.launch create mode 100644 khi_rs030n_moveit_config/launch/khi_rs030n_moveit_controller_manager.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/khi_rs030n_moveit_sensor_manager.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/move_group.launch create mode 100644 khi_rs030n_moveit_config/launch/moveit.rviz create mode 100644 khi_rs030n_moveit_config/launch/moveit_planning_execution.launch create mode 100644 khi_rs030n_moveit_config/launch/moveit_rviz.launch create mode 100644 khi_rs030n_moveit_config/launch/ompl-chomp_planning_pipeline.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/ompl_planning_pipeline.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/planning_context.launch create mode 100644 khi_rs030n_moveit_config/launch/planning_pipeline.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/ros_control_moveit_controller_manager.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/ros_controllers.launch create mode 100644 khi_rs030n_moveit_config/launch/run_benchmark_ompl.launch create mode 100644 khi_rs030n_moveit_config/launch/sensor_manager.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/setup_assistant.launch create mode 100644 khi_rs030n_moveit_config/launch/simple_moveit_controller_manager.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/stomp_planning_pipeline.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/trajectory_execution.launch.xml create mode 100644 khi_rs030n_moveit_config/launch/warehouse.launch create mode 100644 khi_rs030n_moveit_config/launch/warehouse_settings.launch.xml create mode 100644 khi_rs030n_moveit_config/package.xml create mode 100644 khi_rs030n_moveit_config/tests/roslaunch_test_moveit_rs030n.xml create mode 100644 khi_rs_description/config/rs030n_joint_limits.yaml create mode 100644 khi_rs_description/meshes/RS030N_J0.stl create mode 100644 khi_rs_description/meshes/RS030N_J1.stl create mode 100644 khi_rs_description/meshes/RS030N_J2.stl create mode 100644 khi_rs_description/meshes/RS030N_J3.stl create mode 100644 khi_rs_description/meshes/RS030N_J4.stl create mode 100644 khi_rs_description/meshes/RS030N_J5.stl create mode 100644 khi_rs_description/meshes/RS030N_J6.stl create mode 100644 khi_rs_description/tests/roslaunch_test_rs030n.xml create mode 100644 khi_rs_description/urdf/rs030n.urdf.xacro create mode 100644 khi_rs_description/urdf/rs030n_macro.xacro create mode 100644 khi_rs_gazebo/config/rs030n_gazebo_control.yaml create mode 100644 khi_rs_gazebo/launch/rs030n_gazebo_control.launch create mode 100644 khi_rs_gazebo/launch/rs030n_world.launch create mode 100644 khi_rs_ikfast_plugin/khi_rs030n_manipulator_moveit_ikfast_plugin_description.xml create mode 100644 khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_moveit_plugin.cpp create mode 100644 khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_solver.cpp diff --git a/khi_robot_bringup/config/rs030n_controllers.yaml b/khi_robot_bringup/config/rs030n_controllers.yaml new file mode 100644 index 0000000..a47bb1c --- /dev/null +++ b/khi_robot_bringup/config/rs030n_controllers.yaml @@ -0,0 +1,58 @@ + khi_robot_param: + robot: RS030N + arm: + arm1: + - rs030n_arm_controller + + # Publish all joint states ----------------------------------- + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + + # Position - Joint Position Trajectory Controller ------------------- + rs030n_arm_controller: + type: "position_controllers/JointTrajectoryController" + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + constraints: + goal_time: 2.0 # Defaults to zero + stopped_velocity_tolerance: 0.1 # Defaults to 0.01 + joint1: + trajectory: 0 + goal: 0.0 + joint2: + trajectory: 0 + goal: 0.0 + joint3: + trajectory: 0 + goal: 0.0 + joint4: + trajectory: 0 + goal: 0.0 + joint5: + trajectory: 0 + goal: 0.0 + joint6: + trajectory: 0 + goal: 0.0 + + state_publish_rate: 50 # Defaults to 50 + action_monitor_rate: 20 # Defaults to 20 + #hold_trajectory_duration: 0 # Defaults to 0.5 + + + # Joint Group Position Controller ------------------- + rs030n_joint_group_controller: + type: "position_controllers/JointGroupPositionController" + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 \ No newline at end of file diff --git a/khi_robot_bringup/launch/rs030n_bringup.launch b/khi_robot_bringup/launch/rs030n_bringup.launch new file mode 100644 index 0000000..3209a15 --- /dev/null +++ b/khi_robot_bringup/launch/rs030n_bringup.launch @@ -0,0 +1,58 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_robot_test/CMakeLists.txt b/khi_robot_test/CMakeLists.txt index 6768eef..6c875f2 100644 --- a/khi_robot_test/CMakeLists.txt +++ b/khi_robot_test/CMakeLists.txt @@ -47,5 +47,6 @@ if (CATKIN_ENABLE_TESTING) add_rostest(tests/khi_robot_control/test_khi_robot_control_rs007l.xml) add_rostest(tests/khi_robot_control/test_khi_robot_control_rs013n.xml) add_rostest(tests/khi_robot_control/test_khi_robot_control_rs020n.xml) + add_rostest(tests/khi_robot_control/test_khi_robot_control_rs030n.xml) add_rostest(tests/khi_robot_control/test_khi_robot_control_rs080n.xml) endif() diff --git a/khi_robot_test/package.xml b/khi_robot_test/package.xml index 33a1fbe..f8c0d72 100644 --- a/khi_robot_test/package.xml +++ b/khi_robot_test/package.xml @@ -27,6 +27,7 @@ khi_rs007n_moveit_config khi_rs013n_moveit_config khi_rs020n_moveit_config + khi_rs030n_moveit_config khi_rs080n_moveit_config moveit_commander diff --git a/khi_robot_test/tests/khi_robot_control/test_khi_robot_control_rs030n.xml b/khi_robot_test/tests/khi_robot_control/test_khi_robot_control_rs030n.xml new file mode 100644 index 0000000..4a15420 --- /dev/null +++ b/khi_robot_test/tests/khi_robot_control/test_khi_robot_control_rs030n.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/.setup_assistant b/khi_rs030n_moveit_config/.setup_assistant new file mode 100644 index 0000000..38374ef --- /dev/null +++ b/khi_rs030n_moveit_config/.setup_assistant @@ -0,0 +1,11 @@ +moveit_setup_assistant_config: + URDF: + package: khi_rs_description + relative_path: urdf/rs030n.urdf.xacro + xacro_args: "" + SRDF: + relative_path: config/khi_rs030n.srdf + CONFIG: + author_name: RS030N + author_email: kurita_taisuke@khi.co.jp + generated_timestamp: 1693526009 \ No newline at end of file diff --git a/khi_rs030n_moveit_config/CMakeLists.txt b/khi_rs030n_moveit_config/CMakeLists.txt new file mode 100644 index 0000000..5e65bf8 --- /dev/null +++ b/khi_rs030n_moveit_config/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.1.3) +project(khi_rs030n_moveit_config) + +find_package(catkin REQUIRED) + +catkin_package() + +if (CATKIN_ENABLE_TESTING) + find_package(roslaunch REQUIRED) + roslaunch_add_file_check(tests/roslaunch_test_moveit_rs030n.xml) +endif() + +install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} + PATTERN "setup_assistant.launch" EXCLUDE) +install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/khi_rs030n_moveit_config/config/cartesian_limits.yaml b/khi_rs030n_moveit_config/config/cartesian_limits.yaml new file mode 100644 index 0000000..7df72f6 --- /dev/null +++ b/khi_rs030n_moveit_config/config/cartesian_limits.yaml @@ -0,0 +1,5 @@ +cartesian_limits: + max_trans_vel: 1 + max_trans_acc: 2.25 + max_trans_dec: -5 + max_rot_vel: 1.57 diff --git a/khi_rs030n_moveit_config/config/chomp_planning.yaml b/khi_rs030n_moveit_config/config/chomp_planning.yaml new file mode 100644 index 0000000..eb9c912 --- /dev/null +++ b/khi_rs030n_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.0 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearance: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: false +max_recovery_attempts: 5 diff --git a/khi_rs030n_moveit_config/config/controllers.yaml b/khi_rs030n_moveit_config/config/controllers.yaml new file mode 100644 index 0000000..eb99bff --- /dev/null +++ b/khi_rs030n_moveit_config/config/controllers.yaml @@ -0,0 +1,11 @@ +controller_list: + - name: rs030n_arm_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 diff --git a/khi_rs030n_moveit_config/config/fake_controllers.yaml b/khi_rs030n_moveit_config/config/fake_controllers.yaml new file mode 100644 index 0000000..fa61c0d --- /dev/null +++ b/khi_rs030n_moveit_config/config/fake_controllers.yaml @@ -0,0 +1,17 @@ +controller_list: + - name: fake_manipulator_controller + type: $(arg fake_execution_type) + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + - name: fake_tool_controller + type: $(arg fake_execution_type) + joints: + - joint6 +initial: # Define initial robot poses per group + - group: manipulator + pose: home \ No newline at end of file diff --git a/khi_rs030n_moveit_config/config/gazebo_controllers.yaml b/khi_rs030n_moveit_config/config/gazebo_controllers.yaml new file mode 100644 index 0000000..e4d2eb0 --- /dev/null +++ b/khi_rs030n_moveit_config/config/gazebo_controllers.yaml @@ -0,0 +1,4 @@ +# Publish joint_states +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 diff --git a/khi_rs030n_moveit_config/config/gazebo_khi_rs030n.urdf b/khi_rs030n_moveit_config/config/gazebo_khi_rs030n.urdf new file mode 100644 index 0000000..e8f21dc --- /dev/null +++ b/khi_rs030n_moveit_config/config/gazebo_khi_rs030n.urdf @@ -0,0 +1,305 @@ + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + 1 + + + hardware_interface/PositionJointInterface + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + 1 + + + hardware_interface/PositionJointInterface + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + 1 + + + hardware_interface/PositionJointInterface + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + 1 + + + hardware_interface/PositionJointInterface + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + 1 + + + hardware_interface/PositionJointInterface + + + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + 1 + + + hardware_interface/PositionJointInterface + + + + + + / + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/config/khi_rs030n.srdf b/khi_rs030n_moveit_config/config/khi_rs030n.srdf new file mode 100644 index 0000000..2d22e52 --- /dev/null +++ b/khi_rs030n_moveit_config/config/khi_rs030n.srdf @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/config/kinematics.yaml b/khi_rs030n_moveit_config/config/kinematics.yaml new file mode 100644 index 0000000..a2c3e99 --- /dev/null +++ b/khi_rs030n_moveit_config/config/kinematics.yaml @@ -0,0 +1,7 @@ +manipulator: + kinematics_solver: khi_rs030n_manipulator_kinematics/IKFastKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + goal_joint_tolerance: 0.0001 + goal_position_tolerance: 0.0001 + goal_orientation_tolerance: 0.001 \ No newline at end of file diff --git a/khi_rs030n_moveit_config/config/ompl_planning.yaml b/khi_rs030n_moveit_config/config/ompl_planning.yaml new file mode 100644 index 0000000..0c37fe1 --- /dev/null +++ b/khi_rs030n_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,227 @@ +planner_configs: + AnytimePathShortening: + type: geometric::AnytimePathShortening + shortcut: true # Attempt to shortcut all new solution paths + hybridize: true # Compute hybrid solution trajectories + max_hybrid_paths: 24 # Number of hybrid paths generated per iteration + num_planners: 4 # The number of default planners to use for planning + planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" + 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 + frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frontier_node_ratio: 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 + frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frontier_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 + AITstar: + type: geometric::AITstar + use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1 + rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001 + samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100 + use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1 + find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0 + set_max_num_goals: 1 # maximum number of goals sampled from sampleable goal regions. Valid values: [1:1:1000]. Default: 1 + ABITstar: + type: geometric::ABITstar + use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1 + rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001 + samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100 + use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1 + prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1 + delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0 + use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0 + drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0 + stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0 + use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0 + find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0 + initial_inflation_factor: 1000000 # inflation factor for the initial search. Valid values: [1.0:0.01:1000000.0]. Default: 1000000 + inflation_scaling_parameter: 10 # scaling parameter for the inflation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0 + truncation_scaling_parameter: 5.0 # scaling parameter for the truncation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0 + BITstar: + type: geometric::BITstar + use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1 + rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001 + samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100 + use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1 + prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1 + delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0 + use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0 + drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0 + stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0 + use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0 + find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0 +manipulator: + default_planner_config: RRTConnect + planner_configs: + - AnytimePathShortening + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + - AITstar + - ABITstar + - BITstar + projection_evaluator: joints(joint1,joint2) + longest_valid_segment_fraction: 0.005 +tool: + planner_configs: + - AnytimePathShortening + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo + - AITstar + - ABITstar + - BITstar diff --git a/khi_rs030n_moveit_config/config/ros_controllers.yaml b/khi_rs030n_moveit_config/config/ros_controllers.yaml new file mode 100644 index 0000000..eb99bff --- /dev/null +++ b/khi_rs030n_moveit_config/config/ros_controllers.yaml @@ -0,0 +1,11 @@ +controller_list: + - name: rs030n_arm_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 diff --git a/khi_rs030n_moveit_config/config/sensors_3d.yaml b/khi_rs030n_moveit_config/config/sensors_3d.yaml new file mode 100644 index 0000000..51010a3 --- /dev/null +++ b/khi_rs030n_moveit_config/config/sensors_3d.yaml @@ -0,0 +1,2 @@ +sensors: + [] \ No newline at end of file diff --git a/khi_rs030n_moveit_config/config/simple_moveit_controllers.yaml b/khi_rs030n_moveit_config/config/simple_moveit_controllers.yaml new file mode 100644 index 0000000..4118c3b --- /dev/null +++ b/khi_rs030n_moveit_config/config/simple_moveit_controllers.yaml @@ -0,0 +1,2 @@ +controller_list: + [] \ No newline at end of file diff --git a/khi_rs030n_moveit_config/config/stomp_planning.yaml b/khi_rs030n_moveit_config/config/stomp_planning.yaml new file mode 100644 index 0000000..25ef11d --- /dev/null +++ b/khi_rs030n_moveit_config/config/stomp_planning.yaml @@ -0,0 +1,78 @@ +stomp/manipulator: + group_name: manipulator + optimization: + num_timesteps: 60 + num_iterations: 40 + num_iterations_after_valid: 0 + num_rollouts: 30 + max_rollouts: 30 + initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST] + control_cost_weight: 0.0 + task: + noise_generator: + - class: stomp_moveit/NormalDistributionSampling + stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05] + cost_functions: + - class: stomp_moveit/CollisionCheck + collision_penalty: 1.0 + cost_weight: 1.0 + kernel_window_percentage: 0.2 + longest_valid_joint_move: 0.05 + noisy_filters: + - class: stomp_moveit/JointLimits + lock_start: True + lock_goal: True + - class: stomp_moveit/MultiTrajectoryVisualization + line_width: 0.02 + rgb: [255, 255, 0] + marker_array_topic: stomp_trajectories + marker_namespace: noisy + update_filters: + - class: stomp_moveit/PolynomialSmoother + poly_order: 6 + - class: stomp_moveit/TrajectoryVisualization + line_width: 0.05 + rgb: [0, 191, 255] + error_rgb: [255, 0, 0] + publish_intermediate: True + marker_topic: stomp_trajectory + marker_namespace: optimized +stomp/tool: + group_name: tool + optimization: + num_timesteps: 60 + num_iterations: 40 + num_iterations_after_valid: 0 + num_rollouts: 30 + max_rollouts: 30 + initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST] + control_cost_weight: 0.0 + task: + noise_generator: + - class: stomp_moveit/NormalDistributionSampling + stddev: [0.05] + cost_functions: + - class: stomp_moveit/CollisionCheck + collision_penalty: 1.0 + cost_weight: 1.0 + kernel_window_percentage: 0.2 + longest_valid_joint_move: 0.05 + noisy_filters: + - class: stomp_moveit/JointLimits + lock_start: True + lock_goal: True + - class: stomp_moveit/MultiTrajectoryVisualization + line_width: 0.02 + rgb: [255, 255, 0] + marker_array_topic: stomp_trajectories + marker_namespace: noisy + update_filters: + - class: stomp_moveit/PolynomialSmoother + poly_order: 6 + - class: stomp_moveit/TrajectoryVisualization + line_width: 0.05 + rgb: [0, 191, 255] + error_rgb: [255, 0, 0] + publish_intermediate: True + marker_topic: stomp_trajectory + marker_namespace: optimized \ No newline at end of file diff --git a/khi_rs030n_moveit_config/launch/chomp_planning_pipeline.launch.xml b/khi_rs030n_moveit_config/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..ea20dcb --- /dev/null +++ b/khi_rs030n_moveit_config/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,21 @@ + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/default_warehouse_db.launch b/khi_rs030n_moveit_config/launch/default_warehouse_db.launch new file mode 100644 index 0000000..99d7016 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/demo.launch b/khi_rs030n_moveit_config/launch/demo.launch new file mode 100644 index 0000000..76bea61 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/demo.launch @@ -0,0 +1,66 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/demo_gazebo.launch b/khi_rs030n_moveit_config/launch/demo_gazebo.launch new file mode 100644 index 0000000..0ef8f95 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/demo_gazebo.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/khi_rs030n_moveit_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..2baed60 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/gazebo.launch b/khi_rs030n_moveit_config/launch/gazebo.launch new file mode 100644 index 0000000..e94e97b --- /dev/null +++ b/khi_rs030n_moveit_config/launch/gazebo.launch @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/joystick_control.launch b/khi_rs030n_moveit_config/launch/joystick_control.launch new file mode 100644 index 0000000..9411f6e --- /dev/null +++ b/khi_rs030n_moveit_config/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/khi_rs030n_moveit_controller_manager.launch.xml b/khi_rs030n_moveit_config/launch/khi_rs030n_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..600428f --- /dev/null +++ b/khi_rs030n_moveit_config/launch/khi_rs030n_moveit_controller_manager.launch.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/khi_rs030n_moveit_config/launch/khi_rs030n_moveit_sensor_manager.launch.xml b/khi_rs030n_moveit_config/launch/khi_rs030n_moveit_sensor_manager.launch.xml new file mode 100644 index 0000000..5d02698 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/khi_rs030n_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/khi_rs030n_moveit_config/launch/move_group.launch b/khi_rs030n_moveit_config/launch/move_group.launch new file mode 100644 index 0000000..c20c478 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/move_group.launch @@ -0,0 +1,108 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/moveit.rviz b/khi_rs030n_moveit_config/launch/moveit.rviz new file mode 100644 index 0000000..6d87444 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/moveit.rviz @@ -0,0 +1,131 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.5 + Tree Height: 226 + - Class: rviz/Help + Name: Help + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + 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 + - Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Name: MotionPlanning + Planned Path: + Links: ~ + Loop Animation: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + 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 + 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 + 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 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: ~ + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: world + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 2.0 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Field of View: 0.75 + Focal Point: + X: -0.1 + Y: 0.25 + Z: 0.30 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.5 + Target Frame: world + Yaw: -0.6232355833053589 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 848 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + MotionPlanning: + collapsed: false + MotionPlanning - Trajectory Slider: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000173000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001b60000017d0000017d00ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1291 + X: 454 + Y: 25 diff --git a/khi_rs030n_moveit_config/launch/moveit_planning_execution.launch b/khi_rs030n_moveit_config/launch/moveit_planning_execution.launch new file mode 100644 index 0000000..a62ac06 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/moveit_planning_execution.launch @@ -0,0 +1,49 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/moveit_rviz.launch b/khi_rs030n_moveit_config/launch/moveit_rviz.launch new file mode 100644 index 0000000..1c8f0e4 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/moveit_rviz.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/ompl-chomp_planning_pipeline.launch.xml b/khi_rs030n_moveit_config/launch/ompl-chomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..a96cd10 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/ompl-chomp_planning_pipeline.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/ompl_planning_pipeline.launch.xml b/khi_rs030n_moveit_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 0000000..cc2fcc3 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/khi_rs030n_moveit_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml new file mode 100644 index 0000000..c7c4cf5 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/planning_context.launch b/khi_rs030n_moveit_config/launch/planning_context.launch new file mode 100644 index 0000000..be5eebc --- /dev/null +++ b/khi_rs030n_moveit_config/launch/planning_context.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/planning_pipeline.launch.xml b/khi_rs030n_moveit_config/launch/planning_pipeline.launch.xml new file mode 100644 index 0000000..4b4d0d6 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/ros_control_moveit_controller_manager.launch.xml b/khi_rs030n_moveit_config/launch/ros_control_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..9ebc91c --- /dev/null +++ b/khi_rs030n_moveit_config/launch/ros_control_moveit_controller_manager.launch.xml @@ -0,0 +1,4 @@ + + + + diff --git a/khi_rs030n_moveit_config/launch/ros_controllers.launch b/khi_rs030n_moveit_config/launch/ros_controllers.launch new file mode 100644 index 0000000..c789c60 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/ros_controllers.launch @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/run_benchmark_ompl.launch b/khi_rs030n_moveit_config/launch/run_benchmark_ompl.launch new file mode 100644 index 0000000..c1d191c --- /dev/null +++ b/khi_rs030n_moveit_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/sensor_manager.launch.xml b/khi_rs030n_moveit_config/launch/sensor_manager.launch.xml new file mode 100644 index 0000000..6aeddf8 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/setup_assistant.launch b/khi_rs030n_moveit_config/launch/setup_assistant.launch new file mode 100644 index 0000000..1a6f37c --- /dev/null +++ b/khi_rs030n_moveit_config/launch/setup_assistant.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/simple_moveit_controller_manager.launch.xml b/khi_rs030n_moveit_config/launch/simple_moveit_controller_manager.launch.xml new file mode 100644 index 0000000..e88ce20 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/simple_moveit_controller_manager.launch.xml @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/stomp_planning_pipeline.launch.xml b/khi_rs030n_moveit_config/launch/stomp_planning_pipeline.launch.xml new file mode 100644 index 0000000..f252ebc --- /dev/null +++ b/khi_rs030n_moveit_config/launch/stomp_planning_pipeline.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/trajectory_execution.launch.xml b/khi_rs030n_moveit_config/launch/trajectory_execution.launch.xml new file mode 100644 index 0000000..20c3dfc --- /dev/null +++ b/khi_rs030n_moveit_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/warehouse.launch b/khi_rs030n_moveit_config/launch/warehouse.launch new file mode 100644 index 0000000..0712e67 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/launch/warehouse_settings.launch.xml b/khi_rs030n_moveit_config/launch/warehouse_settings.launch.xml new file mode 100644 index 0000000..e473b08 --- /dev/null +++ b/khi_rs030n_moveit_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/khi_rs030n_moveit_config/package.xml b/khi_rs030n_moveit_config/package.xml new file mode 100644 index 0000000..4ded01a --- /dev/null +++ b/khi_rs030n_moveit_config/package.xml @@ -0,0 +1,41 @@ + + + khi_rs030n_moveit_config + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the khi_rs030n with the MoveIt Motion Planning Framework + + RS030N + RS030N + + BSD + + http://moveit.ros.org/ + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners + moveit_ros_visualization + moveit_setup_assistant + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + robot_state_publisher + rviz + tf2_ros + xacro + + + + + + khi_rs_description + + + diff --git a/khi_rs030n_moveit_config/tests/roslaunch_test_moveit_rs030n.xml b/khi_rs030n_moveit_config/tests/roslaunch_test_moveit_rs030n.xml new file mode 100644 index 0000000..db2b447 --- /dev/null +++ b/khi_rs030n_moveit_config/tests/roslaunch_test_moveit_rs030n.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/khi_rs_description/CMakeLists.txt b/khi_rs_description/CMakeLists.txt index 9a80d6c..cd648f8 100644 --- a/khi_rs_description/CMakeLists.txt +++ b/khi_rs_description/CMakeLists.txt @@ -12,6 +12,7 @@ if (CATKIN_ENABLE_TESTING) roslaunch_add_file_check(tests/roslaunch_test_rs013n.xml) roslaunch_add_file_check(tests/roslaunch_test_rs020n.xml) roslaunch_add_file_check(tests/roslaunch_test_rs025n.xml) + roslaunch_add_file_check(tests/roslaunch_test_rs030n.xml) roslaunch_add_file_check(tests/roslaunch_test_rs080n.xml) endif() diff --git a/khi_rs_description/config/rs030n_joint_limits.yaml b/khi_rs_description/config/rs030n_joint_limits.yaml new file mode 100644 index 0000000..fac4f6a --- /dev/null +++ b/khi_rs_description/config/rs030n_joint_limits.yaml @@ -0,0 +1,58 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +# default_velocity_scaling_factor: 0.1 +# default_acceleration_scaling_factor: 0.1 + +# 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: + joint1: + has_position_limits: true + min_position: -3.14159265359 + max_position: 3.14159265359 + has_velocity_limits: true + max_velocity: 3.078760800518 + has_acceleration_limits: true + max_acceleration: 4.68483115009004 + joint2: + has_position_limits: true + min_position: -1.83259571459 + max_position: 2.44346095279 + has_velocity_limits: true + max_velocity: 3.078760800518 + has_acceleration_limits: true + max_acceleration: 4.84328867428427 + joint3: + has_position_limits: true + min_position: -2.70526034059 + max_position: 2.35619449019 + has_velocity_limits: true + max_velocity: 3.16428193386572 + has_acceleration_limits: true + max_acceleration: 4.97469573133849 + joint4: + has_position_limits: true + min_position: -6.28318530718 + max_position: 6.28318530718 + has_velocity_limits: true + max_velocity: 4.44709893408155 + has_acceleration_limits: true + max_acceleration: 9.76690872804774 + joint5: + has_position_limits: true + min_position: -2.53072741539 + max_position: 2.53072741539 + has_velocity_limits: true + max_velocity: 4.44709893408155 + has_acceleration_limits: true + max_acceleration: 12.6051557088479 + joint6: + has_position_limits: true + min_position: -6.28318530718 + max_position: 6.28318530718 + has_velocity_limits: true + max_velocity: 6.15752160103599 + has_acceleration_limits: true + max_acceleration: 19.6602895095619 \ No newline at end of file diff --git a/khi_rs_description/meshes/RS030N_J0.stl b/khi_rs_description/meshes/RS030N_J0.stl new file mode 100644 index 0000000000000000000000000000000000000000..1cd6bee5cd26f36ecf072b5f71ec98ff42abfe68 GIT binary patch literal 195584 zcmb512bdJa)`pv$qvV{U(pMf+PXSj9f)U5LA?)7*SL}G9v6$AwdLD zk|IF_L@|H~FoEcQPE}X$S39luXP?JQ-96tsU!R(pIu&|md-d*8Vf*K=r+vP4ZQ}C^ zX>YFGd$PiM`o-4O_1dKNz9DtS?ipuid^>OBycN#>>!*EzP!@NbxSwm)u-K3FON-C` znC3P6^g?XW*CkXt%hZ`^+b@?=?U0~G+(%V>Nv6d9$^Swq44@;+?vQee~YDewj;ySOyKNHFWiO;_;>AhEGXBxlSk+wZhb-^no);+oYp9$rG#DSMeds}lA zPz2Jp2daKdD=ikK9N)rM6-g+M41`BS3KK}%9ux^xL<_pA*#DoPEAc3EMIdc^po)4y zQ14y?LC=9l&!Ed!g|zK~Dta~ry-Kcupx2T|uS7*4ZF``KUX_Ag?bkrid%~l4lp>I} zJy1pOEhhAz!46@j$vfhwA1rqS&68VH)>#%PYK2&8QfRMBiXjb_W&KcQ$i#p;YNm!3ylJH>s9q)|lh zV-cN3SEAac-;zBrf&}$QOX@2{t49w#kU*7rK9W5!f&@KJF?yaNJdm(dU$t@%oh_M8 z=)`H|)7F|^uP!bT(NoN4vEkM z2~?TYQb>dz7(s$(0$dS7BJ@B4Rc5sm5}^l1kf8eHaWx8w&;tonnblHAgdP|{f~t+j z)gdH84P z%xWnlLJy1}LAAr>u|6b14@Rf8sty zkf7S(@>m}dN}iEGm02x?M4S;OFoFct4wuLJkWliB1ggwx$s&{o&ggNbk2F8L`HA}& zK_b#4&R2zN1DwOtBPA#gk$hDcL4rKgiYz4P@%1x^1gf}})AJGGfe|FA*VXBX<-s;S z5~!lrf;tNc2~z8;LIPDhi=kIy`c=glVGoQTL9c0b7Lx3N1gdy8M(?O}4{bpn7(s&G zY3eK_^oa8%@l_##DxOu+$dCw$&;uh#(1@YVLP8?+Kmt`fJEjpX!UH2n(8#CGLXtg@ zKozeGXrzwtzz7mFf~&KTWDg`z#p@fYI1wHgL4qogItxkmKmt{~PNT{h;ein(sG_Q~ zkYo=eP{r#_ngK+3U<3)88K|?6WDg`z#Vc)^$wYWy1PPkqsI!n{4LJy1}K{ID{ z77`Mi2mQo-Bv8e>IlLzn5*i=^BS@IjjF54~!sT&L%=4^gsetTy1!L7!sieMvyRP6Cn|LAYrMf+VDCznczBPB1o9C ziI51d3JFx<{(f*l>Yuoe5hQT8-X?ILn%DeX<@idhy=CW~@+ZZrA$R%An%;%(2#iD#I`ihISBuNBQOW}e(^jgW548sprmr{>MQD#teu#@qTklsMNSHRO zOdo0wB&-NLo96f0W9HQIqRFW#%ELtXu}qs)T+4Y^M|&WFktjlYJlAbR;?H^0l?M{0 z%_^?tygQ{mkibY3p*_4;D!VH`P#$q4Oq*3)%Xybgdmw?4C_;PGcW8%Z?o`erj)ZBm z%B(E42ND>GBDBZjX(PR*UrbOQNSHROxRz5L4)Q<(BT6W?5*Udhw8xh#4tqt0+@m~@Fl|p=QK*F?H#kHL3 zaNvOiMxqGqv2{r?zgVX3$^!}0W);_Rs>7~+&XK@K6rnx3)UD+|>-ow93Dag3*K(@E zfd>*8i6XSeO{HW0Q%mb84uj>5*UdhvD2=+k2v{_|NnzRQJ7>OdZ2iFd&2+9Kq(`FUd4jQ==+5-uU zL=oD9YX?;X<$;80vx;j6jog6;5*Udhv^D(YUcOagKGy> z1m$5O{8*;VDy|(gatD2d1V*9=?ZLH!DuVJr!n9e%wSz|Pzyk@4L=oD9YX?;X<$;80 zvx;W@>JBm8S4dzaiqIZhJE$Tk4OdZ z2iFd&2+9Kq(`FUd4jQ=w4mbns3Is2ButxCTsvsw z4m^;+NED$xxOPxQP##E_HmkUH(8wKlAc2u6LVIxS;5{s!mmp!OdZ2iFeXkzx-d zOq*3)J80w%JdnUh6rnx1cJPiAdmv%jtm4{1BX{6|1V*9=?ZLH!ccj<@3Dag3*A5!F zJ^k860wYm`_TbvVJ5ua{glV&iYX^*8i6XQIJ#?HOpZ@V@pPrjG==W;svG(WB zm1uQ$71jQv_KwYmzONp5XtgFVf&`ClG`9Q?0#(mk8WHQzF3JNVNYK0#cIfe{kU-Ur zf|p}AJ5?jD3L{7iEbqDtsz4rb?GyJYlAws-=a%R+dR)~uvt|99<5gh<3A)-e%3RUu zdVW5TKo#`@tUuD3xQ`Je=y_^M&tQZH5~!lrLX2Ju=|o)n*dFwpyYwniDzn}RGY<)j zAaUVXM|WQp;4~!r|wFGw60s{tp zj36=P{mfp!wFlF$Dy}J;Ko!+Q*d0Ut7CkV6#1mUedxh_q9N~cks%WkSyUyr=5hQq&<}o>ZmBcj__mMyq z%^B4WNJs=WbguzKkl@xI9!Q{y=DuntCnQ1-j3B`^kVo#22tANM71voF#ghq) zAi=eq$NG@qt0EtDcU$;asG_w9oXTjmf_#i1!Se{NA;}&{po-R1Y9}uw=!&!lMv&n7 z3D=X5P;$-#2~^SA5KhTR9%qCJj37bv$>VyG?12QTXpIY}ef;3;z#bSug6fm1C&?a2 zpo(XFJc@@zTv?C@Mv$Ot<8gHe33W+)RY;(UXRbVoheYUs5hSSEcw8MqBJ@B4RXhXd zQ9L9<4~!r|)yCuM5E7vW5~$*p1dsb65qe+*392?OkM$uDdLV%+UJ-Gn2#L@GBS=u~ zaCxi`iO>THRPoA=$Ni9C5Bg8tdmcuR;Pobt;vvBv^rP;f483|PJ zx|v7ukRX76)Mo+02oh9nT&@lw5odWu0#&^J=TY1ulm|wTplaiCbqEPkYY!w)MLW>y zbK4<7SHwT+vl(FoiKMlGl4m4Pg)0m7;30vl37qwF)ucQ`cvS%w_c4Nm*+~zHxJGOO zRn#M}LvIW?5A;A4&ll(!jJPU{AYt~!t*fFdi~C5RiswD_N{sNp2oh#rJlO*YRM9Ix zLGQr`4~!sT_QjJukU$mBTxl#xgoNo}A0tT6`yY1bNlyL5KXHpd6^%-;->%jA)s7yh z;yF8wqUl!^*Hqlc2of~9!hSn?Ab~1gdr&oq@W2QXR3%`)9X*gh6|bSFszrEU1PQ8k zu-}dzNT7;WkF<7+@W2QXW|!M~&g1+HB7rJi1=B1e!UH2nm|gB<4vZ0u2?@F) z{)zh-LBi~EhlG-6Bv3`OGr_w^ArWVU35+0NcDX}B$uknD;(ZL>cM6F(BTQff3A4)` z5*o-rpo;fnXclhIUX=$%kTAR4p+{Vs&~pxtg(}`L;(e!(2(JnwNSIyjkO)1HKo##$ zaRmyA&;uh#P@RSSc9Mr4NT7=A6W7IL4~!r|^99&%M-L=W#np!Ed$I>ckf3=F?6;!_ z5~$*8!}FA64~!r|voY9jM-L=W#np!ATge_6LBi~EheY^%Ab~2bHayb|3A!-;iTfBq z!t8Q~L|g$G2vl+H;2CpBXn+WeAVITy*l*{{F&;>uiq;;mdmb1tXnCNDs|~Le!mA2B zFoFcFp*|n5_khPj6`!N>YCj~{gQ)axf#L}5U4&-^mN%<|pSX_^ zB)FpSdfoCM%HF5O-E7=}cASxPcD^$B{D*lymX30HtsFkjrVsh|Hi3~SLSI!YIy?V8 z`1}VFrp+popZ2hbpm#YEMQD%T>FoTf)Sv&r$1-hJnZD8l_b?7VsK`41#a zn^j!>sn&bi0||^o5!$05ot^&`eEtIo(`FS{f8J}-9!Ov$iqIaVUast}3O@gVglV&i zt3U6VX%8eY5=Cf_-gI`J7JU8#3Dag3SAX97(;i4*B#O`;AJEzPi^1nVkT7jlnf0gk zKmsFCg!WiYXXn2KpZ`F@v{}W~pDK5d2ND>GBDBYGIy)~GeEtIo(`FS{f2!Pp2ND>G zBDBY+baw6rpZ`F@v{}W~pDK6YfdodP2<@?r&d!SlpZ`F@v{}W~pDK6YfdodP2<>qL zot-ZUKL3G)X|sx}Kkr}Z=Nt))L=oDf3!R-m7kvH$3Dag3SAVM9fd>*8i6XSe96CFn z9(?`-3Dag3*K(@Efd>*8i6XQ|M>;$IB>4OX5~j^6uH`gx2OdaZB#O`;Tsx?S@Vy^# zButxCT+3-DAc2u6LVIxSpo*YA|AB;Qv&x)PXb&VX5=Cea zt{qen)IDBEm^Q1pcF@S3rah3rNED$xxOPxQ5Ig}w!n9e%wSz|Pzyk@4L=oD9YX?;X z<$;80v&x)*={%6YNED$xxOPxQP##E_HmkUH(8!(89!Ov$iqIZhJE$Tk4OdZ2iFd&2+9Kq(`FUd4jQ?Ie$J7=NED$xxOPxQ zP##E_HmkUH(8wKlAc2u6LVIxSpo*Y8kT7jlaqXayJMcgPBTmbns3Is2 zButxCH0xLQ$?3jA0wYm`_Tbt<6+w9*VcM+X+Cd|CkOvYNi6XQI*AA)($^!}0W);^C z8o2`xBrp<1Xb-L(R1uU15~j^6t{pUT2OdaZB#O`;Tsx>DC=Vn|n^jypXygt&kibY3 zp*^^EP(@H4NSHROxOULU9n=pbFcL**53U_l5tIiKrp+p@9W-(W9!Ov$iqIZhJE$Tk z4mbnct?sokT7jl(X3ycU}+B| zFcL**53U`&BgGy_m^Q1pcF@Qj%&C#UNED$xxOVW46nh|H+N`2kzdFIvc_4w2C_;O1 z?cg0L_CUh4S;e)3M($u8g#<>T2<^eOgLkCZ0}0b+71s_LxdRU*FcL**53U`&BgGy_ zm^Q0u)~`;mbYCHXktjlYaP8n7DfU3Zv{}WqgGO#wdmw?4C_;O1?cg0L_CUh4S;e)3 zM()4^35-M$+JkEc??|x+5~j^6t{pUT2OdaZB#O`;TswG2ian4pZB}vZppiT9KmsFC zg!bUt!8=myfrM$Zifadr+<^xY7>OdZ2iFeXkzx-dOq*3)J80zg^mC2`MxqGq!L@^T zq}T%q(`FUd4jQ=w4guY;qM2p5$Nu_#dfo7evj0#&&lY2<#Er+EZ{5hNO{8Sic=*C>K8vwMF16rj5#Kl1gO!>lay>xw%` zXCL=5g2b%Zhuq(4locTnbeBz_%B+w=BJ?opGmao()`rOhMv%Dj>W}WJ&4nYb3JFxv zYYbM~ltg${7(wFiqglOfd2>W~Ab~1+ufVPWdSC>JW1^rp_ufm1Fmr&RMChEdrRnn5hRYKRq-Au zyd}Z|2~<&KfITwwzz7oj{-gIxga;C+q6!CledH0>K5-u-NbviQ-iPTP!G+lbs;E+{ zb!YgThaMO~f=2}!10p<-Ko!k6VDFVKDfGYy5Uc-%Ka);`9!Q{yXE8h`CwpK7395&xE`~(tfdr~}HpZiPNKg*^qwYx!BS=uyR8=k{ z;w;Zdpo(XeJc@?|0sN!xtqmhcP!06BW`#tYJR^ZBUajyb9ujdjU;-mZ@EVFo@sMB-`cZe1 zhY=*G2D)6cLL$!cj0CD^7f*d6*CLb$Mv$Ny=yJ^p2~ukhBv8d`S{{=vLV4ia5a*&u z^TV5;xQ`Jel04$X(0__Z(De#-H~XU8=J^8kmHNGTeEv7?V+0Aa@DDz0=~Ba=Naf&|TbV3!j;kU$kzO{!lJ9vDG_=5Mgei5^Ix zifbUxY$Ec22oh#*F(ksi!pA}t*FdU9UP$Q9rB@yet zsNx#Pv)N=1j37a)71*;x4vx>r?>i-aET;dCi5VGcKU|FWV8YSPyg&H&Hi3~S zLT7#@=LYfk_>t;73JKF@m3cpE4nA| zZ6sD_ouWLDFl|OdZ$34BX$M#;; zf5!v~(`FUVr|Es}X%8eY5=Cf_K`TFWSFE4LeHBN-v{}XTX&QY34@lA<#~0S@<770S;g~d8mR*hBrp<1XpeFy(!Bl` z?o}R0m^Q1-4w8O8kibY3p*=qS?Q8F1vpbXr5~j^6v*)BekibY3p*=1WD2ND>GBDBYEnd|yFcBCi| zButxCJfEhyaNvOiMxqGq@z(;+-~WxepCOKfX|sxF$27Bbbsk7yB#O`;7iM?$ODrs* z@<770S;ezst`6D*35-M$+T-BX{(jrbS(OJ8rp+pzHFM3<9!Ov$iqIZhpQui8osJ`6 z+N|PvC{>5R0||^o5!!?66IC7MfrM$Zif5Hn9Rd#|FcL**53WyCb(9AZrp+of*QL3M z?kglP5=Ceau1{2Tlm`-~%_^ROQ+0@G4tGGTmc$sOqSD?vOBTR&jlz>JWG!fsrUedvJZC zsv|fLButxCT%V{qBy=7~U?hsr9$cTO>L?E+Oq*3)pQt(n9!Ov$iqIZhpQ!364J>Mj6@OIgXpy0|-O2it7_q2cbQX zz(^FKJ-9wm)lnWum^Q1pK2dcDJdnUh6rnx1K2g*8i6XQI*C(nv$^!}0W);^b zst$n%5*UdhvL?E+Oq*3)pQt(nc_4w2 zC_;O1eWE(0JdiMLR?+H3?K9{+kibY3p*^@hQPoi%NSHROxIR&J2=YJzBT*8i6XQI*C*b+V-F-un^jz& zs5-d1uaLk<6rnx1KJo4ydmv%jtm67a)gkae0wYm`_Tc)&yLaq?glV&iRxj%OT<3uV zMxqGq!S#uE@7Mzg(`FT|Uex)y_CNw7QH1v3`oz0;?16-7vx@5zRfnLjkibY3p*^@h z@$MaaAYs}nkKmMC=Ya%QE~*>KJ&MpCT%UONPUQiFp;^WCiK>IAJ&?di6rnx1KJo4y zdmv%jtm67a)gkae0wYm`_Tc)&yLaq?glV&iRxj!_T<3uVMxqGq!S#uE@7Mzg(`FUd zC#nuX9!Ov$iqIbP&~bizK8ee}^wYFlt6HhY%5k)Q;^qnZJmRi5il;T}-8%5lYE57S z37TK4Pblfk`N1_6_mMzV{|1?2_uUcYfe|El1f}sS;;N89)#&MaW6z${`RVI1SA`KI za@|tfJ@P(ya31tu+#fJ^S=u-ErV7q*@|hW120YkWwL3jgEYbN3Pqo#fGeJLbA0tSR zAFNokT6-XYs^QK1CWfDFneJgAA0tSZb%OPL#QCa_KvmQ7vlCYyXcFOp5hTny!SYa< zBY`S2>kkReLtWL>ce=zLt*m?W)Qa=5dR3V~kRUbxsL#ZOYfB`WEN<=|$z;}p zTAfUw%B(+=JurfVSrsP}7(wFj#EI_boy_VEuL=oNnbm!=2S$)67JJSeP`_csGl&GL z%q~T;2S$)MGH0`Uov0Pzfds0|ZcDNUMv!Rv>_K zbx3~BF@nVV&3*6Q#|lJvAb~2b{#@mfJurgA+?A=`*SY7X6JcK=fht;sseQ|24~!s@ zc)YduTDOUtLxMf%KXnIo_*kf-)g+t`k~;WN_l1WMB;vUjr$T9!`4Ic?4y2~^Rp5!?q5 z7%=2x1c_T(RQHa3`Cfzv5~$+!4cC_BJTQX9Q}fGu!&-isPEZay4ol${$sQO% z;+|!Ny}Q=`9pQlls(4k&l_J>#BSfZ4S`{DZK3lCtI-%ql2~<&i zg8Sk4!5Lu!BS<8z2bDY{fhwv`$*a^j6SykEmC%{%mM3nNbwzUK7(s%bCpcr_OQN4R zdmw?T2gUn|mzSHcy~ZVS_A$YCBB zLBgDcBzqu%s?Bp+i<@@rPM;x%9vDHwoP}5(>KQ}=RUdqlDk|SLEq#U@dSCbR z3_rL=;yx0n`fRN))?Utd%KFJTQWUISWb70|``Z`lgc1A@fe|FkSxB-65~!-5R$X+fwKKv4BS@ID zkYo=eP_?UZIdR9-FCsiJf&|Sf;Zz2n4|~cwhtxnjME{FX}}YSN}_+ z4-%-_cUKOvdt)AZw!|0bV+0AB<-@5AON|E-s587nKM6Z)bk4~!sT&O(wskU$mfMkZ*NGr|KSNYLsLPGzvKkU$mR1HkLi@T$T* zkU&-Utj{KH8{06Qh-)P7V+0Al2Y}br$sS0cYR1U1iG3TRX5kn?g7&Y~=LeHLkU$ll z8wE+Lf8stykl=d&c+Vu+0|`{&xsmOGrzChPlXTJ$U~wN+curvx-8W~J*-H)d>rY&g zLeF5hOWwBP0r#=ORYa~8Wjx%0cAO_OIr8jFgZz~TR;D4b?wxh+fO*#|0%>{!zI9q` zedkU;b?J&261YQ;wBzhQT0x$7I{2>_{v(Ea(^W41?q+(VsCfUck{<3SJI=}M737ia z9sD~#f65{XH@xWfI9*)qK3m#D+HpEfC?_}MzQNxoi(15cwSRIe6)7n`9$Usk+HpSl zyo`LmYbXEy979s9tNQu8d#ZOSl{wOmGwrj&a>(mF{TpWYNkanrrwY)Hle=+YnW%iD zKk>D-Tadu#0BO2=V{mzYam$YW5B2uOaBV=3n=n^}>k`K)+PAbn@Kh)N@=KFkB*CMEY5~g>NcAU&Vmh#`J(Am$u#3txDNSJ33X~+5UP+`B~ zb3Ogtn?FoLcgi+lUWs-dMeaBv241+^pRss#8oqw;b+!HCeD~c%BlX-k&d@8H=r4kf z@XHNe6~i+qR3Ys+x0hcf7EK%FCwi_+Llx3r6dUSpo!uhvICkc7abf#7e`b-jF+58{ z71E9~|DgxP#U}UrFJ9e{hAO1LoLa-pe!&eqywM%Rs+^Pkci&kb!&5|5A?-MyA8a6Q z%`?THw|G+;s*pb3{DT<%O}D@!rSZu`nIY5sV?E!F;rM|nq#fs*>1z`sewpUCtFe55t^a(wU;5K`VmMx*3TZvKjrd`@|G}z68mcnTY3Ux{9{aER z)?L&6DLvC-cp6T0s6yIt+D>2VK6GiCU%$*&_6Su-Q+{dbef4mMQr?f5ruqeUi5Q-S zqY7#I&fNnIym`5%_$~jtjr%HmETrjqN~AyM=k6cvmD(`DA6Vtx7@mfs3Telw{@{aN zr$+btmrm^9=RABYr0MmRNPq3-81{-c^^r0D;QO}6aNh@2NITByGON7mlSlarYwY6J zZunS8)B7fo{vKTa`Cjkuhllz{H|>n!z7ML9cATcS9r2p|aJRqmj@|qo3?B<=djBU( z^>LhHyDoVJx8LUf@zbst?)#t$X~$W1^>44*l0p8qCqLk^Bz!ESaU`O@+czwq|3a6W z{L97m#Bf|f71EB=vFva;@c!*y(NkmH7V##cSM_;rwLRzDo_%S2dUCO9KhdL^D8KLt zcg+iL(tUFsh`5u8yhNa?YUL(ka@psU$|j0593o>`4tTjU5VdkQ5Ic`ARUSxFH6WrT z5&4NgRf&BK#jFQjQyw<)Ly^1Wu-iZP3S=O>XX=W6nO7+fq#frX5w{RgjR;ho?Ok6K z-L_hJ*u?4g2FnRgo%5<@Ac|eBEf!{ZM|mJkBODPA5mA^3RF&9JM|}U;X60cMeLLPN z*FEvO$^!|{uPOd>Vw=tbXvevOh=+){nXd{|?oYMEcl&neJS-x0@c?<_%FKSB3`EyK z)x@GXdzA;$bY~tBwTakA1ggHzUPGK;_>uCkiQ$Ppa>p+@{rwq;(|sz7289nR52PKZ zD-pjE(SQh4?fj#PIML*Y^00{kYkSGQ6$>O0OX^h+<%gV99!NXRSRxt_v4T8MHDY%~ zv1aLMlXFbWFYE&RYu%B?;GWTwBxu$ctoTUfvWlA%Zc01e5X8Y;$+dz zvU};$zMp}(VPZ*9WaiJx18MqR10re@v55#&{gA1&xccKoBj5C;tiQS9&v2q;5RXuulV(TvkZhkHoxfnbT;LIG~KOC#4p9J z_a7qyRclWb5c$q!R~|Oe^h7f`VnPFdUIwDTtlZ+6S8^#2q#dUY5%&`@f(TSiJD*2v z%92NU*u;Q08_K`dHT6elAa0zIUCf-HPkA6s?++sKt#7LO3RPo{6gUJCZ&{zO?17tjJ#5)lRt*83Lp3Q;_nivmC7g&q#dUV5toU$ zmk3l9xOhIXeoa~BVH5KnE+$jr-I9oBr=3o88(Us^AniDB5K)7O-QdM0=DwfVFFNyxDuaIa{ zXlG*Mvo(|l(zHq?BD3u8S0)csjm)(xQMhw0r>N_Ft4WH;dFKR`2j=HEmtP$vo8Ps}D@u8w3a`*6st+73 zfBtfrx00?3iTek%5Ql#pr}9ABahenH1QF$kKo#a>69;}BBe#uQpx*8DSgQEFU=Ni?iOHV$ac38m2j)lbS|ZN$eN1JJ zD!f9Q==$L}dE2(fyfSoENGw_y6EWFI<$<*0v>@Uv5yy!@73O3UxBNL?essemFB9c) z<=56?^~)_(9yw3@V%FNGDi6$$W|l;>=rqZzP6Vp(3T>k2+xN?LIVO8u>8g#{4} zJ=0j_fi(Ty9U?{&QJM%;VNN#Ds^kRu#?Z-L`Gy-~NZ=_D(vEZM>It&%@F<;W%FLQcP#B8CKJjWck~xsowU@#Vi6dN1FB-CQO!R&sO%zQsxi%?M0O<-^I8Z zv?|j^t<8r4}+_yu^ovVbyG#^A793JPK~tVG$x|T z9aU6cp$dD!CfsMI$iA;u@wRqYA43AqRgtE@$TfS4Z24h!?-zQt56;p-94(ztnddyw zM!ZmVv&tNM#Bn|(Vg(W0SE$0AY~pI?sd96p9NrLm29Y>>K2_9fze#0|H0|$pnJU{5 z!Fw5~!kld4lQ*WyK6mEudi-`ch6HAgwBsBfI#m{}f5>e|c^rJMgJ@o4uF5>u*tTN& z{@E&X>=DQLf`}XH9&#^HU!e+fvWZQ#rpam_9dci%Jdn6&Mr-lWu*X#9NIOm%5u-jl z#L5e1%F=(Z;URhW}a_=l#+x!D)F4&{Nwh#y*u+rN&f%#n7S6e7mwT;#q< z1gfwXY+_dP>9T9PMQ+uv*T#^*I~9<2oJ|i-lO@)txHTz{6Wu$CtRL=4;rF>;rJd-p zU{?yi&#^}wXFU*cBb(A9BIe7lZcD0 zWA5KH3r7{^WD^Zvoh}zY8gmPr-ycH)Ge?^Kg5cI^^4sfY$I4S4y@qrYpRUW-k~8n- zwiD~d_G(f!QJeC}QKqA4QKx=DQ5NyOg`t0rzE0#%rkP2{A4GJ&vP<<9s<0PqqDJ>=a@~{fCt6Y-NW7i5wOF!lmC77x$Eim| zvw82UzCsoDf=x`PPxqHQ^?stHToXeA@1{fAaVBq>A|Gp>Nff5c+uqY&OlL0Fx&O2l3-)JA z@cSHlgzkVK;_<%aR9~SAbFzs6qo&Av_m>mAGl9gcajnElQ?n-ceU3DpW)LxPUpetE z5vanPY+~v5De_2`^5XlGnJfY`N1Fa7=a@kC{6^b zuorBi%>2pn!@4oC`j0g+B=G)Jq#ft|s}p3`+IF*H`dd6p2PHJuzx^eU&-VbfQSa7a#Q%pAvy8%*iHB zm6{}FrGBDLrfo4KFmt47r0#XUEdB9Vah~!h{&A|fV|Qnjx!mT7wR1bF%&|x4-VY*H z9vZ9q3RResO;ju}LFSklkHx4L{z5d{O|UyM2#YYRpvjYxS~q@7L_^nh~so7VjdAc zP+y@6bFzuj_2^sJ@;oZ|3=)Zj1L>Pox(rmABkee4iTEq`qhbINsKT6VBFhuw<~54Q08amd177N2`ck#vr|O*)Uhga>=8O+A)+f0+*hc= zoNVIpQe)-th6}`xG%rD7^_mu9=;6^SbEN4m3nHo#(Tg%i73O3UZ%-U63*NgxG%qb; zNMPnjJI?shqvexnOI3}kv^FNH=YCja{`7_xBGcCos?4!R9A_dCQ;DccnWGAGvI*zl zXxXU6tD-FBfyDJEn~8zX{8wd;wB!7FV6^N-#Lv`MsKT6V;$YP=^4T%3itS}C#E`(u zk#?L4FO87JpINJFRK?{jMfFopsLVgu*i4jqVy?;@d&F_75Rr`tp8KE*bFzs&H;t6d z%dQi3D03u6ebq#as`|Lf9BCSNiD*p(@4cc5bFvA!ex&Su$2zen=lU2D_!$bMX@~ye zFq!X$t)e33(PK(;k!QhkD)WQ$nuz&j7OTv$M;zx@A}SM6hzL|+PByXNwc&E(v8}?R zJdpTiMD7M6PKK z#PG8(tIUyhoS%sJb;L)4PxVoSIoZVO;zMQbO&^Kpi+mSD0y9UNPE4}gB^Nh1E(%f} z72jwi20p(=WnTY4eX-`Fw^ZiXBXm|o#5^KO5`ikr$tL=*xl6`BJuYsfJdo&GsGj)h zx|J$(q^X`0afpadsIO3kIoZUgTL;TY|M^B7p^CF7TLaPcyDch@SYtsj27EMMqb!Mkcmw48puxUbCHDi5R`=f6bUOazbAsKT6V zqD!}1WsX~a5jp6p*2e0J>+`>-^4Kz|wpe>^o5}<8bDS6v?TFyaQH57%6CHlLRc0;u ztC&Vtg~XuuYl@3kx2imlrWHLA-ZLufEew9bx zg*C+4w7n`1%+GPo5HW{{TtuJ>uh1sy-Z)UU9iK_QL|27G$M36&8#eAyc_8gLHHhdz z1n>Kx3UjiFcaHUupAX6*ucxbeC8dVQ{mD_4$KOv>6(a{9R(W84j ziOSRZ%04@C$e-xdj>O_0DvR6Oe5~?7+Hu+uQIUvcln1IXC!6@`P+xiUj~sIJ;teq* z@RNZ^JI*ODld6DH6MaeJDtITtkDKENJ`c`F*JwkgKM2simZz52IIoZU>E3ipH z?kwv*TvGC0#-_UE#F4VUs?0xJNq_NUJB{wpQr zlavP%<0_XDMGpO_GDn(L^hC@dq9YNg!d|e6n^L>TH=37{g+E;vLjpf*i?rj6KG1VUMW$c>fb8!f#phw9;L6S%&|ut=RqPG5W#(gD$L0yat`Sr_kUPkPNh7M z$hD-H@Lu>`WsbDtDxVZKhR~Jkv*F z%CCh*gJ&JVyEsTYPPVsO%bG;+NR2AY$tGU?xwX8ys;ay)zko$x=19}pxr-|+&8j7N z_S)k@VUf}yr^@{N^94o0^4V49*dvb9h=}||a9^PcbFzsCj=Qo}p4#%ilm`+E>K72b zKFF#vN1EoMM6@G1I5zHHcYUknM%9BI1Oph_e8Or0j`eg5X*+~UoL3#!a3 zEX^qjdHGf5*dvZ}KM_NTNTtkCg*n+okrj>Pyp2udvy=xCnL6bV+dj#wGDn)e;MOE#>FSX1fXcR)w+86%twczu~@3 z?fF*=h&*q8U|lVr6;+q>es3iYEf{O5@Cq?M`kv*Y^<}?1TF9>LJ6Xhf^4NVezZg>D zd+TZ)XUF{7a^xjfuAO&x48NbDbjQr%n@0+Y1*wJkGjZ@e6Fd7~FORf!7iSja_KgQ)jsR*7g?R) z&-R6%KgGKn@$;(m37!XY%aTR<_(S@ZaFM_}50Q49@}0BFVfhF6rKX&;Jn+s#r0J6{ z4KvA^-_fTUU;Mx#@NPq-X{1igB3~;rz@Pu?qwa=J5(!#Gdz~*VwC+hnn!X9RKvp?* zMSp*j_mD;4eUJ7Xjs4!wBDe1A?`I$Nh(*M1JC=B`T2LXWb`e zHx-FCi(I}c{5;0#arMNYp>M0-)BRV=hsnYvw|n<@TV)Y=Pa@Lv$;plP$f1+>d8tR= zvk1IX5^1{kqtI~K{uklxec+%)4DHoi+&1h5cg_9nT%;Z6-BI=Ay0$Il(IJ1R*VT`e z^NTGH@VMc^wRY1&)5rLugnP&@h7yEj?{zIKtOox5_m zW%2Ph`^y)vaPc|7yJPL=BS*V}a{rJU{cnc7VG(%GF4A<)880S38Q;ynzGvJb@J?c+ z=~JfbipncLck|bGo@Ei2Zuuqg)8NwTRf4qR^s7=vZe4eSUv$q(7gcyiv`u{bQ$@M7 zW;?&@@MRW(_h}Oz4qAyz@{& zl?T#}bLy|_Wwnth{#_g2a#4kM!P`XUyBo^b$fo{hHD9#|yf+_d`kdF9W^&WC27a^7 z!z=P=FD-NPeELcZ$66eN9cRov_sT!tT<_iR z+Fvdbc=tHc^r@{^hRHIwrFjQ3<*+XBmRR!ik*0lyEu-aY)n4~@ zziM9<-rtTi-3QQkr0kGuqqn~E2FnBQ>_^&h?#(w``mgQuoV_P40>AeKX*!9UKT`Hu z_L}#0>)ampDBcBc_wMdLN6Qlj7JAKc=CBC7-yCVjIoE%zZ1~eG@0a{nUG%^^yOE~- z-7RBe^>a^o-GWl4I6Z4&BtSFyVE|&X?c9O zw~Oe1UHb-{2hwyG>uXcx7h~MCK__x~sKPtiY~q>cr^*9QS4m7Roy{WfPB5e$=axsN z%Hw~{PV}z$tBW3Z2NlwEU&gqpa@*+I2|2*ND(;0j9cQI+9!NV*nU5yRyaODua!pqC z47z)AC0K=b>>%wpuP&G*>%LZ29N(79BJfTZq-lONV4^HMv!(FjHi37DAWffeD>gyC zGPsY}b~%gXfp=CQ?KlM*OpvdA-CNWh_1o)L|2&0=}rnK{z5Gx5sg(*(r)}b~XYZ9g53Uh!XU}CuYDM6wF4FWquQW{F z_`DR=6PYanPeYM*oJy;Q$#z52#JzW9vk0#3S1v76en>mcA9?PP7r)&r@>kb$2BX4r zN1JGs>rQ!ln`7cGnN!UG41p(nNYnb`&;Q8s3%?fkUzgb;@GK2!I{#QVSbjC=OYzPR zSuLW|iiToI{r6QKNYgjabi7TDdE!?w{H@I~{Qg8diNW1^$JzV%KzU(NCi%^|QZ5pB zf`zo>Tt^ek;B?`?f{ksU^~sN8Y>Tdv!k(?|rtx zBJjKxY5JV-u%U8OyAQ=p&!4ggJgG*SzHh1LEwa@Omqe=~xjpPrJQK8g_suQ+W&4L6 z8NZa%BJlJLY5IpI6cm8dnYu8k{ zq*E2Sx|dDhjyck_5BEY$PW_>#yfdD~^1z*Dr0E{|zhZLj#G3N_;H(z0q-$YusXOg* zQXWWCJ)hc4HmF%oR@<4&Lly4n+C;HI4Q0hU8p|eAZ36d`k*3#flR7fnq84(%g)ElG zm1nbyB9n@!9cZK-XL{c{vcR|&@`seH7QuTxqhBtq@<5vIx!Y1uilV*zWjof#aBmWK z9q|+3w4XSplFYlSo&Qj5T@1hB4?n$*pO$x=g6|iXcNgg9*Qve3BG3k%stymq7=XTr}7<;Fjo`pdkvG5j_}{Kf+O zP6b*Oy;)PPT;r;955UJIMpTZvA7wlwfpeY@A{E9_CEY4>Aqclq#;qW*y6Yhw5SlT1zC3=~<|7t?y?`|JRkprzf8|{M z-0QDendA4@*hK!Uz2(z=3;3Tj+-?!rqe#=pFzPP3Y0Kx{g(d4^xQfT`EW+B6yu~8$IY63riY`o) z3$7dJy)#$F@bi_p17&}{w&}^KazA}zPS3A)#_%(0NZX%LY$d15VJC{YPp$bNhM)66 z+Wwr^^v9>mmR0&CF8#behM$!{+WxFeslAhBHQ|T_k7xDp6E3)FwAX`E?wcZ?Dzz)o ze{C*{z?CV|w4(1iRaQS*NEBZ2Neu64$1Aiy(=g7NC>ORIE{c72G=}#DBW>RozHjvy zIlAA=BHxS?F`Tg?ZQomarfYBc?z#MO-d*p;@QwtW-P?DhbbGG7tao=s`N8~MF+9~p z+CJ4!>CsHSF~6bwt@(%QtjK(CKGOE-QqAA;%bFkEC~GzS&^i;wnME4SI0}4votW|V zgY?~PXLr_-pY?7jA1b%YMHQYX+h@WB9w{w{f8RmwyRnFevzHC@xUI7m7c>6b#Cjz9 z9+r~zWXac>%ZkfRS`j4dt6Fooj@;a?r94Y_q@X*_sqkv4p067uchQIZhxRzP0e6@2 zJo2K~Oe|mdtowcaS(N!6B1#ZZ^V84QBY~=#H#HZ-M!(>8Upa}0BSif5_updO2PZ88 zReyfeLU@lab&q!)OvIN&93kTBx*670p{mM@DPr-_H{CBD>`cUQA}$f}`UAb2;#Hxl zVIx=U@4DJ8HavxhPl(7ydHnar2O1-RD%@44Z#*F)D-qL5%xH`eBo>VEMXutT+@Y}= zgI1#h4bQ8_qHR&i1>_%pD2$j*^6&L4^$1jt(}lB?sbb5%t8cT z73Xoe#@r@Ipz7nMoy57pC){`Ed`5p0nEUD?c~pC$%tj@$vd|?w|tOi8vMz z2S2E85vcm{l^eyaPhEC1U0h9sdCn`1&DIP(Q03+BBOdrBtG9IeYXNbUu8O|}6bV$B zw*ID2_V`m1@hAcxNfRqJ-Ya+I6yo^!BIfx>bUa<7Hq&M&#OxaJ?;VGU4~bwNBT)pe zsT}9=FUHCZEuT&z49%)w$6I-8Vl5FHYY%CJk&J}dZKJ!wx=)gGH{C4iZmn(+xO2z5 z(H`wg>O7cuJRmTVkuZCi^!f7(Q{}iZnZ)7Ndm19aZKL9fGne*AwFeVpiTH#FjASIt zt}5LuvU9r3nYm8lnVLB)0xKEs;&Sh64<>REv7^R;1{ldmm>uZQ!`)Wnz#1fQcR0A( zSh`2<%yrxaH6LDsk&J}dtq=RkJKVa{S|qq_R6!rQR$qA^x8AcBBN+*EvJpP#9zEyl zkl?ma1+SjKgP-#!Hr?!T?_ng0uwJ`KgrQj#yeb2a;MJ}Oj6@OIBX|!c5r$@!c{lTw z>-QkNYZZZ!C_;N^PXEo99=qxY9yd7h+=2XITTYFMxotbC-v@g2Pu#}{5)UuSEhaSS zkxs-lXA`LUVsQ@f`@W9p1Or6b1giLo*x$;7As-`1Bt$lGIY(+bL66TrHi0UheN@Wd zBArljCNP3?6!caP9ugQqf_t2MJ~@wI3|A3UAsu>9Bkm)CD%_<~L|k(=fhyde)7mHk zRk$>fHoX=+dhM#VO`wVutYpRikKjy=2hz3&kIs~x;NNn4^RCBD zn|naDlL=H|`+pNFvvm<0ZkiQ(7~1wg6}7!Qe~irU__5nT?p65U>#qCAkcJy1n$@7f4Cqovq-^LXWfwC#Z^YJ1m4G;Y*L zbZ9wC#Z^YJ1m4nCi@riL~v3Dr)msqOR(n2~*YhaahfjjN8F@rP}=e%}-pS zipQ#JCU_;J9v5lz`24T-Koz!)pCH0vl?M{R%u;zE zO{>&G$CmdvlT~@3irOCC>7+c8iQNUayvbLEL@>Wr9!NXR@@j{dA6)l#EhbP!ZI4%5 z+*irO;T!ua4FhkN&?EojhLc_3|jpo-eDYa@DmbGkB*Q~a1n+a4KJ|4PL9J;?QxUlIH` z_=@4xyjkzq9;gat9EwgN=<)eSt-SE{8oob})>{3)aT%5RGpa`TxiW)Y7vooasl?dl>NdGgz?^1JBI0Li^e0TCQ#(l?%e}13y zE780%GQ48K*Kz0(=gfl))#KtTCg>~mdnS@r^r}ZW2Yv)raGM{&TG7WdMlupiYoZT* z=4VvTRJGR-T$OrU(`J?Z3?hM%C_;N&%-Tfqe|%L)m^Q2MRY~_#1A&n!LVIuyd}Zu` zglV%1d%Z(E z7`M&ulL=IrHa?OjM$N7*-^=PL52ND8HLEc6OD0fd+N?5X3l zGQUqJwgd#KOq*3UF`PW22%|zjZadDozWwBFZE~oqGLOrVy~Xl~OnG|>B=mFs>C^q? zu~ymq()aCcfhyeJHIJl;178f0uh-h|tt`Ig9VCi2&ndDm>ZCl7roV5nVz^vTZM&DK z)}SS-aDUe(HoQGrW_s~;uR`T+&5>v)=r8G}+#u$cO7W1UZ%LbfpWOE760hN3t=~q~ z#rt!Jn+MZ35ie?)fw=w839@5>5#FNiJzJm(_mFLmON++JV}%xY2U>MYLE=L%hv>7c zgBbf|3lC|>8MpF&`SO$pyuUK9X^E<;eY1;x_2_%BcQ?sEyxMHKJe%o7clOHUt4IjT)yB#O}Qk3$=t6Wcf5r#z4_ zZC2qNmCnzBz(^FKJ;pT{B^Dl^pgfQ;ZC2qNm0pQJU?hsr9tB>lDo(vPMR_1$+N?6q z6F+xUlj-!n9ds_OG=E z5*Udhw8#5d?vbPZbA`uLMRL-SdtteG}dya9vggO%sRKe zV#2=`9eA|v>`5pLCRmajA+-E)ePztVJT^lU3d183h2=2h8usA$_vP9rbuvqPt{YnuY{2MqAh=+H)AbayITJzk;p`fgN@uU9xkpU;f3i?2!0r> zg=<&q|0EKbsDs%hdH1O;v|`!}gSBw&hVg$AiA?yZD=Esf83t?N+709X7vaW3p2>9b zVXzio`+1(|+Bi%6Yk&6b(J)*h(bw|Jk7zL=*P$>_+O=;VzLrS*Yk3k%zB`ZiIKh(S z2%%j&*S?)I;a`gmEZCjL3xxqY4-+g&ju0CAq^9hv{rZXt|5|iV6S?zvp)i5Baku6WczER?+aOx5B4p8Y}xZjMUYFF{=N;OR2nLt+IjsCrm?1I_z->V(z|L& z$y*y)%UYO5O*-DtS##d)6@|mY-U&L3_WI|Ee!5EzqWAmQ%xEY-=6;u5-`w=99#^f* zHrDFhKaZ;1u&Z0+_)iKE180=gyU;)XxnYVJCeW`9&x|r{S?FzR>Iu7}T#~m;pqCmR z{j#hM2kYtYwiMI1YsbX+5+SY^$fhRWZSTGn)7Z;m*|Yl1%h|OveafZSwsB5zikfMK^>Er--6pG8WyaN*m65zL=W&=|iBB^j*X{~ajWwy_ z1tl`!UyGJGyM%RpVS**e5uq@!+E8Onsv8Cq{Dh*P zQGp4$_O(1ZN$Qwz7y-FvNpeIe3@@#mM+u)6EiV<^r-swYC0LRi5emc0!N&-n7A-F~ zy)c+yNpeIe46h`*VKCueiKzXAEi5LS2&szD{5(dTt!ZT(j!II>NP&_b}p}f(LL?--e(ZaY!c;?R? z{Rk5*Nsb7GfiW57jp8IS;a`gu#%IDanC>V}m|#hAL?{f5Mk#MJDv=5QTC}8|^yhBf z(Wo%NlH`a`7%*?YH{s@oSd!R^q^?|hV`Slc5?Po?R!g4i=Z$E~-+vP{4(Ep9zg1{` zu&{Vm62A#uyZ1%M{|kk~@BZj~lpnwUCVW~nn3n$!$0HH%ne@i)c}}j?4WuvVUVq-8 zn|pok+a>OOgRqj*N{$dp{t~sk$+Y+noj$#LtKUZCRQ|QxKi=kj_kKv#{jW#(5+>yO z?JtK$h!Btr;cMmF-^E`1-YXFz(GPsxa^ircn-o^xtPcUar{0V9L&rs?-Z+x4{#iO@dr_Lk*w z`IM$0oT%8ghEY_@4Y{}VAX(m|f6MWNM|DSoz^`gB%^x0W5m|gAtB2cT2 zW(gB>M{bE*JbAJ6^;RK<^#9(uf2&^H-0gh~g0<2W_$n^1e&5;Csy7I`>?$Y0`eI9& zgh84mOcX8kRou~4A37OZ3lZ41Jg{X>xtc>uj@2w->*6QjoQA(btNmIO8*7BY#A7z- z6_rE{n{dcdll*JB?^~Cr?EVuXd__SsHRiJC|uN2>@D;Rlx zDYlutZs4G>)%q5keoG7c!j?f8$rBr#m8)0qP|A~PT)A9|C2aGioo86wG8k2DmnwJZ zxIwTMTN>6--YynA-+i8X65~G{25Z%u(8gXlVX$*xlUP)@rz-?ER{TgU>i3jp2@`Ca z_(HnZSI&_5>Z<%(eGG!NO#7%*<-Ne_Ynkk3un)EauIEi+chi@g4}UvjZ^j57OPJud z#n~K*&pUtYc|tvZXP9O!uIEjnIEXzS!4f8}CUmk#mwVYut8cR94E}TCnEJGP6(i=X z#i@?3OhNQJc}z_N!4f7?7initIW*8KC6_lg48C+Ft9F`?H}agdxV&K;4n$QD9a@Yx zN+J`MZe#CnG0-ic*q>ox<3QRD6IE-Z6}Ls)MpaAM$L_gkpcnI{A2be}cz&Yl0D>h< z$n~h4KJk0=bWT6SdMtjA628`2)zg0c*8yJ4d$vgD#6x>Aek|eV%JsIYKGD8#jPpvV zSM+M6)uV*3)giWr-9`=YVqTy~jMD~$Mq06ipDWjeCcWShy$@w|b~WpvIw9szaEd6Gr?L$ZdxA`!4f7oMJ(%Ds_0;|1JCHC zh&dC6mQhN!ftU>csKx0raiTg6tCdvrYs*JHCqMrmCwvJLa_!#_5xX!m zS{yZ;gyBnAi*xgF!Y>(2$hChzL`WPYF8nOklKYWT0w$3OU&4f3`}eW?H&*cfdTg++ zS9H8;+aQNp)ihK_S*v)e9P0dEerbQdTD&?AB7L#(iX}{NcsS8>QD$|ob`?D{zKVX7 z@MHT%)9k9mO5bWXfXEK*!T7O+pDWjXs$15K_gdQH+D=qOt`B>R@U?{S%K}zlBMw2t zB^~1N{=9r{KSO-nEQj-|?k7U6=);S7-TR@I^Lr2rLHvcZVhIz6E96yk^AGmwk_5be zOT{AQG|zz;h<{na#M~jd)zgRlmNOBtK8n~&%$Z; zv~Q-zt}hE59AgbheK=b}he}&~lhTuom~iaMte|>GVOwB?|H2 zcjuDN;o)=@#QF;mF-R+xFu`RSyNe+XrxBOYhzAp_#cya?~H5&(t~`3;OPFBW#Ok)#Rcg|&J!{seGsqxVYj}%XD$*Zpjuz z2tUuIhwbMx@;^KtP^{EfNs*E$jGyN$VFIPZF^MtNRypmFgG{hi+mTz67KTSyB#f~h z!4f92Mdxu$qSlJ1f(3@gYbIFhlaZe$MeJO{5TYOmmN0>wbxa~xZ0DdZ{Xj9nTAQ~l zPdXSL@tV15==wS!J}LD;v4n|Uc0NalPz{%I#nyG@hmH)cPG8#~SPMCrWafDp5ZN-+ zRxDuxrNm((vc}8r_j@D4?#P{g?T;WxN`+Qy$(2v==%7zT!hj#@jwg!uDxu3rkr4bQ zs2|^j$rwheCHD8N=6_zl;al&Z@l{yD6q$<0uO``_}!CIWsIBx=9D0I*J zYYhGsZ^;cqJTDH#{7Qsv~)E3atT$!CG?dkI&(o(_@2!JK()u33+{v@8fdbz*BP~ z-YdNPpm_V@>9d3hPB-~>wo0%Xyx0CAuP^*8)`I`wM7-B{5a~Y5tnjb+aA64(96yx9 zwi6xS-(`Ze%$Tpn`561)yQf4v;QKg!?*~4dL;W4c?~9l)IuTDF{;uQuyG*bakI7ornjf15Q^9vn6Y})Ku|-?=e!NTy}UqU?iS**oxh|@ek*dTg=U+`_}w8;Y*m1YyWGqlHfgr6o%U`#F$8A)waI7W5BC}%y4_3^VI-5$#`;*o z1jhOTk&)CaiO;K37(JH}VV;TMc^r&o1|p;9RX`l}#@kuK1jgY5k-3Sh*>dWqFnaEd zi-w=YS{Ta=L`KiIf~X7PW26;Jn7}xEATld+a$`f?4WsAXLgS+0XBk?$O&~IQo^ew{ ztwHPxjf;jQOkjjQ;LiwI*6c&rO$sBzQcAdFaJq4B;><}9|6tU)BM6o-!D)z*qPn}3 zj3G}z%$Z;<&P|+r0-`AhDOW6Eg40k|6-Vnn7!lqQ8gCDmIMy;t$;wpGdL)SVL*wn? z^23B>r0&GOLhJZsE>(I({!AtJkT4^Z6q(^Yx^20=d`f7(mL*JZ-v=JRTc^~WlG(O? zpV&ucm%`6tt&dNyO^VD^zn6Z!x>owlxL@|aq*=lQ_kCcsH{j2euz7^WNpb7>J|BtM+xe& zRC!s|OZAH_J~h_{od0aWmX){KT>HefQg+t-V`U~TTxT%BIg7J7dVQt(V%D-!Xx1`J zuomYm&IbIpn0_|H`zkeN8aNErVw=ax{yr6S$BRqVkx@^{Y+tyRVS@9?va&C3sncSH zH)CjqH%zb==aXgq`+6_kHQRA@4kJ;V?p))TMDJ5wbpHH@)fvoGvxEtLTes!({*$OB z49O|(XL{G+^-Q6*HiU!-$@63gcWsN@4~LNmXTuGH3IBTi3qK`IzC1I$HcHlb$zP&o ziQg-h=i+``g!md?pY`>=KJ&GtC(QGw{{7Hf?FZ4%BUp={YZ4p=6aKY)Ma8sbB^L&3 z@pb5}7ENyv{P3q-?z%gEu753YLM`gf@P@wHVuB^f5iV`T&PW$rexa=!1{40ZX!)~! zp)i;*Bs7cY-w%cH;j6WsyDx=m2VWx3@~=e;-iJG{77Bw2mLx}n!thIo6chM^?u?r} zi)sJ5oF(I{q-;(+F zL-BAK@5@P+FyUWwofsM+OpXvO+;_(llMN#*;pgHyT!V++$%}`?oQbfOf8S3lp~7z! z9?j(E`qw@Y(iYBtmX{x4TJA^k+MR7858j?wG^l1WS@5 zLh(Rp4|?`tG2vf}7D~Q5#t{mG36>;Bgu;N;20c5snDDPf3l{8-mxaP$f+fijp)gSU zI9`2aG2vf}7HT55?;Hw)36>;Bgu;-VLoT{?32IBXZz<1W+Q0u8VX=e>|2jmVHBesr zk?0c=hJP(uXc^pIMkpRkup~Jm6b4!~?X`o6O!(KXme*qmg~0?`OSeBLlH`a`7-*ff z*PbUb;a`guT57ik84805LqdHg|9&V8_$8WrpRj)}mg@UgCIP=hlkXGmzcRso7tXYx zF!))l<=+p*Be^g{!i0YvBDh>Z;(B*Xc-Q3h5n=g+)SUcW|2kanCQ9Lz@;fwBMK!CM z65m?(SaNr>lIsB{3#-DhP2BsT5JLY=)GT2FdoQ^=HVf_Q;`yO4m|!j0bs9S>MZypQ ze~FqUOknpUlL!GI={Q!S~|o6&>VxGUNUkofP$NDwX@-Xw4EP zQq6rQ&My6;_g1ybeDX!y*l2b5kV&vs#?^_%fBn@Dqr$KiUp)9YS`GhZv}OqteFjcj zQ~H7*#=K6S#6AQu@)3fy@U}^jcqcu|0_VWOFWBYl7bh9I=JK@tV zfq6fCVt?U`(JW!Y?sM0!fgF6!&A~nwGCMza7_YuTelWpW*LMD6FG7A?a`WT*!bMKC zT$%LZ67}_lxa;gR9T@#E_|qche;4t{cczB4~>8vRF9 z6U`DP3O7G)FR1;DbAOf)57+f`KAv`1{e8KcL9mwjR<|29aPCB}Ph zeyXXu?EO?dJAQycuom8m>?8lhQR?BygX-ef-6TK45++RhSTJ{jD%UZSzJz$3skJUJ zuy|`X4>(Rwt=kVy03#M1VUoY5+*o)SkXAFgnF=jt(q`ufI+aRW+k zlRLOE=TxZl$IL*f8J)eDzYC%N4uqy1FsvR7jWDG0=8V4=?65L2Lz)4FpS=;P_eApNo#$v2&8tNW_B)*1B}BOCWQt zK3>c}1MwsXNh_8x!6|~#!K7^VHyJJU<&n__!CLmNxq%%IdwDT0*5#&s;^(~j407kKL}OARbJxR=I+? z1Agm+6{a9Q2JspQmN3C7g6}4_e;3zlb(DJT@Mwcztuc+d2S$~9!Hao`6SM8shx6;J zhyQ{c_F%w8*@&D+4WyvbFfN(FXk1d?vCpL;u>Pk5+*o)m_P41Jnq4TooWQ)!31k@ zOKn+mLHr9s?1LptaQrOme*B8q@5V%{qwq4AU@g-FSUhESlEmW*;?bnmtT;c{ zg5!ras`JgjTCXla{bBp{F2@NrZ%69ggCL~7`W^9L2^0LbI8Qj?{lI6aOQa++!CDvZ zb+IG$?j#WXK!^>pgb9wHWtG_eT~ZIP_F;mxQ2W@C+NZ_pGR_vXA6a07d#=7^`)w_! zLd8F3+L5;Q84%J&NxjPwCOCeU_1&W5fr4K9!31mNh@E3c+S(H!Gzdv6mN3Eb!>$oY z*#i5};_O6=!vt%g#jztTPM`Vho#yZvE+YqjtF_Md{VPs|lB+k^5&!Br5CuVGM$B2l z1ji3ESl^~~{({di5%FMxwcrid5&!BJ5GkCHU&0b5IDVG(#=ErwzL&uSYr)H~BVNX| zxf7gx@DuMM=IpC;D!`v3zkN1{3Z5^@5+*o)SV1?egp(0|Vj^PB1Z%+qq&`k=5I5k9 zN?Ngm367uZSq6O1k_p!0{*`5wT-(k5tM(21)}GOtJueVpAJ_Cn2X~LL3*^3M$L$-f z*<)c(hM$D5u%oiumCB}2uYWySb4$-206)pH(th+^+}Tkn)zSTKPdMB{a?8n2vaEqE zN5wsRFO@18>IsMYmfYf)ZEf^N-zEL#g~2rd*9_bX$4Saj*#i~4c(CQLMe&oc3sm=* zKsGO}xWsWuUsTs=}au?8k`-d*`d;T^gwe z^9LHlZ|9V1QYu=-e|RL0Y0H`l;u45^AXw|jp$2NO^OyZNQMbV{mH+#x>f^?p4I<@$ znyTtjOP$#8PaM;h6%Qf@h!r4MYf74U_5IRw_T$8Z^wE0J-BoH+zD5S|)LWI+CwcGK z>pEt)nZ~!TAl?PB1q5q-a5hH$(ER6Qh!-Xo)GbFio>uziHG9#?av0f( z(D3>|R0k0R!CKR&R#QtZoJ@vjGOMD#qt2>|S+g6&}Xrm^22h-iIQ zl?K6D9dcGudFLKUhWN&*trMQQqjI1AO)*jGmlEn;@ALM-wlCOBTb2;LK>U5`H^o{x zKX_Ud8GI-i;@H}z`gqe+di$aU1~LBKVya7xvv!FGlWnHaet=jFqRfX26l)cYDXVV0 zb08Ta_xqUR?3YfrnU&WdzFS*TEm?fbZu0kgHq(|>A*vDH?c*1o1$OYBc9>~Z23*v1Ul$bHxc6Ji@u%EdmIwk#pW zgAf~JEwMkbu*ZqqunikFBKEi(=Zc7J#raL~F4@))M;@3wxZX2ixcY8*yMCOo(krDHn@k+OiTrbOW&i1Z#=? z)qov7PGpB|G=zMOo%m!Rf$D0ja@eXIH8(9?5Uf6lSc*W&a-ifxvRCk$QJupLIwAFe4qLD z+A=lNzCP3OZQIY-`C@*JUb=mS>Wa0p{k`7a6;;`NE0fq6eM7yvsFSYrZb5_KH)Ptf zW)@hdk|txRMuH>lz# zZ9OAzcFkI|@@})+<*n)Fxk>b%yGuP?sEJ;(|C(ar{OV{F`E}vO_o7*T+Xy4?Q2u2H$B`lS14n`wMqlTYjX z&wZ`}nXr2#Vkhq`HX(74XG_`bSX8NI)7IPD?^Q;AT#nLu-1Uv>WRa|zwIrP+UXoTO z@kEd2`ry*NYSiDqDJCQi@-|X-nZ}Cv!neXeD%M~Kw} z+UgENzfpB_Z!rjowZvXx&NTKTI~=WxrW&V4je15GdMiN%>KwGIl!&rV*KME{ls#g1 zt8pXFY@ORRNvEs-uuxSm)=0A!`w1p7>4l$E^SndVQPiSLu=m0={M~xRbjw}qmDF(j zEN;V#HLas|^xfrp9F~<1L^}{)fM6}oO_TVuTuoj3>#to8fC+BHnZ~#%2pdFM)NriD zxoHx6GBncfb^1|BeZ>T~;Y?fBS0F}$$bmYMwK)GxV%+%FdR^|zsw`?aCb$h}8nc@q zegknCH5_Y6Jt8%N)Nm#t^@!9bRZy2OA$671MpDBujjs(CR8`-sNuxT#1L!!dj{3I3 z6RvMCWNEB=dO;r717PnQI~Rl4@uFrF2f(ytIUvq~*a(8P*dsTI*HYxtZ=U^GeF^(uBKxS~ z>ioG>Zhg+QWsL&y8HkM_Sc^S!llV4wDcx}9J=Y6oBIn@3>XoG_+}40;%VL7H*uOT3 zS4Y**x4%!Pe}_dek-5bas#diJZY|0*_TB+;21IsP6l<|ZZW2>}sH4~Q%C4hfQB1s7 zynu?`c-OTLrm^cOh_6BHfJLzud*mjOy?tZ7Iy$djeledx9Q&o9YCip%Yf(&FR*rdP zRGM5lU7vcw-Rf$?xH7IqeK4w`%00BWYf)@z@LoY=0UO-y#vKHHlN&M(!)R)`b zP+MRhOib9AU)?R8)wL+5(N_a;7=(D?ti`rs5`A|+sV{$)8J6ceTY$fmB}N#lC2Ok?c_h{hmNf?zGSE|aKyMd|EGCG_<73me3Y-?ORX zN26VznrZAim{dr~PkO0hO=4Bje-&$z(l5PKwlvF1g0}pGU@f*4lc-pFf|8%~Ync#h zlF~1|RHiM6czA)2OdJVigG1Vp}nZ1!;a!^7|YX z#e`Uslz!=@GHqG&p)EflSc`4NBr@$wspYp7_Q8Z$lazk($eD(ROayDOt(e5Y6*;y1 z%ELaG5NndsFP=WrmURHy@_QNtYq71E#JL7Vwfv%BQA~(6N$D3)pJ{woNh=^0#WcPQ1Mw6H zu|d{iTQP}&Xl;t1)maMrU_v}TX$8chn8uhTh$s-BfnY7R6_a>?*5(RY9r5~@5RXq< z0kJ5iu?P??+It;-~&eUf%+8rmo(qrl71A^ zmbDK(qRQwQi4VtPtUMOVmWDOLAYwg&wb)in;y(IN+t4$TkyIvlER<<{69-}qh!n6v z)?!;RiO%Q|4M5LGW;2-Ju~4Qhs}qPZCOG{?@Mfuwb)inq6Yd+67`H z2rFyq?CLVcuw?v-2_8LV8hd$zkWnw01z;^6tv89c zF?O{bV^}hN#RQMHGL5++5CIS}uf|$DT5l4^Fm^QoV_26^u9)D_Y^KqwffxfqW&v1> z$HGk_^Ml^{tM?A6AJ64dGCD7#^iq~&L|(?(WmMiA@fw}Br!JN1ger5jl0mQ*kC$22 zt)z2tHy7+wFIj z<-vISl2z^X{0jHgGxKUHo~h&%<&jCt8ds>Fn)`W6``(|!-FW!({X8#Ub?UR~TJV-V z>%<1kTE2L(nSSYLR{h*xwG@xTaCqjJ%;j%u>ko?+)itkHbK7sfpUJe@=Uld`ul;sx z1AAn{vBtP4=Ldh;fwA!MFWcAFRJBvJFbU2Nrg7FU`R(jku-|Ta8P7f2)|TJ$#$%11 zFuw_Zp@MU+p)J3UL2!?k3Da+{-LI#8s&0KdS2L5~5h$i{1}IWiQn)%&m+NzmlUcV* z%1R1L>avf+?{3=14|t<^yqUZe6a4N>Tb7g%DJiW{N_d8k-;i4(oTG@`OO0HV9Ar!7 z@XWW8k}f4)N;}W?ad=#JVNEJZx|Db+?OcCI>6TJ1C7kEgaq=SUPwcP&Y>-P z=eaws!7Xdc{3EK({4RR=o(b+8mp{YDv!Ny-agex3Jh;Z;xf`?gX}0_+ooD@8_2ucZ znk7thH0B2-4iXoM2hXK&YrwN|mL+kJxJW!$!UVTImZfvQrV@T=tmfr-MRTq8nQE#w zy>Ql^^6xisW({}$x25Wj3gy-1cLo{+&%`lpS$C=*RCkY$P}3iF)2zkwcqUN~ZzOLf zZzXRbQh5_DeOxLnOWsJ{Ox}vMnCA5wScQZ)x{WuJw_+cTwV1{^L70D>ho4T zb0(QE&z$rK`A4&a3GXY)WZsGi)-q4q~`Z!J;xy3b;*LS;*< zEbW;}=RJFCrG_2dA4{_u7)%`DR6&yLWPAM~6oVUrX-i z>YUyA@!I_VLHJriRQ)}xv##Cd|3Ua#ZWtxAIA5eV^FN4Oo|X_-ie+}bn3M+J4@&9y zubBHpWRAUX@LC z&Cb@OwzEEijWC*}p6a~Rys)18YOH3hy?t)lC+BJBwRrmxqW*>UftwSs2c1>jAYQt4 z$Nn&0JNN`vF>P6|ys=6p^sc0TA5cs$*zv$#RjRJjXLW5=u4t5+Fs!b#`faT?4tZdo zudkhx)8p_~8{gTfTBs_zdH?*HwW3<3Q2keEXU&S(M~GG_a_g%#i|OCeS_WZ_PNlka zspr)H$5u>Rmb#up|DCItetLG4X07karBp?G)^^H`jCq7;lGoO&KhLVC=1o#eto<~V zn)zb9vo1?5#k6HDesQqAvUagLx@nNjr|Rb49<9o6spIT=t%fqr&b4}scu^0^uuheJ zIfG)Yn|5mT@}UGLb9CGz#I?$ubnO!t)S=X!41(W^X{-Y%Io(;5v5+obB2Jfx`O8i@ zzlJmDc2#xv&%f=ZS!+0%x>r-*1pl=EjIQF8jH-nE$baHx=iS@I^nntwnzcTvd&Ax~ zv9hBUR(gaucrJ6GTBhPU`*ZaS;+b#%u~VO~?riB$O)-rfjjNqjYey8+wfmIO>*w9G zCl#*Y9R9tk$~N9oKW?qz$ifNoZkg>czojXd`d_Ik4t%CQW z)Q1_XITL4>e}pJeps9{^4ycNw&nqTI{F+i_I$O(0Xi!NpjWv+}j?qsxUSePye@uQ#f;3;{Q8g#KP;^0FN@K=T3@jTrH*rcxmQz_{q4G4uurU0 zrb#Wur3dR?dro&!uPUrdY>CmV#U;ih(w-|7SpH!dedrBk5M$=wwv&p-Ix&@M8Kn{@ zPIb-`=$O5%o={zB*5Y!-;UNbb)=|wel-1duu4xbjYu~qjtrP2vSyNLnjW5H>Hd8G& zl+}yAtFBp#OQlJCQu45Rxn@ya<)^0%;?^EZ{S}OLemPV_F^&1bYNu4T8AWx9o5eM2 zaXB`L)V~+d^%rN=XQyN~h_xR_sbX{EoC))*8@6Iu3qL8W*A~yJyDv|tS&K_0hljoN zn%CEv2mYmEa>5qrxt&X-QYkmvPU_;-j53Y7Bn`gTE_hiDKX*W}7MFGo4_}!^_tst3 ztycHDzF`pk%0;VlxwP}?=qie7%c{A*pPsk$6P0JoP{mqYUQOc39jlxydIe|)*!g8Wg0VzX{rQz{8(O}T@s^Ni*3au8egfbW|yd> zKYON%L2!%AG{PvW)SAnc^q=2V(yYa{ViGqR?NJFg%IFUU6g3ELk(oxXsP7>)rdL@# zwMQY%T5KyO@&2$}x^Mb|`m09i41!x^rZIk{^Xs-N3h2FUQfb!Wl5Y}cKGpiCQqg*T zx5GwD&uuN!*z;;=J$++VO1((!QmnQTp*rr^>*|LmPT2fh_EDI|?v$Ng)fX;|RU>nbH9Q%%6_Y45xwBpV z%SyV#x*CR`$Q~e%I%3bfa3I8Xg(@JDloR zJ2+#T{TfQ*g(q#z{s-6Rrk7zoXrbcE7S)A{Y0X+(JDWty;@xzPGiy}z;*X7%p6e)X zcd>%*m;U{Pon6;S3`u4Fe=!2zpsL?4;+w4Jd%&moK)THALoi*oU;4R&{ z)KCAt>5%IA{KhzzFtOyv)M`y^17}Wq@xsr{9jMRsUauw%a%?78>$!7jRGD>+oLB0_ zf;hc!puYFlI<@@Tmo`h7s8b`2%GbJ~Q{twCvH#9M{Z6Yj>cepd41%?C)l92W&ui>- z=qX{WJTp++<=3ha#rN1OVdDDyG-|`>M$QY(rH@mj@GzZeWkc0%d4ghswLTb?M)mx$ zu`{)W2JvOT9(s4?4eCt!cd_0oB4OhE`P3?Zn?}y1I3b2FY@s*5y+SSi>y|;VR-seT z>Tc^s&d8{E5cwN+bryY=S8rRBVD!~^HyZAdS=J9dyE#X9AL^Iu%uUs(TBv4KIbR_e|7?LWFCIJbA!0dep3Pt~7qSJ0|h38Sxe>yo9a zR!?whW~pQJ+pr$4+1Kjh$tCstOeKw;7Zc-;MyZp}B{%^$=6ed{(dExPsUH+dWe|oI z_1i3Kcl#{5L*=LRtZ`;vjfu14QmN6K6Pz6@B|o12Jyus5luj48f7GZMSnKVdqt$|r z^_`2k6^MK@qIJUBx~edC!rak2TIKn$iSuA_9TopelzQjuM$Y>Eb=95*QEJrArcUis zvJ2Ep9lugr*A7vquJ+I@VIpIW6zaX0#?H&@gvfZkgPLBZgnIeiVFtlk)t`M}AKBa3 z`JjgEO_iluQ{C4ZtWu=UjFqyHlE`I=-xjs#gi3m9qhfHL-ifw{zkV`&Jv|8CkKm8TFfG_7LmN4-{ z$J8q4cMY8Pj!J$^&(%oR`T3Btp1NWXti^G{IKzqhx^u&0YQ)di6ib-6Tq0UE9^JsX zF|{_r*fyZFK6>r2>eafiW`eai6=1bvO6asNe6L#8E2>$-#GXYdRohMtoWW6&x<$@M z=`ZFVRQD3=7zAsXsk^o0UG;g5qiV_<^)ySEsC*jbYH$PR^3!7Hsq3#+hyDtxJv%xY z1Z!~_LvMS<2kMPXU#aigcGfIm;^`9)?Wd9&IO88m7zMv9q<-$VQmxN1&>&dLEW1Y! zU9*cW|6INH=0MF7CSE)6uYIC=LnmgS*vEpiZv_rFn52$P9A*%##XD(P*08x9b@%7rOqgxds|{w_JxkwFHO_Z72-e~f13T}W-flSxr`O-^q*=lQw~6@T zuyRQ!^{Hd(@6$aEg0;BawXAAiER5S$;vf4^PIsrm@NRfq@_7e4tjye1N&URfvB&;9 zLiRQc6Wo?C4R2{qdgrTS7gftV-Hf;5H!rD4hw~7=1WpnF z@iGVnf+b80sQHAlAN28v9M%6)HRo5Wg{@9h!SdS}$7D?FoBvj&O@)@r%sN!7epFV72){k6KfpKqys5NX9__vzeGYS^Ex z-IV5XjPG$kSoxRQk{>K#V(s*3l|FYXFLj4J5v7~w?yE{7t(agf)Ay+iVi1UCAXvgg zuMuhSje1Kjb*Ij#qu(3FLk5a^wMo# zKcGe-b(vr-?w4Q{($3OqOP8azltfOS-5;h_MJjf3Q!t3YgROPSq-edOXhp>YYhAgYLB)O6(kr`8`+O?t zOG`=F<@6a}G^5HB?BS*^#|fwQfLIGc@`EKz+`OJyrAyt-OWjEr->q45vucI3VuH0e zPBfY)euUBHsvS`~mbt4zmox@pDf!*wvn3E#1RxOX(C zTT`=y39gT^Yuy3|Cr%wv9gtQ`uolP3vR+&0s0SdbgJ200TpwdEq;Z*b>sC+dZjx4% z?ySYBfbm@rtw2cGWeF2pyW#}Njiq#rL9x1V5uDmg>CRfc`{z-WF;);7{m7L)i+-VF zQ$6flFU2)7YcY*_H*I%)vEUK4>3lC^^n-21w2xIYn&{fgGwZeahZ=d#`D_x|HdoL| z2P)|8`Gy+t;J0ELyS?q+V~XM(cs5w)^ig%RO--Ft zE3-kc7Pq1pxdU+oL;wU!m>77dvdZ)OAkPMO=loZ-9@Ji+-_<}d!CG7v(2oMq97G+Q zPQnrRW!KmmiboE>$lqx~MYFZ)Fgy#i@Y$3dA@N_pyfwOPHuJx2F1I$#5?}8oqi% zrJq?|@BKcLL9iC5f@ReQk^)8hspb+cTJS1oEyck`grTXod7J#V_#DGns4 zYQIhMQuh>yiU+30^##EaCZ><5@6w_1tD~7S>o2~qZ(GO@CRl4)wnnP+d(*ts{TM`+ z)Aj9wAXvggii3^ZFhc(BM@?Gk&)%71A4GmI!CGbFo2ayXrg^Em3q&-Cr65?sM4jlS zZWy7_+Cim9=nr#$Zs$PiGQnD(f!Nr3nwPpSgIE9}GYFP2aqvJWj8MH> zA5!;W?%L|juco+pz{wZF5e7`DQtpM>N2$nFxscu>9;GIG`OyxVuH1HUrkVd+#ToT$7K+gY9Cc+kRL2zg7XP2Ct8BB zXc2lLb<5nXsa7r==jI3J&9b|(s&niX}{Ns$-XCv;-fZMaYc&V1l)Z zOjhdn>@i+`bOf;wgtRy;VS-Z~w1^smlawaVv_i$)PPjsjpbV1gAPyz09nnep;nCvmOM&`HxME^pAMZ7_YOQuCb(6TR#d_Wwa!ei zQ;{AnPA{+)wnBY-EGYlqJi$`(81j0$w{z-3=9~hHy{E>A3lsO{@ zU4kV{NS^y+@8K|Tk*JwqE&sHR0`?(1n*qUrJe2OzX{gD zxpcOi;~q|34@;EYzr#E2vldRvqcd3}p_l|~;oQFP$*Zn@Vu&&c*5Yx$NC=YW{8p^R zwrLVlUb&OioG`W%}Y2_2Fg&ITsF)`Fi{C60vg}Ov_KapHJ z$YHP+=hJ_O!CL=k%)_Uga;*mX@j5ZlDa7J3%26;BVqqdu$K5G|7o@1v|=r}PTrG|JfNB( ztR?q-KgfJ5)K}rtlDNg;Hu1j+*78q3O}3^EhrwF@xu*X&!CL+)rT;f!Xwey`{~ZtZ zkPTm(kVIpSp1q~V>h{DCmZ-VS;F^K!6$%3NE~gKtE_*m8!CIVy?0vYsyP$Ah@6Ii8 zGH!^znp;Zb8htAFezRPOz7?=DQRGSI-8 zfzk6m7|URSYX*K>oJ0fS-~FNSc9t-KQB@~0-u_AE%)!wZJ%0jY8BDMir#j9O0?`Pg z=TRV7!URTDoyd6m&L*vbUt%nL3C1#*U@a~^IM))y-*e~K2SBid35=>bk@0qno(E<0 zJS#>&m|!g_l~Rj_#=>6$G2bIt!URTZoyd55fv9tVhTdEew=&#DVFbyE%oXJY5f4H} zYgxhsW}TeKY~PZ(OPyKXToDtjg%KntGFOC=K}SXiWpt1wOkmc@iOlw4uE>$OqJ5#! zsPMB`3nNHQWUk03_J&5I!V)GhhvYIV9g0(Pa?L=lX+Jl(yjkmLe2~Ks(Dm$}$a45#YUq@+Yg0(Pa z?L=lXihw8vA^?IVOmM2>tE~;qg2yp>o(E&$Ot2Ql!kx%$#+~)eg84Ceeioy(EMbE4 z$+CXkT+Jzixgwd{X8)7(26H-2WVY`vh?hXfYz9l1;8eG)L3WB@ZOks+#ppQ`tc5up zCoIE zBbXnvOTVDBGr?MzD{>;UeZPYE6|+nGF(1VeCODt4OWLY<=Lv5vm0M)a8*W7{E7zy- z&P8v&mL*JZs#_N3QiJoo*;gi5i(655zBahXBUr)&r#g1hIoT}uhc}nX1Z#0C>dw~& zzXu^L4ojHeRJW|R-WnYI2XmuM6c?1}jyZ$O_YqAR2(Eh!rU;VS?K$%fiYU$6r~)1Z!c9juTlaTNlK!$XcAR zgb8kU@m*1^H=Xyq6+-+h*22mmC$i#qBZxjATAX&*6on;Bu>at$bPD(@o%mU-#l3r+ z^tXFYm|zJL><5WA?fxaos6mR;X_MOZY@+IP{XGuXasKte0|%1et-1F-eW-f`YsL9m zj}g$8KQ|16`1nR6_qia#bVxV!UySb}bYF|#&O1o~A9U&Fg)z2k#^C%C&*(hW8X5#^v2Eg8{qY%tKNNgM zk8NVwITKuCzy@1156*nJSvC6os;rK7{I4)MH`C2a?ewhJ#Mz!xzMMSRJt6p6vBj$L z=1iI;OklOK6Itcmt!9el^j1Z!dSw9c>C&dN%KI-QERKfT&&!~fVi2!c&Yc&UIRjpj?*|LjsN+#Tv{0O~=Buwy} zg=KZ!yE#zwLNWWdFUJ@JYngKsS*ri##CTsQaJk}=fi zFjE(+)q}KJJzVc{x?$bB6Zzgi2w4%|18Kz)COAbbYjm|!PJ*{ip9$8&`h6$z-NXDVx7F$ZK0&Q+rq~S2LxMx z6Hv`tY%>Vf!fp~y+m9PKL(bMh7+0IT6wLh28a4Zy)w0h-Si%Ip+H+*rh`H{r5sf$6}>f50P!CFHO{2MrmZ;@l&Z;_w9 z^r4-v^ei=O(h$uOCa&)MC-A{f4V{Za(#J z_L=w!`%JKei4Aer0|)xobMh1w|0>t>gPcKm8mX^8e#OWSPHFZ&aQe`-4$kwXOQ^R) z`x=D(5+>5;Na4&5?}T9W{Lb0YZ;bk6UsuDEVJ-HeEbIG$`swhl7&~);D))5>!xv@ZiBr+et?*7EYkq7I+%k8KdOqJZ z#m{0bv%c!Futo4?>_(F7in|+0*r#UV-1*c_p78!9Uw_jhI6HQOYB_t3;f1pn*IigO znX6~;-z%T1T@T+iYEdS*CPIrdbcb_(ZzY|6M?sCRiJfZLPo!3sItpJC2mC!DCmfA( zWTz0v-6occ+j7XLALceN;@x#XnRmVFJ57I$g1gWCC`Pw5&A0#|Aa_78!}XMVMeMeAVp8 z-XfRWy+wX)H$Kq(WD4CRbw{ISV4E*<;$fg@QUhm#yW7I1V9~(*``1;`V_h{%n84TB z0ol3bj=OV9wS1GDTF<1zZivkcg0(80PT|ZQ+`#$6-8JHNqgS2D6H@B8ceKr~92LGLeD-5^-&t3@fDR@nXGl_>e%dFDqyI()=lYL+m;Icr(#mlq6n zOP5AZ`YE?Tu-2s#(N2TW{w^NNF69pvteZ-=%ThqIgb5>`tS=YU4nE!Gu3GiSuZjuQ zI^8j~lRdl}$*9z|gBNoDqf(4NuUNu_ndep8cMMveomPo;W*7u(aVu(BSzC1st_+@1 ziAUa$y)44*HWS>6TGrCWd7QVlZd7HT8(_3*++K10Xjy}oJ`7xLyi8qb_p)XQ6I|Xf zPW|Fa=jhk_RCMzW2EkffKVqMvDT|#Bxsp`2dtEe3nBek;-7l)82u^+SxSH7}-XK_u z>qpCKKkc5AZOMMMB~yLP5+=C3VUMj;rGgdGol?aH6*36c;`$NaO}thz*z)A}97nHmO%RK_{(fBdPKU@fj6E$fSS8U(ZE{#Kp*^SWXQ6I|XbYuUeDf?eO< zqY4$8Z4j(w*1HWdcMYznzFU28c&=gz6I|XbtI<;zVz*)6s3Mgb$Q}^kT83*M_9ZN9 zPsvvT1F_FU$4AMFT88$S2#3K0*Ah5~H&cV)8tgN1vzoil zM7Ty~Z<1{V?fIAv!N%BU;&ha|&qTOJX2P_nKhM3a3STL#lfJYy_P`BX!5+A!um>*o ziVGxRr`y`t>9$zRUxD-Q*KnT4p1JU^wog~X%NEmhhS!uG<-%Hb{`@;I6}#!)>Q?O$ zV%P7P?M&Dkw<`9=Wdgg)1umbf?tF;7ahb+`8B4x(CJlH(zkIBm#$I!Q1K0z%B=*2v zKE-l&VyD{{*y(n|ynBHc3fFLwuxBoIf}VBSx%f>!ePn$(&05*VTh1=*rfXq0U6WW6 zS3WrB?rn9iVMc=}a4*VPjGb;LW2alD@$FKsBEg(XGU!H5Ce2z?`b0Suv77Ew*iF|Y z+7)OTJQFye4vspnn84n4&doEmobuQkmubt&R&rGExo@(lJGH*CU#}bOY(5j`yu9&g z*(J{@j-76sVW(T{nd`_N*pqjaM$DTO9UCmxq=|jK)MT5ry8oNXnStGOi()rjlXyGt z@ZhJpa_Qquzd!Egkrm`F^rb`yAsVk(q7RZVHw6|bC?QiArH(oO@a)eo{zp9r7S>8T)Dffc>;nwMyZ6E~(*_E(sHq-bjJ}!5#T>GMW_|KMRE%ug7 zqHSI~n23G0&*e>0OsxMjl`{wXY;VRs+f3tI{a;@Qb{XTSsT+Pb`kZX%CEBHS+E=LO ze73I|O39hNLxKxpXQ~PFH`}aLV0*Mv2|IJ|!_M3$QL;*>;LPI}RCDaJ%>=&{)0Wj^ z(=@eYL{Xipel6X%^_4&`?4W!CJ1AH9?Rp?9c2F*i9hABBU=H%(RFwdtf8Sb~wK)Gx z;$Y#*cEi`o>-H&P4PyNK+krLMLAf$^P-YrCv3=ao{(F6Sy?%X+W-TsPCb2T09F@9~ zUhrvUgD6`2e&9HEP#%IEl$o}yH;Ywvie;~?69-q;ti`3$B-;IS$hq`yX??^gY!J8i zSk4*jpnMWLC^L=SzgK7U&~ZPvlf?Qljt%xfAIR|d^&s8)CRHs<0vN|c2FLH z9h8~Ix8a#{1s`O6QZMeEMza=|N|QK#zFx3$-W0mwy}gQwt|d}A|7^0I`^BmmWg2Jw zmeaviNojQaTL%?uak=8~aQe`qp23CRf2pqR9cmCSl#6zLzz)hwv4b+xu=A;1f-x12 zsr+llDc0ihY7!6A3=ii1V36AV;yjy)q|c(AZ1ZY6JGWF)Ok<|u^&!DK8Q)ezGAG%r z#a3hz%lc1OQ@<~)quz?q+@^Bd$97{`u{EZtZ@(?9R~?Gcti`rs5>5ZkZLiu|Mh~B? z41(KQrf~xC-qQBsf6JhzR{OQTe z`d(rNgWwjKY0FykVS(W8Kz4m?c}C4zT=Gq#MT;iE1Hb>ShJEy%(bBUAz_ew3bvGfn z|KxQw&ps~uf`|PC!&bBi3Y*m0MnS2S=KAKK7OO>KV*vG0dUDT ziQkrt46asX)a%ZNhL^!U3e%Q#{Oa&v>(%X5j+b{Co($WHNyNUnEieUp6(0%hRUGy# z*#qPfir(G57EXK2ah3?}RU9e17(^n#9MGI|s63C+Js0J3)v02HXOeUdEN2<(#jv6Z8kz37WOIJ~xS|rHzB7 zu@m%%p`D<^eFLu5xYfo^o|YBdx4x6!`dquJ_ilV_%Sk#|K^&KF;0Jco^fgtA>#gj+ zr>?Ry9f?&1S~tR(FS{Q;bS{E8zH!QWCRmHl55wL&2xAY3GM(P7#sq8e>0{_SBaGib zJd=>LkqOq~bI>sAj4-x?n3V6!>P)Z}pCyIyD-cIP*t7E(F=s9Fj4I5H22X-G(6{X- z4uiGKle7LsJcKx#Z-GIu7M})ZS@%6cR*Y~MtmR*e4z&IU;p%uf>jKup`wyKLHgwWw zx~8r!=Vr?JnR0d}pUB4fZ&@u6^A(84o|)G-u!IRd0S@P8fH($XR{oM3nP9E+tC!jR zPS#SJ_jE(K$_-*ah$WxAP>m&AuJ}ozxX3yjTqSyEc)_Q|$&wdRDLEZVuKoK`rseE`V;ZA_ho90fKO6tpTk&(fv%TCmGzpd@M}*>WJykU= zKZy(z{!GwP;T9V50mXfMC1%n8dBu9k8@bdz2A`||# zABLp18-ysz8@Yd?6g!k>NgXJqQR+dd z8>KW#{fPPs#1+`#FGVU>VS>*bWEwmCfyjn1$`y;Q#sr^U$TU{5f{=Pq>O>~^6j!FP z%O(h^7o|>Qg3ktI8f!U0NWCa^A`^UqAk&s5wHq=cD0Lzee6AtWAwud!sS}ytJYYIR zNWCbTo*W_fnGO+BFFs26G!t@dSyCTLy(o1epC`=uY@Y5Y^`X>@QYW$&pABgeyFe5M zaVTT1jZEyES4;hJY^i;&WiOj)w6!3f1hMQug^jGmv{|ksKM-?;D7h8|``}avNL;Z{7{YF=)Qp^URt??T>Izi$rHjhXoSJET%%@i!!`&bbYIK2^9bS9B|%|* zExs1Qt5>`*m|%%dGZBipS0}n*FyUW|mRCP|VKBjxwZ7pGl-Rms{`3r$EiNA)V7(ntdw3DpU%i5-fK9FS6|#5Sc-|7b=ykYOk0*% zli1-2b-@UuYu%lJrk~bPmvdydnZ`a|2t(@L_|IQ7!gzP)p}?A2_0=!??#D45daL6g zZqKe|5LuIc2&_omSk=G$V;s|18|B6PrO7SC7Y)Z_c&-b9uFaaM!&~>pF^!##K%77r zcPC~PpE^toTYo#yJ6}t+{_AydOuOEz8*|A^COFra{@;W=iD}p0O*RZaJSODYvhqB5 zsCuD(zctMge>dR!yIeBf`S$%l;fK{#|M)l2p0`GREJw_D4{j{pYqvisb?9oe#{nX{w*_e^RpR6eX%gx zWQ{w;1LRqT70xo0DEpa(D(t^##r`ZDVt-O){@v~LoGZ%7NBlV=*nCfCMJ#PUxs@V(~xQcTAaBUlH3#9J}fvy5@SJqqd3W8{3EWySZA)!`wpq zJ91Img!#Ybe=ra8GrS`=O`CDH^M&+;{V5`9O{@8`gLPcZD=hzu+>ClqVct0~?;6}0 z5GY#4?3AD1u~4yg{XG3e*}te4J*aoII-Nbs-pmSN7*(xyd6DJx7QM)i(Yh*5R%m5) zz4wOQ+Ll`pPi_Z@$sLYMfm+iZ1(dXADlwZC8XU;iyXd0wR6}3%Zz;X?{3zjEGFji! z!dsu!mkU>)U3!eAIBivnk=?AmgSUv`BSRTRHF;7=Xp8shZT`*qi)fNimj50{@3btl zND(dCR2A06C-t0O8FbV%Qr6`+Yn>4W>u~Wdi#--3yz6Y&Pc`kPx9kumras-JPug8m z|8_cDuu1>uDRtV>R&}3K+j`>K0oFS3CBvw~iz|w`SJ&uwN7nj9obRApeLC%63vzpN z6j%$WHO-@KZEH?8pRtEdN?nz&po_D0Ht9LLSJYMUwSEQb%VRrOhoHQQz#2tO?*;hz zP;72kjbAu_m;JrvhSA_dX=Y~orNvca^`w%_tc8FIhm5XqK`igbx|I1EuNR`@hHAWB z`4omxO_%I9T*Jz-QLTIaBKie>6!%&*;Kk?9SH#s;myHp@#hH0rq1Lp7<^Kt%iVb+} zgR>Y$Eh%m_-n}owN*^2Zi#VT6v)+5~JFh#xpdz+kGK_tqw7g%2n%=@U=%;b2ZUh^< zc?e%nGrOqVIhwVJSZztp_ac3WaQXB3;CH<15MGu#IMG*U>6A%RiJOC7|w z-nG&ZJrDjSMtqsgde85vh^3mFc-W&NtF-un1vRbSN+O;_KN1+#wD=bzq-K?LM3&i; z#iHKlSf5(06w&)PXAzV&m|fZS$%0zb+(;}S(VGNDOl35SoX~Vc?L+6q?d`tY`OiQ_WKRBK{1si2 znY{#RO^YCLlY|EejH+4vp3$*M`E-Qe!588}$I^USR&PaYnfu=G_Ae@reAM(FUJ@5c zOeTR**j7~GdDy{PwT8|Y-MGt8^gsW~*qKsLwkXu}TrE|sBY{!ax>RxNoU3(}Q#3!e zWWFK-Mm;ySF32xi6lzU-OkxFzO(ZZ1TbC+)JUp#!SJvmXx93)brOh>CWYHqBMWLoU zUSBecu{F!d7PWbJ0a5%jlP%}$VSllyT$pSh*wSd~5{Zea0;8~XsbbRYj-vFmzgb^u zA1J=m&METI(_Pu3pas*M1`y{$V398uyv{8bahATpAJR%3~C=J{;c3E ze23+cEef@!okR~OCFNm+E_JQKcY)5gXo1bh^sOhbUsbUEUjKbEX zif%4G)&ey--%9NR#kiB27+WisY*DD`=_`psB+NF5QP{dv@$Z$~R__(nc(;YLHXQuj z_pLq{uiN>{7KNJL!#m4Ij2T=^wx~AWON+s4E65g=?_4plq*iI!qOhfD+E^09NQ|T3 zD2&3kqKZau2aC6Vj+4JpC|*A;APNT+lPwB0jo2dbjD*<+F$&v?Dzun2Vt?f%)`i*! zikIDTi=Z(DWQ#&gBb~ag5xYtBB7srZR#c(QzbIPXdCJaG`#|xgua8*OA-8N%s5PxT ziB2T;lfWo!U8)Ey^o5>OyKz@)A1LnoXA_N|_{bK8nx5CDifkk>3fqb*I_Gq^9=PEz ze{oRcPxKV+%4C-<3N?+5N)S4BnHWjSSwLak}wrMWLoVNW39own2=- zwxWvPD*0H8ID7N4)ILx|7WNfJSvT3DP}8+DiDD$CkiaNxE2`*|yNLC#j`{c|Y9A<$ z6v-)k<1@(?g<8`RNsJ~ji3CPr>rzGN?}65F)k|=L+6Rg$*|Up@i=1VPLQQW!B{7Xe zCTfEig>6L@Ek&?3pg)~~zoU6^@OOj0d5g(Qon(tbO)J-LD51Y5 ziT)%o3fqb*P8T^K95yVIXMHH5HZ-^KMAu9VidL&Rg`QRVfFUSBijdxs!6%U$sHf%{VUWo zSB6AJ5=qnsF$&v?D)Q0VRF^Ll>sQXMHOoWv2o=Gc|Q>~Ju4!yiiEt5f+%b&swm5IS~rco&b+97;NM*^yNnpM;HA8O ziJFc?5?e`_Z4jfdt*ByNdXj6u_dk{`3N_85BXN*KA_H-TTz8ud=;xD$cy{YFAj?Q8wv~N zbw{=+)HLFkL^ugI5*USTMHQ#t)v}J+kb|etU1t=d7vvG&7QB*owo%ht*{97H?Qc|* zS1d*E)Dz#2zSqtBd%dUD5GBhz*Uh^I*a~P47Kx4|%=Up%cpR%@ZOhAIK!LHgyK3-v z$0b)1S4!NMM>}dwTR>tEi2-!9V-z08s`#+W**fj=YI#P6V&&Y5!tu#}Wd8~KO9%1Gc3yKyIA)?Ln%kpSPO)ZMVJrY?-U=$w5s<=9&oOMB$ zJ8S|SyC^R0D<_83J138J)U;k7iMb?3lfWoEj#cq;ZzZeM<0D&2$1aL8)ys%Gp{L~0 zj+*YUkl03I6bX#N<5(4+MICFdRgU}({TiUa=O3u)sXmDUBy!Wyj!}3VtD^eq#@2Tm zGV$*Vd=*imKru1C%0+p!qoz6T-c77eU7oPFv{hIJZlU^ArZ9;sB+Ppm7=_P5RIy=d zwDnz&6t?)6y26@9O>0?@_(@{lFZ%4srFE$mjhL+nRk9PdKc;utjv}dWp?AtL4pG~P^Vh#`M<+XEJzpm93fzP8*Yg)#k zlf>eikJ*W-%{Y$nzU zHN?>J57nDiQ3Z}?Kuz~vJsqtr-!g-m|7P&m5cud%I6Rvms87fS_$= z=J=#n%NmH*)4tFc(M=XS@1nQ3{x{YrwDF-OtYM-eFv@(EZXZ8EvpHsEvzEzJn>Xti z#_;|gZi#xY?`&9M>+J`O4e zn#Z*&0}MZhApO6Zi5$=9F$%S&9q8EEh{;h|zgk-rSZ}B`ZI@Sb>u=Y;vNx0mjsw7) z@OOn~HO701m2S=1`Qd{&o?l^$%JF+$adF!-y`^U|jg8uLsI^G;^I)FURDtJIsA>LS zbQ9~*-KW@*Jc5;I945N;S)|unKUBxx4D}iP&OWWIuOg4IHPhxRPxVo&ziNGgTU(oc zKF7R%j#bLQQ4gv(|1-rHH|morGo zA1!XJ6{}Xd^J>K^bBscLvf&w{_I{n6|L8-%Q7?1u5pPEo;7Nl5IX*MRDAbxZ>+m5l zlGYs9d8q`)DAbov95a639LBPIDo16EzHnaXFM@eDS8tBbOfd?zrX63IB2ofFd6E3I z`ZxS7)anR`-Seu5#mTqzs;h@^Y-@PD;&DtPId-fU`4?qod#d(S+6T4?yvm?;gpaHf zJz6wpA9u!ZjJg<7Q#@;TL*GB~x^neG=RS#dL@0}4%Xlk}QFxu8meIM+L$Nw>9P{^V zt_VCYK~1yhg0on?)=y){=_tW-AB;jxcP1V_6vmY{eEHIXY}Dbk#)h`#Te9!mNionszs5PzJp(L?wUQvGd zaS4u5*dA5U?(PK9U1a6CXj~Br9N&yu)B0CfA(}^d@|(exIYwc>qKf8w`UuPR_pHtA zW{SYGWz;mQvCdi1wN7W=`?@Q`QN=he7>`g|51_~~asEzc-f&7mhEaG_s-k|Ti=uR< zHhfmOVT!Og?m#Sd){>Xak24GY2KqvUXI_OP{+4dDzsQ+ z^sB~`er8ejIUZxGI9c|H`0iho#}9Sj_zemiDNS$gy|hCt8QX}zD516wj6zLkWR9oB z<$aC#_E`rRMqzuzdZRh+#sRUjY8#$nRogj6p{8rjN(tQU`c%DLwj^`xDYK8pWLKS7 zr}`e^-YhqBRTX9*b4fF*p2YKK{)_akmrhGz{|3eIlTK_w^@8GRZ$Fw-@j7P$pV?ul z?z!7g1V*+0>cqy=DlYkH6&ITA6gimpEuV*V>KMiF8x%B0nYE-c_DV$EqpYo(U%ByyCi z#|KQ>%Yr?hDFUO~|L({tCFB!v&-0KtvAikIdUq9DUG^HoZ&0MHc4S%wFY$I@R#P+! zj@R1^@J|9*4XsHdBv0p`ACdDahCnQEgR2OGMM8xC{~Wq*nV1ps4lHQq-paS6yilr z|Hqt1=28Sk;nvbx-c`%+pf%6f)7x2vvp%%(>8DgvX_%o{y&=f#{Hc-E;U6oFCd9&9sex@eurpXc2s z*QU~6(Arc*X>F?4@80O$XXFua_42dAZ=UP78~F*>b>^|#>RxXVGA=j2+qsgtnpK*h zRj2elw3-#8)vQp{Xv38oX@w+jUOgk{__r|XaKLN5V0K?|vA;n=IGNBjNE zG*+T*Z?-2TiGIcWYdDI>W4*+zO5Uvd!wh17 z9#8S9xrf=ui2v`YYn7#yRafq2t)@L!qG%ro`)`IS?$S!o38&h!&a)Q=`-%h=cu=nS5jHRs`M{^}koE5dGZ}+zK?P*cC zR-7v4HYjAxL4CWMt#3~gm@R5en^LumbrALKzISBbo>q&v&WI|szP&e$cS@=c=H-eGl~Q zX#)2eYT367=-bowE$%f{>}nRPf2Y3vxUFwb+Y+oFb*sv4+G99V-@f10x2LVWgMU|T zAJn&tAnMx}*!uRgGH|O@aU!;@wKnzb7pZT@qZ*HP?7L`=N#>r`gVeXLw)O34Jr4E^ zs<6^(h$WmG>jAlC-=4NkBKD%#Ytxtsk2&n1M`1q2F_Rv}isbW~yEiB8HJUsMzkRose zMAWqEsq-9>m8Ut#W?LFSPbbvJyAZr^rQ zygVBxt|XV>hwcTLnWu>(uP5tuM*ku6KutYE!R=!6ncO_-T@bHQ;G90*yRf~k(zdW; z<5zkgTKVrbt^B8H9X)r86HEPg!;7-6(xL*K-so9r70Io%ilizgo!lwvSN7*E7N~;i zO1H1sj+)*xdV3q2G&46}7aVMEm0{m1tX%a2j*qQJEVQPZ0j>+NS} z-F2jrKv>{#TF0LBj^Iu(u`n{?ck2Jo*&4;QbPZV76-lj^cgUso)M&z&2@@f#GlwQ{SHV5=v-6+YEs-$HXX zDqT@b4&qTmlC%<_aUW<+^ zI+k?%QH_5W`(RoVuy{oQ$8MUyEkvzp)S`shqW0NZR9fGT<*8*X+?_0*P=8gM`YUYD z*v{3SdjGxBd`x(R_0x~Tdgc3WY|clp4&L~mll~;~d-r~ladA|tHzXQ1w54Xu18<}*QgvtJ;h#!d%uWE3FY~u z-$JdwHO%-w!hWYv=9H>6ZCrQ-J|$PMHR|VKeR3vG#@l6)b>ez33+q$DP1Y6Gp{8vl z(VfI+s$Go2+Eqo1{T29#CBfEpxBDw%Q0vTW@Cg^0IcmCpMWP0YJ-7Pn7=^WYHJCV^3ylPYGu591XYm!+em zzapkZd$QJ>oMaxTsfQymn#2am9HTHNRkZ4@^LuSeTE9{4&Ul@Z4Ze~==8<7yc2<4A zgUkc-)3j0~eA|_jnPU{@q>33o>G{gNl2&)xDinLNXJc~*Ycdbiv^qYCXLn0lyHn;E zg*mCBaV^H56b-PR=(@#%;&#idtYdu#dEXB;9anXuxbvC9R$tm5^SAl2W2b%?W~)6? zDHm&Z=!;?QL97v4TY|*<(}k^Hsje^zb5g~>ccS>NT1BjND038k`*N~?nx74`4Wg#m z{UlbB@F0Ovn3F2jm#)m8k1t|Pu4J{Kz|2w8^Qa8fdAnTstWK19Xw$rG_Vy1l^HrDp zncMj{GIOjEnzv1&7YTn77=<~h;>?`t{MM9w*2a_vif1+bSYnS?GIP{47l6bK617QS z6y~IgUN@`r-AD3Shw~2>6qq?`x;B_li^pory%gnJx z=q+O;dXUIK0;4b|RqQWXoA=)8Yt2V_py;wK5A$pJP-c#r=GT%KM#8KsjKZ8$aePp1 zKK`|@b?%U@78L$HX{K@OM}~Qq8?~kdKCQ=_Rm~>bxo2<@_WjXanfZoU1=+&-w`As6 zBXr(QqALk=pJNo}q>8a)>hp)&vRPMC9w^R#&ClNX-H@51rgH`of<%527=<~hBK&H7 zKK5lcYoBL(EhsQ^)U;BeUnAZuz}>o^TJ4#h#o5x3t1|PJ2aB-34quX)V~uE9GKrxi z%svsLFeg}z?4!&v3Ug9L z>HW=k$nTk~^C=G$D+?539bAvg%u&;L1`_2-OeBF(n3F0tzxjg?SfE+6Qy#`nKQwDo+A0*rj}k05+b8otO(Qu- zd>}EG1V&*_s$er)^DfQai*mG81$j9(KkHtZ$LHQ<*h>FhG7rp;&J#&gA(4XwM&TB! zVmxodBeQ-G*=eg#`0XskYDe#od7!41LP&HWVfH>4g*mBWlv{hAq0%GaM_V=YUIjL4 z^Cp?ce7ACJ?t}F*56q9|V38<5q5=tw!Yx!q%N^}``PYxcXxb_i#cBq!+@;saJW$h! zMiP%-Jrdp|FbZ>0#gRIl_|#8V#S1#xKeh>>w*;?{c{nCiU|+{AlX+l%boZRZNfKtC zh*7wOs>u4S6F)Wony5irg`(Nca%}IjB{C1xbf22UM-n4RU=-%0iYiSz^Lp>DiPtN3 zSWrZ+D#IfBu9d$AsOfFZt-JDii6@152H?IkjQI_pCo^AiJeavCV5zSVb|)1BGYa5LVrBqRbpMt)4`pa5t;0D~!UNR58Co4}Nj6RqWZ2OGkm3qo#MI zJnhNHXW1;S(;jqxW?{{akCK_seG$$ouNxsV#~RVJh9q8*C_$NH6y~Iga*KNLPg6IG zWt2IJr8&dco>qU#%u#DvB@)X>6d{38n3F0(fAr#xS2v3_ySG_T1g;Ba$10DPM>}d- zdAMC4J}=iYVV<{p9A)hG$N@5QkK~HXXK5eXK8G5iF)Sqdk+@+Bh{Bw(4(XYfZ(sg& z+A`T+q3H7{oMmLaWag+fZ6b*uB$iX=7=<~h;&|V_yyn?u;&|b!78IB{YI^QWZ}MF2 zFhkU&J$NlPl4Xo+Ei-@DOJ{?2{vk8R8liPRNJNq_>q?1&T2RG=*8RDA-x;C_<$)sC zl#1->U%$)Du|{Zo35h@wV@Y5X=A;VmmHqka1vA9khS?N>nWLt2xE%xd;$x#lFlFwQ zF^au8UPEU7{2gO$7gUv*V~x<&9f>_8qDf#B=A??`-UIo;z%jy^@<371OJ`?RRhF5f zrqPBZzLRK10;8}NRI%dxK)$u(7;&r0Rtt*1f-AD>4;#v(9W||i`}ZK;@o8_-obqVd zsWOW%Szczoyly0$+bmFKjx|C(90`p?2nmeBoK%rqdoXXmxR1C)*XJlkcV;xZwY1C} zHPtSO86=!2bBw~AR55V%V1D*XAMv5)1q%wy95vnR3mL-0voxY{J%{yv^Q*84?fqru zml7+ncQ10u%&|r^tu=}B?v2DBlsQIWPO5NyH-!JOp^-dWLa}KEXH#Q*Wag+fEjx*w z>l?|s!YIs16*>7(-r;2<;T__kqrl8j)2x)`LwS&6s0gGyyjN9aZm~`>^N=x7EUKNO z%p7Zk&SXe}7kn$|+P8Oy`Z_zLri{>RvA?BcU)N#TNfkpD#PM5|{X}cZ1I5w-l~|UBmy*o8IH)x(mc&*P zl}TU}=A?>;-{Sb^ct3IS@hJ-m%p5h%$h{NCV?KN~KGGh{$g8s&Th__U_xMy{lRvJO znPZL6+;9@1A3qyrU11dFq>9grrDw#QIT3duf^49;1wj?kL zb5h0L*YUib;}>H?Lsvy$=BQ~+r}gptI4wL9KzTSHug-3)h?AL*T3m&dSvgo{jx|E} zeMqdzB@FWpJw{i(x+x$Eb5h0n z4vE}%)d*w#_oEgRm^o@qtFk14FSzb$cvBwzTGe1nLPza2+xgt`RoPAd5qr&cjx|EF z8cEzE;X?wWFeg>Gv`geCqrHp>$^(TDugngd8NSzS=cwsgjYPhhUWR#fr$j+5sN&4F zM1Fs;moZ?ylOiy4tPwhPk0$U=M^Ef6KzSs0uECDfycl6-ez0Oyw(#ZI2s3l65lve} zqR)X7d(FDSD9lL}!^hEV#ug{{E~Vdd6ah6VvvxO5N0^zTrnPrSI1fI#*Q_gy!dg&8 z?N^C>$gz`qZ|&M_L19daVk_zn*<&8}x@V}nOizV%`44-(=f&w!~t!b9N3H(;ohI$RkW5Va^ti^^#7BlmDr>n5V z^?$RNnPZL68}dkusL@b2>k6YVCsm}BPviq1H`F63a}>u@qF6Up&thhdn(m~MhY5N2WHF6k2I~qvNW41 zGshaCD=!kCcK)NA=j|AUIjQ2@wgkQ=Xt~~s@<7qEQxpqLnJzO&O(SbaI0rA6b%jw_ z3#thAOXNofF4u<^+G0U5>{=xjK6<3ZJlaufntNnC&$sH9{+52Drd_Yb&buFxnP1*f znbm%jEHlR%p>Y5t=B~V@yHVyCg*mC>(9d}Or2cJvGi8n<`;kg4>!IoM@@4Y8pZKDLGH}FpP0j=8vCd82buZ&XHm>j z`;E*TYlPPD9lL}r?SQK@WoUH<$>bn_ekdSFtWk%ss9|vTr+!$jq@uG|h{I z3kmZm!6?j06``|-@_Z$0uw0Y}iWx5%3&~zsW{#TrT@okhyvn?nfl-)~D!jf7<*x_P zZE%C^=J}%PI)XE%UQdR-DKv|hFMsHh%Pd7tPy$=My22>TNfmAU`thYB7BDZ$1I37Y zVXXehSeZF$TJM#_5)x+S7=<~hVrTDu{O`RB*pu^*EhsQ^)S5PCM{j=o@3qYHmojh* ze|`;N{(Z;FEu{8A;w_2GbY_WB1ChitvB!EwN}|kRh)m-lMk!2hW*am7>bCHN^IkWG4efusOcOoZ%;llcDKv}w-^8J z+vh=ShSRjv%$JhzCDE7a3Zu^N4PiUtrpwG#@hGMT_j|RAnb)-_a7$2Y+HDdR5?&-Q zD&M+r=6rjm%v=>C26v}frn}gOqZt_r%p5h{Np0ATm$n>X<{2{nE!SZ|thn2vbn<9K zBAkSIFC3%J?I_Rc3|b)TN6oxK<1W0)`HTM}qVkkykpouCGEmc~FcR<2U1a8%B8A;*ikF2u^868ZnK@z$h2!)x?Wz6@GC|`1Pl5eC97=-G7CcQ87i9ftt=TNIWHRgak&_ zYhI9b^|~s{P{oTs8t`K|v-0F$#Jyel*~~TfWf`dHiiO@tvVcSh5*T%;Kt9&8^Ichn zD*AZT@H77wioLw>PT%$s)@@P3r-W*g?X4(tuIla=NneIWo&KR55yYS)MdK zjGOn{QA9S#$lCYvl4YQ#-&zv;NSIIJFv{_V6C3T|Da%mB*XRI#d8y7@{34EIbz~E( zWtU~3rddKHzLI!P0;B32)!2vA-m(l;G}~T;dyb9b?|u=TW4`K}zWc~BP-|LG65qx| zar22gMooP2S>G6!Qwq*Wf`bx8~};7B!a07jOusnhJMJJUzVYYrLG>lXU|5w{4b*7 z(93$Qzlz8*P}2$&}<+4FC$xjB{-#o>Q<>2FvWSq5ran~KB(5@z3yQ4^eY>QhIRl4Yo( z)T77jw?Xas+h4`<4SMsGva$@+G;8bOW7dv@`8;X@L=}IwPH*WSD9ccV@2nKIabG9i z<`*%$_CNZh-zvy5P}AEyNUR|dMgpT^)-BZ=k1r?7P{n1R)2!IPU3us)qR81fdd4Ne zvJBLkww^>FiT)%oYHZEf`rC^YWErZs+if2!WOV0)ei1{vE$0*!FRcx6156k$X z4>zAEq6j|MTYq>sT;_qA?rf8ABVnGGU=-%0iu$fI+0=x7{1Vk}!ksqypq7y`k46nz z>h2A6nFr=a&r(T@CShidQMiSwC>uMIrG)gCzqKf~7x+U@=vz_dftqHFkho65%p9XI zCsnN7F_Xp2>dy;!@35eV^y#I~D;mzs`-!M&)XT*&%x&rb{+cpB*sG?#`)MVa`Ck>Q z>&{o{{t}%nVU5r@WD;H^E|b70%t;km#j)&Tt%2OURzq<+s;WNggGFYJn&vb_jAh?Q zR3d>?dV~k+x9c&PIci$zmc(fif04i_%t;k@ zwf?MT-@!b-gpVRHbJR2|r9=}p!FLG%L3w2G$fH*oQ$=RJ`foq|YfL4XIo1eW6_J=k z;sXhc!kko5=0p>g|MC!SKHEl7z|B|BJeHDM^%sMQ`VmQnvPqpHk2)Wu2fJ|IeFjx|EhSW?Az z${eFGCsn*%AI>_|jOA4+4-|)YJL*@*M#{`l(^!L4Vb&E!VNR-;`!<}lUKz_94ZLDO zftjPGRe|65voptHxg%v>H2S8+b!au2`LKi6EGdmE%gnJx=&C4Hn019wn3F1&ch1ea zkByV<97XfF|5`jdSCW~d*0g96y+~B2%rOdcQpJoJxmno@alGuEtct+QQES?A{#{Qz z8^_IYOFO+cS%NCi$QSdOaP)eMPnIe&bF2|syN#|ZN0D$Kfl-)~Dt`a*U4Jq;o?Ges z3Pr1_Yb}ZXQ8IJXbe~%Lq2DB7_K6sUwV;ae9e?O+>6z`yw_7YI`XrvT%)1pSk9O3w z=0L{-`t-%|+#H`6xnsDc>3&=0ZGKC%e3@m-9BYJDRUt8hgjrV@g*mCB@8<*h%r*(! zyoZcp`SCc*&*iqvQES?$PY3ilBm~tJMqy5>m=c++KeQ%r2kSWt3d|fe_0;Xg=-0y& zxH)5FOl(n0qrx@hKL7G>Axo$KY?)(?&>KBdg;`e^g*mBW=g~3xZ(kC)ITH!RoA82` zeicyQIl5;r!H7ot2+ym~Ze&r2Hf zW8Nu3O(V~)xme;!n019wn3F2@dAM4lpCs}O@h2@PFmu#YyYp5hz1f?<&1YT%jXQhy zMB6eyU-IVO;JmiXu|_oQ%Uqi<$9Q2B=A?>+eyfv?$0f>R7lr5Nl)Vp2+A>E?S6;q0 zQJ6BvD9lL}jq9yWN;#FtpJ^_Nz|2w8x#;Se1|O2Z&G`m*9@a@(_S4qGE%>KqQmsq2 zc8)bdBb`>%G$Kiub%jxwlPX$9)-oQ1Cvx)+J&L-^Y9wvDYwO`q(_2ZRY{Gn^h*4Mz zs;E7!mN8{fA|JMWvjs(`)jmm~jci9dYMPJJWw9}j#+aCMOsch=k<|PzTjm*^rX^i( zYs(yKgw{#zy4aXa!mKNd!kkpm`QBpVHubx?DGwBjCjXrj)7zFgYP$Pz*CslXz$nZ~ z6}j^-F&Y*~xCi8Cbb zlfWpR{MmxOsHgHc!us(7|Jv)DC0o|itp z*@D93pDRhO8*OJYsA)}(#>Iszol~24KW5+dGFtA(2P|qcA5`T+UHK#CMJ3&D$qi zP+;b$=^U0 zMWS0Z5wvwEH|GzcxHq7nvCGMJt%h3DdXNYq(VPTEVNR;JSi732k|~xqE%3vF0y9TV zV?ScriHF?=%ir@MJ#=GcQj|Q0`_Lo8n7oq9Ga0NATDhLYGZN*gonsW{q>42;+KaEn zhH&$_Gm70a!i<~;boqOZTGQ^6_(Y-(35>#=R1wv?y~sCy2*28Niv>ldt7VNQgKbx- zsA)uenM6@`-9T=RR{!z2q0zm%?Ve2jh4qa(VYYiRSR-^KrV8`-9HTHNRor=%C|-0L z#QiA`6q_d2H3l`Y-IGC0Z)79!fy4k37=<~hqF0Gw!tcl+KIJc~1qEh~n%+ixW1?U? z`}3xh$Brg3#)ws1?(>Kxos9R3EOMV?jnFe;66Hvkb%jxwlPW4kPZIrm58&tM`U8c_ z?;VU12O{J?M@?hANW_sa`*w`NoK$gb$Rx4--~b+b|APeuW{#T9+nwi&1{3>obH@7P z$YDnL+q%sB&%SZSjhhiNbF2}1mnn&MBz`A>QJ9k|#>UPUTGf8s9OH!|%ex`Q2xr@! zRMa%miNt?Z`pLS&D9lL}cXrPg^OpDH)!S^fp!l;_f8)%KFnQjNnp#xmH6nXpZ*I;F z-ybpFxbd>0%zR14aYpA4VKQ^95lwqeA{z;FT?355oK&%5!W!}Les7*YnWGrDc8qa9 zzwKT)YAS<73JJ5WFiOb@_6@yL@5~zEQMnHiC7XCg*mArWcMyn|DT?GdV!Y~6qq?`dIyi?u&6Yy+y87;)oKe3ueCukbNox1 z=A<7MWl2n;t-`40+vgkI?v$6URuwHTUl6+|b@?ChX6q^=cdhcW4Ah$DM&c9+cPay; z=DVyk;>MJfWvF6Or8^>DyN>c1J&H2lw;0P02Ffx}(-UZbeKdw^*KJ7tG>*7QnXNRwMSBqu7vW(sa)wKD z*sr%d634S7J17G04x!dGzuaS}?ZtDKZZCA)D!i+Ln&w(gS)+e;i|6@Qt7SN(xLBHX zs3mhkP1go%4~kFEWBA-GvUUyoKF5BA>dmm%o2EUbS}li{?@JCPDUyM-?V_5 zM(<1w;L&e&Yr&l36@hP(KuxRZ*3ZXBc~`aSC9}#k^!qIJ7iR0kwI9vQJMPLUPOrAm zyS4^JmgcMe3b%&Tb5aDZXNa0cn4T)n+1em$wa9mJEk=78xN;zBnw?p(G=I`K+0N)#MM><+2{X;-m;%=L|KSQ+KY%`#tuy&dl;b$1-qzFw~kB>{W{g z#c>66iV)z?`O zxaJjV%A>;{d_hgkdjG`-9m~MgrBKs3+}fr*aH+GkMZAkrM$L8Q*}}3%Wge($C4^q| zUZ+eS#n+IXmR4a!S(l2(<&1t@n+Vshq31a7+VfkbAB$pD^Xe#YO()c}qTJ**Tdwul!2>Rp{Dr;FI(_Uho2waZ}HO+$9 z(UDj0a#d_O`BBF*a2+Sqnl@o>J3hI}ebJG-C}sS9Jc50Fzf$gV)FhgA;Zd_sh|L+? z7)IfWNvassq#JLMPl%nfofUyA4WXv@VAbr&ugusa99DhOl`>#WAJlXfKD`@1(J)Co zeB+{&kvg(p=Ao|dbNhT>Ui80d;@{~`EPthHY-s;FG749OK}|E<{^`$OmLDz7tZ`KY zuB3um)3U@5cIfnPCU2HWV2{)vdynJ5X!dnsS4Az~e@u$puwh zxf9LUaaWlWYFZnY?)g*+3K3tZ_rWM!BSRIQM~Ctsg?)u*6II~a5~yj_p|7!gg7;@* z_<#&b8Mr0`YHH`lV|n%8HL*Ikvm*9nt<5Ia_$$fmMNw6J)bw65Ydnu?>1kA6<){dpZI7D9M$L-nEye~Info{^;?&97 ztaOIZKr;{2^gFnc%D8iU@4M1&bl(2|Q8=$%71#cW=ks&!wrpDMq6nN1j+)M?X{+W; zX`p{QW1hGFe;GKB8nvdmPLJpM=l~j_U|xUxzeufViJ>98 zBK64E%{)-kTYIt(<=?lKV7F?!*^fjSg>z9=(c!{iZtSbZ@}JG52%N)-n$|WPJ&4aa z-JT8n@28Gif^#2H(=TVi!Ti5#jo9@~8I>|p`!2bKsOe0f?hM}X9L9>&an8L=aJFEzt?S@*@cHEBP1yT;P>3cRR0%yCSrWv_@U3k&?7uoE2 zvlW3e(NJqz-bNky&MtSE*M(q3C^OMuew?Pgc-)Ck+H;lNxUH69-b*s?DVeo^n$}Nj z+?L0Ef63NO-ze`m*`sh?nJSKdX~~;}ePfYfvlM~z%23lABo{X41%(sOF|n*7aF!Tq z>V4L<;Quw&_@e4_6>)BJQMPo+C7B0m$|HLdzImk^Z_#0+j!`&EOck#J8t{!Dytx1I z8H&I;U#RK6539>pRP*5(O9vFM)tWRKUPEM z&u4DXF$!lssiNV`B7AB4D1N2#--^IlNvJjLQ}O(~$CO*}>8DF2WUdJe$ zF{FymZ5_B4*n+=ypQH$!&4ZeHpSmB}^vE`RNl{Nl;A|e$^xnRj8h*p)Zjnu&dTzfxY|nP*{m#~kmZ)BO^EE4!Vy8*k>DQ4x4o9<`?Zc3QBu zWxH{o`_76OojhI-{xeeEV@IuNj^0~Y$>d&~`|q~o>or@S;8;OE6U12wIC7odE`Q`7 zHm^)yK5b)e9R<$jKuyopE^lFv5BB1&zui~LzH1^mKGwjm2k+Z>mm+Z14r*HQ zr0Z$6Cn$!$AGuu-IF|^urd=I-gSFb!iT59OTM?hL@6rc$4Un~fTGKXE+sxe7_23&l z-5Ay=&W}-Rw`I&S#>@2Pi!@h7;7kP!+Tar(z3$R@?l8}p;ja|9q|~0!L$_rZM!jS0#B@ zN#GB|p6XZzj$%YDU!0}&qPLAZk9JhbAf04?x`bNOiY+f_WPK6GV;{)pYDxCzXE=h2 zY9Yz~yp5hTY$+zjHyz4H(VbND8@s@fN2p1J6c*8ahw?tPGAe?O7{h+Vpr&`^POBnz zTpi56R&+D>M_Lq)@lnN>fo;W#HiLNm?kKG;qz#k)fo6h)X3VN zH%^?d2#ms~a@1=7auY54#qupdwta3t8gM_WqYW>OUSpJ@66X?HC~}+0jt}x>lVCkjL!tscfJgm8^ag=eNrqv zX;^TjY`n*=u9W`Y^}c*WpCzKplVl67HjG+bZ91B+&v*2lE>d1NF~UH!XM-k6K-6>c-k`{BoxxR`#{+?zwr!WS%YIRXpB1(X@lz zVtDrX$?V_!KXv>Dg?dFlGqEFoGVLyV)N;E8@1)>85_KJx2?v{Vamk6FGqze3w2d}7|r{6(`%N?l=%qNe-p-6Hw91I2mGhnp>3 zR(i8e+kVPCaCH!M6_0tfYH*i2`S|>&Cl!IUfSSe{1XSfyGZ*4*Ju~YVg{z#XqVVl# z>f!S6A1BTzb%iyGTGJl?EX!-%4C9F#H(UN0n~@!ykVXE=;L0893L8uEhV!#q%W{un z=M;gpfSP{Q^blTYb_MQ6?>NLLT!BOtMY~tzMXHqH)3zU1>I!QVHI16It7@pLUwHQ}&KsL99^ zI6i>yf2Q*RzK4~%!WuYO{QH4MJZ04uOGL%XdSJJLG7ntwLS30+Q@fnJj%PhS z$nTmWuoh6$K5v?xpNOx|Z{_)_WR5F$sA5k`Kki$wHoyFCzap?kQPV8CP9NEc#%=h> zl&u!LuEEtP)Kw!qa%bS@5B|Y>OuC^6tOe9`4|$mb4_?@Uw{v@^WR9z9sA63P7yk4_ zGrqg3Pz2T}YMN1XKZSXDcjf_opD9~~t5K-eY9*tdu#som^MT%b6@l5Jru)>*PP3f_ zVtD(yuFC2cctx*{xoa~hg*975Z&GSIL0OXn1+Jr^X?LmYf(6eO??^5W5*q`;M_;tLUrzIu@am00v{8&k@?{=O+@(7AqKzZN;(4jQ&WgY*I@ENH)1{&~G9#9sHU72W2zAU!ouTk( z?O)=0?rUr(H$1cM3IM{sMWEYQMFc!A9;K6kG^h-z#2tOGbjJPBff9#$QNFG zsAP_#mGSzM&HzeW6yZ<1aF;5(6@fL1n#P`AzAegr=)j|AZBRx>zV-)R@t<54VYmiqbne+g`)dtbw2ji>x~O+$g-q$f;G<9%jt5LZ_AmSv!@ ze>S5M*M%6fv*buE0|kDQp0Jf+$uLx`i5x7;Kw6Q9uGBJ6;5X?BTN#_G zWEXAf#LF^J*gu<5t{b~0y(;UUS_TUICOu&*BiJ#>*tjoImVv_l*^D}#GAd&BU3(cQ z@SF66t&GtRV)UZZWf{Xz*gu<58RAD(4?6x1BLyw85MkftA2a)58Z74v;rmw{3bnND`TH~UjCzPv@8RK{j(X> zZp}%(aQSDcWuU-s(i65ajw~q0-CKmoGEmq*n^DiZ+|#GlxRhE33j8KLVJoBJAC>v3 zK1F01DD0ojsO;xI>ATAqsb!$RZ_*RCGU9w1^3NB&WEm*zpUtSe|2na!g_ha(2MGKo zJz*<@t!~3>4*Ed*QX7WC{@IL*h{?hxbRUyi1`7NpJz*>3*7I(BqxG;X1BLyw88u|Q zH@mg8QEC||@SF66t&Ft?`}2lBX2>#7*gu<52LpUqHkK>33>5fHdcs!57~fdluVZyt z1`7LUGwLn#V_Tq76e~|7=FRO7drODyCGlm4O1k zNl&Ea@gtGvIi0eX%Fs~QKbukKmiV)MuAWJ$d4Rxg(i65a&JL$p_bJy6vkVmW&t}xk z7ryLp?n9|%pulg^6RCN08OoPkYb4AvP}o14QInVFWPO_EH&XKef#0MjY-RK_`tk4y zG^dmPgTnsVj2d|^E2|mXBDD+@_)U7kRz}XLF*LgElq>^<{j(X>Js~suQhI!987T0Z z^n|U9u|Hbz8-u^fGEmq*n^E_ZGO(?iR-~4J0>4R5*vcqV;5YuyifmT1u29%Nn^Ci( zKIr4)_obGB0>4R5*vg2@TZ#XdrMN5uh5fS`Rbb3*eNX*=Q_Dbs-=rsOWyIzWS78#UInxKYNi{1`7NpJz*=OV-tUFiK`{cKw3j1d>iq6P&I-gH10|kDQp0JfcXZnn;4P+T8?4QjjIwRNV+90(I z6!=Yg!d3>I=`*@EkY%8-e>S7&j9jN{gVZum;5X?BTN!kw&*<7fmVv_l*^HtyatmD> zq?UmKze!Kn%AhlSM%M5ayW)z)~Tj<&#wG0&aO?tvs2A%2abZsEZKwh5l!b6iG0xwuET^k6HyM5{-zro zhl!r^ibTHX2G?Q2n~5j~Nk8ZY$6=!9ydse=xoDQXM3jT1A9RD`Fwt{fk;pgQ z;5tlrGZEz==?C55I85}MS0wUHH@FTH-b_R}NcurHI1Up%=M{;3(+xUPi|}S5%0bc( zy1~iRCVI{*68WYZ{CnNt5#CJ1eU9%xK{xo38O}t{c|{`Mbc60VBD|T1a**_cZjc=( zyTSXcp7V-CzUcAOHc|{`Mbc5?K;mt&p zgQOpHgP-|6O!S;rB=SW!xDFHEOhh?I`aw514ii1+6^VS&4X(q4Hxp3~l77$)j>AOH zc|{^$bc5?K;mt&pgQOpHgX1vKb6%0i7v13Vy1^s7nTT?b^n-429430sD-!wpt)G9_ Ki1212%JCmY0+HkZ literal 0 HcmV?d00001 diff --git a/khi_rs_description/meshes/RS030N_J1.stl b/khi_rs_description/meshes/RS030N_J1.stl new file mode 100644 index 0000000000000000000000000000000000000000..43a2c7a96efbb1c7dcc06b20a5ef83ce199db5c1 GIT binary patch literal 394984 zcmb511$Y$4`^N`&cX#(-$=&TPuEm`Mf)fG+cS+C!h2T!1xVt8~o53koC|W2Kr$8y% zmKN*(oxPjmySXI&{du0|ncn;T?00o$-kI6ER;|A(c6`;|wz2=|-_87{EQ0>he-Yxsv-yrsuS@8uw%y{F2dB}J zwkl?p|H&HaY}%@%SvCpJp9q1fy(9j1?$260Zi2S&_CR9DlE&JgyoF2xX{!gS${u#O z);S8tO?W+!$oO!wwxxX@lR(<)fvTcI#<-SU$s0G}^+2NTzBSsTY*|eLX{!gSa@=0- zdh#?|+=SNyiS}=~ma9hg>UWrHh;JdLXej@P;<7b0U*K+UkL-LqV5a zt*<1BoA7!dkzw0wja7WE$$JcGs|Tt`?UMf=C*k!#Lhcc5+a!>-dZ3Dqn#;YE9zKNE z0||L%=^UAag$9!dfhxLsT%K*|;X`;mkdSu>U2Bs-8Z79kMHStJT;4U(!-w#CAR+H` zx@S!SX{!gS=xO5e?w1}ugx3QJ`NYz*XA($TJy1op0+&y*^zb3P9!SWVhw2cAB#^dx zpo(fYvzCjK@OmI2>p-dtO%J549;l+)l*?LGdiW4t4+d+4U>4CJ>166d#aM=n-4w$!9JE*QVJ&?9~ph~J`oi06m2(Jecvh9#cNg!?YK$SddS*OQIcs-Di zZHGK!Ng!?YK$X0DvQCea@OmI2+YWi=b~P!dR6Jy0c| zCRwM)Nq9YwkZp&2k|cq&)dN+sR*MgVH>q}q+iH7Oh>zyaW#IaXM zpo;1(v+wKcfe|FyW(d{?mtP!*2NI~Fdduwl`g&jliRLqU=nXe?kHZ5AR8hTU_I-Ul zFoMK)!$R~$U30|Yfds0k-ZJ~Xz8)AsLiIR(35*~?&z~-zwuA{(sUD{f*|Ob?78kuO^heayYkI6RO*mFjU?Jj}hq2okFQXd%qK!Uz(rhIZDc?q3$i zULk=h)qnK$zz7nPo3_)B{>J0*Kmt{&|LE(15hVO}HPs7Vxfh2A5*C%GU+U|jdX_SR zME^~7^fOBmaSLHy4wyHS=pN&A z?`jsp^uP!bGCPv}iG&GM(NkcKmstq&$k78;^mK80YUA+02om%(n>{pN4ec0Bjb*JPwQ?A#)v> z!6ZzeN@fz&ld<*yOb?78p~kO#J&-^Z^_)2M;at81Mv#!Xr>svBCQwCvMoxXvI6N?d z1l5P;=$Eet5~z}yy{usqCQwDaWlp{DI0%d&Ax9{v-v18*Rn+U}lug7zU<3&{(jseB z-{U|6Rg}GO%A?{SFoJ{{Tk`cl0#%f^amq!xFM$yx)M!+~1gg~7Qo;nPD0}6U3CFQl z7(qgfE%|yNfhsjplrVuRnaxvHAIDx{1PL`#ttcI#v@4pCv zqeD2(By%X)8u@x4fhw61$yPOC0#!0wk!^j#1gd22A$uSR6R47zgzOh3OrT2U1+ssa zFo7!BXP3Rsgb7s19=Pny`VusfW{wWZ2=;NY?`vMZ2=_&d5J;d(KC$$)=?QzFO4dB| zbo~c`Dp`Zd5wL_kP$lbidItZ4K$UE5=o$PE0#&jNlp{w8?-iWWPs_xFk%VO7_O&h)co*s$_3Wj_~*r7(qhzD&_b|!UU>h@0ee&F~)ts$>>SPqCGt zXFWp5XIZv|@=D34RJMh(>@%|Mtr?I&mCRP;NR{t3M*>wcTan{u2@|N2xrZFpOPD|v z-l6WgP1SI?SE!2fToDu@u+M;V6KY1tcdw8@m71qYm_U`hda{1^C9u|~WAgT?;_v$) zfhskFm9Ph@)O=LJ1ghvvduN)g*F)C$vR@^)g|jC(L*pePGE^NvhBLB z&zjNGm^`tDKSmTS_XO(|#(sPdqi-t`W{fCd96|zBgXb>O7LV@i@wmdA`rCYA#*x>D z{V{?B)^?1&x;9@QopYE`bD}te1ga(t4%LjjJv<%@Q!dayW*lZ@T%0igBS>H!%vjf1 zZS*9;qm3$!Ge#kSs`ibLb8h%2e41t5W{ zn+MAAU8xFqh~uZi#oa}vv;rF#qYk(fZmhdFD+(h>V1JIWf9mCPZM_g~_}5+^fCQ@AXp5XhPpIRlSnp3)lak|& z)IsZ`FoFd3GU+ba_0IJo|9B(q24?^gs46%+r>kin_0-NS)0DqFGTJCQ${B?bB(U$x zSf44)c%EIOjbZt(1R#N`lW%*t#tu`p&!=K@c*^y|jJ~ZeM_~jB?2$88?7iJN$23ykH;X}fD8Luz1XpA6%*$ZP6@898VZA6SsYeNE6wc6fsRp`{rb6*`UlUTGE z5M-1ql{Ok9NMKIISjh6k!ci{B*!?Vr4GC1)2QmIXz`s&2Q*$SdTvc|0a=FDlNkI!5)+g`+Wo1m>TNttwbd{IsgJ zQFL5+8xp80pcUZzzb@zT$lauhNaw6-%&%EK8Y4(xR?Jv=QAI3iRMnVpIlzVls&1q$ z$Cn)~;PL1|we-Y*;>O9r0nr#i!rIH|U$C~wcd(dYWUXsM0##?W1@Lr_GI~5JQESt9 zK{g{~d7WsCAc3<^jO8iQTpVNBj1-RMHY8AWHhEoMEL9?p$2Mv;zj>O(XmX}mG)9oX zIV8rqe;+7*sFTEq8XIUs0#&~!Z^nl#ysNqE#HllSiVW0a%73b3G)9oXIV8reJm@K& z)VZfWp47{R1gh39Z^t`Fx;!4w^M#2E)MJ|dxMws*kia=4#-jR$iPJ-)bun#_4GC1; z-rt!|vn};_{F!l>m`gn-=bM4i7(oK(kQmF?VwlL^X`Wv5o3S<|P*td558h{QZ;wZ4 zyV0T=^_c#8JSG|=NZ^bRV;8?3Ely2usc+mc$%X`~Ha8C8DFgF(JhD9*Cw`?qR=}i5 z(HKDjXM`9#mVCUpeEySms@QZJ5~#x70At)4E`q7O{rT~9GfZvo(zMOgmnj>haMv$u-D^1gfsJ4&i6U=XSa8#HU9_i*Kl9^V>H#8Y4*H z+zVqp7LOJ)y0qZE_66CHK-JbxJ$O`DFONr(^~1z_YS|9=>J*I;ByjG9`qTr4iS={m z@Jni4WAWZOPIg8Y4*HObTP|z6}$#hDY(i`zzUyK-I>} z?YJ}2>G2p8)=O-rmMvzRUo=LLz?l@r(wFNc^5weAQ`_^}kU-Vkw$1pJusa?PYSDyj z+0vZN8;ubpaPEaMqg;^aK`mR6KFMuJpla@*x_o+1#@*MPS~MYBwmDCeM`HvDoEKrN z#?IzqZ2hdF=h(XeNTBL!RU1E9C8NjVEUP0XQOg#b?S2$SkihJou{S4ci+XR0ir;(e z3qS%@)?Ro9XH}7xTDBcw`=c;|1or36yp~g5E3={q%xhFxW~r2mx+t&p90%pKobp=X z$!on4Bq;xc@pj5Sd9Co| zwO#^Ml#9A3ul0CPUdt)36`s7-8$p8dPnesayp~g5D?E9vmp~QeqAtp7Jsy{Fk zC$IHJkf4keW=trr<&@V7PhRUKP(`_jcU`ZU*BX@9%8?0q1-)aFsx0qt99uN=T7&Xh z!;{x~$0m`W{8OjAR(C%il-C-R*BYL@)=QuYM|QT zYfxTmc=B2=fhxLpVU&~dT7&Xh!;{x~BS=ujs#9L;@u0lcpuE=b-4ZTH(oSy%8kjQOnla?Lm31MtQC9 zXg?CPhRVdAVK*j%n4Iot5aSp zJbA5`Ko#Yp8s)XhBjAuud9Co|wcZF4lz+lZHRZKB<+Z|-*Ln$5Q7)=cUhDCoyjG{Y zR(SGSZv+X-KVkly@>-qpTH(oSy#%T#7u6`Q^>|S0Z^&MNC$IHJkdWibvbA>KSCrQp zl-CMRUh5@LMY*U>d9BBTT7N_K0z7%GH-dzmIgzck+k^62gYsJ8$!om?swfxLDX;Z- zP+n_LUMoC#tv7-M&L^08twDLM@Z_~#0#%fY>Xg@dJSeX(x}D#}H5%4m^V{xu{Ngt;d7%T7&Xh?#XMt5hUacvg`}FJt(g=D6i$7 zyw*#gigHn%@>-7v<+TRowcL}}dLu~4d2QJ)x;-ebH7KujdGcB>fhz0`n0c*1d9BNn z*LwR2NMLWk%xewGYc)?^>uu?=2Ow7s$QH=GSCrQpl-FvWyw*#gigHn%@>*BX@98lJq?OQ6cy3#Yu+puE=bZu-OSG!d;E4izg}*z zsP*Bk4I@Zcv($%_bB0jPxhV1JXe3Z&%{hOdY~m4R6JG~sDoS%+-k!cJFL*Rzo!l#H zUGm~wxbgL>LN0$EF2~5cbqNxkPlxJd7A$Z|nz0;J#~VprzIJ8iy=_RKs_xiYz3=oNzms;vF1 z-!2w0YDU!&9oafLZ{Y1MArW>hlRn_3KfhRW2YHm$av6VSY9f~Z5Gv;lyacNLeUw5U z99VL}LUAYaVrY_yoPdjuE2xiHHCsP?flTgw|qZH=bzxDDs#>`QRhU2M;w^ z5{=u{*Co{^m+ixwq?yF6IcM3ePqh@S$BR_Mf0A>l-V73n3OCm}_I(%1KOUVz9+^X? zXcvcui>FB<ZTQ=*?KQGvQ*`vtq8S6($#v+pl~5Xi-@M$g-NRuPs9P-pNZm zbxD7kalcG6?p-@=jlu{LII7OrfV|_ynAU&0w)NQ*fCQ>OgoW^VNppH?pYoZj8O8pp zY_7}jOIcPg_H#l0=DT37%1sls9mQ25trxyP-R-UU8J5w4V zL)wd%w@=%VKvlZjueD~a8}ai)h7$3^;53Hcj<(`L-BU3bL1J;%KeZ8s8uGW_^d_Qv zZf5wc>m(9wYHLRVRfR77s{NX*39mYB1QFRcf6|+G?krA4p0HyCiJG&1(JIi&{)mpD zL@c}XR_~Ojs~9+{dJGb%T2=kJc0arYFSuFOSM&e6qd%$KOI+Q1&5jWy4&*qkZGPXH z=eae3h+FTT>Pz=^7q;+`F&IJOR_P0xnB0m#Zq$#6g+;IEJwAnq{ORi1kwDe{g+e=4 zvK=3+O(vqriJ$b*&wGogZD9v7f<&)XLR(h69X~lSjEH4P4Wq|^(xPV9xBkI1{Pbl@ zb8%TSV0(@|1IEr2sBJ7bP)syWy&(n(R9Q3n5)loI)1?cD9*gGNkwDeOoVxxfbsE!~ z=A$;;=R;|3;_9qHF)|02bHTD-i}Mj#)17kF9@fS~G<*My7a!bRtiRXMjs&W<{_(^$ zaqm|i;wY{0nnr89at{c$c%TZ`Vlnnj(Yvl@!^ex3)eG6u_L%9May!)QK@NYA!nGuQ zAG2&7dmT(8sV!+Fb>y?!(MX^QYi-7AeU;O-lSWbt)eH_m0#(>b&@)IQcTH&IF6W-r zat(`jmi1TAHDA8wxPCvVpZM+G;TR-P_4oOG+RD)#czR%sn zZEJ@R@mJsVdX>6^MfAXl0qB9Mk~QaOWvX=HNyiN*qCxEidhV3N#HOl_4 zZ)mR;{_N8CiT+~w^4^D#K-H>?yR=eYb>ykCPA6jT&qwtDXFuWUe!?FKROP&~U;CqW z2X0i9eV@oQXY?ikeMO0y4=sCzDy+vC3qN~GZ@jOsxD+s=I(neWTEh*cImoIs2f3?f zL=0whSeIbl##sAqC;0BF{X}IRYDWU=5~La1LnB2;XryS;_FpZz8fIJ8(WpBq#u({O zHsF(v{w&u_c*mBIX!E9rUM*QCPj6`*jd-o45wBjSi^d>nB752~g2bc6E%anJuX#M$&`4^38cAKr zr^g_HD(h&io-){I-}(cea4^D-5hTitY@jF7-g!KJJQZjRrxD>v6&A%Hfhy~$^MwAb zjXt;1ix(Tev10@YYdbiubaSH>%O)nRSQUc=s<0KM5tiVrMlG6~c$_;T2J>3XWifkY zEK$Go#?q+PBC_^$8>%o%wGuu1-OyW}=qUHFOv~+P%iFJ7NzeK8 z%op|YPx^>|I?nXR2(~!5C0e&Mtc)(YjTQSk6|!LliJ2GXaEx`JnbD*)GrGRP)@W>B zv30i2(U&h-o#(qVM&ukb)rJuy_B?IiN}aoxXQZe(tpj-3d9*0B?tC;7sIrdx^lUed zuSh*o{M&k=4OKX5WF?MIN+Cikb`U8VHnn44q~DgL{NmDDX79z?FS$D=o9IF-$x9D! z8G|dkQH3;Pn>XYXCnq!!hhNsPV`TYhbV3!Aw2ZOB_0Qi>He`Zo`N+q&@GlJ<9aJwO@=iq?Kp>wDRnAlJ6~R z)lh{rV{=On5GR%#;BC`?XTwO%n!$W-@-euRxZgQJ=>!&5t3|^4f}1_>&umAvv%;uK;B~7 zEUKwXHQKLN3mqV?4xU6L?lhcj_s)jY{!}B&vq`8Tmr^Af~(Z#i| ze@nlPw(A{Zmu0n*r==@YpIm#X$Ad<^j4QMjr}S@wqA-GlbuG@$9OI3vGyc&AoeT>= z0#%OQA^Nx@IX!#Tm*(!y(%fD3J1?Rzf`oPMZoz@kMwXP#^hI@_2Oxo}Yg2pZX@BYN z@tF25$aq>ik@5A_O}10@>*NkH|7xbc$aUK+Tj!%H(0c%Kbi2dL2+qAdV{c@dR+5iLIlmzQxsnqg9NImj|!`!OD`KKoSla1Ph)~D9;n(nsTZH@SJU*P zOqky7i=ub?+Fwj9#{kR~be?er@B4hE|2(Qq?$y?F9K)|Y*7Hs1Vboat$%X`~Li<0` ze&5~1Lp;2j#5h80?j~IQ9E}93aBUo8IcYt0Nm@^Rz2Fkd^MQ9bWdQukn(fBb$BMyS zD(HufbhBdw3G0!6m^xZyqjlkD({7R3gm+u0!t+Kg4y}l9MJwVyiFV=>??ee{O4RA};8qmuAuC%hhQQ*HiTV#*UG|fUo$+RnJTh+!AB=PX&qz^oByqzO!VXnya@RP=z#OeskN4N)u8V znZKK6$H=`lCKli@1fhwdK>$~YIQR;LqL+qVm z$4G_N)p$_0Y^DcpiLu1=#>mkF#f%aQzK)@>H}Bggs6v{tVZjEyp-|e`v|*whBdI2o z;xi`~F+Ffg)C=cTL;$_{(qiajITPo7iw0FlGgkF{MbW27fbqxg zvx<7(HaD`Z7!yOe3|DV8p$cinY?U*LIa690^V$xwW28`te_Z( z$56iHQg4}|3Teg;553O2+d_<`2fEoYa%cKJ*U@PmOb^@=&1NKx;=k_+Gq$ekDM#*H zw5rgY??)BVj9u8di*Ktt(1?21(TXdBjTGp|r>496K`ikB-Jh5}M(fqqMF_bB~)Z2@w zLYlF6`wafa$T3Fqy^ZV`Io>d}EAihUrU!0`F`eF=TuEBqY7!7X(-cGKOQs6$X_R)9V5<-L$xsj zyPF=kC3^de-lPAD-lM-+vOo-t8*1vEd{iOL*p2*4^`Q-h8ejFuV#mm^a;vn;TRNE@ zxFs4-r0)ZmNZ$w0IZw728fo_5urD&SToS#{^4jKJS^Fi4#%41jX=VTQ0e?p0N_$ixP3sxTs6;moBb=? z5@RiC&7DDO?&f8lBQtvMnmbe>O>ZKx0mg(O2lXGe_p)JRPvKzwQ_LdM1GmIj7g{^G zj@AxpL49OK?_E2HDx_&$#`Zbv?h<5^KYifx$PW>lEkzw z@fZJnWETS?NXYW($ku$Js}B)*D%?EOXlD|!V_KjOp;SwI3C-4{HJ`m&66xC=_D{1s zt2jHPxq%VfZi&o$w0Eo9@dvN^5^-&Ru9$Rf^NUv{8yXlvLYBK%4&){Nmb1vSH)Mzo zd{;!&TUy75P^#|h*J*E8cH{*HN}^1Ylrb~wYvOrOSwn7X#=|bWh5s;KFmk$<@TsLzn28zMiQBhRo5YmSJ^7%PWBII*Agx)B9=z6rQRZH$y=5%Rr;IUSz1xU$z0z5Z z1Bv|?M`*!0y76zX%h|sB`O4Zt=QbA0ZFwvNs_>W?d$H;}Tayo=VrH4Mx;$4cu7>cj zsVDN@6_aSrry=}v$%*D(sl8<^9s40>&**-lLgwQpp(04k?NM2qwW=2nS~{NgYWLqs z?F;_uDz>kAWg$?7$K<}-OP3E9(~qpxaHbk(r_U$7vqsI5Gq%0bU}uUF;o?u{S`8ye z^oT0vxLvC+58Ei`2j#y!SH_9zIg+{e$}{7Rw3YZHT_5e=KH*~OmTa0lSIQk#M>nr` z+#eIlFXWOdw#Hw~z#B|&FM7F>xUad#166q5Xr*lP#nDU0j}+Ys54Y?Us_;6wkHh^p zLNvHH+B+tLD>HGFDt-c0IOY^Tfhrt9il0E0Zw(jMai9uo*Z4h9g>`=X1gfwlGKmN` zXFa>9!f`EM54GwASEt|{Tl@s7a2_vy0#!J>7(an3ob!yIKo!o!#!sLM=ZE7bP=&MB z@e`=RJ3oE`RruUUBEpb=WJ#|6D_y3t>*MB1=Gws>2S>PWcl9&NKMx9X$j_zDBxJ!P zQ1#QTXO4*W@emPl5s?qSbyc2L#q?0L)LA`H#a!jJ(cR)9ydFp_A1qvjbNQPdiuUzD z)j!F4YfX+-kDKs%AaS_iU00p-nn@_y*8^424FB0{p# z1Bo0R^63`~eP?6MnOH3>yaoz(+XPg6Pc z$QGGzmo~OjN$ON6VUNkVz;yVFK%5Mf(z;mY36So!Mb-_qWmo z^hH1JG|TCyl+ahqmhVT!em;;0`Z2H0cUkF#iBmcA>h%Y^2}LJNv>%&OZ?(+*)G9h* z;@eHx^xV3eP;|lsKJ$vU5E1ez!Xw9;LD9Yh-Qjwby}K=ERBkCp=Yo2>dvTpzB$P@L zsm>PEbL`(8$MsN8j#S|jCCl>t7Vlm~P{}+FY%Nu7AnEv@bG(;S8!n0X?<>5Q@HoEQ zSKoHdUhSlDk>~%Vk0H0E`d6zS7uKsKEykN(aQA(_)NqBf6*;hph@!EGTV-?U$t#uT znI5&{NYe;ps*(pb6HzP{@%e6gea@9?{D3QvBQ4JrW0#1?8;eMuI;sBfq0TR~4(3QR z_ESjvsy`8tCl;|k__bzhUymo=(2XNaZ;TB4yUGnBa>XWK6c1_lUY#JKKrBM${c5Za z#{k{LaUx=$T}h}jjkF{pg#05*GW#ig^eZh>qF^q|sy>(HtDCcFCm#j5?<+}||6;4= zypM4t)q_m>eeb%SfP{Y@xKwXDiq~mi8`BvqP-pwvLxNn zqvDhz{J=l%v!G~S0##eel;_3Ubum4B2#J~=NTl&E$3rT1GYLiedZ4Pvp6a|*ksfgq zUJoSpjjqNoU+QTRiuUzDRrQ<(FLy39Zo=zZ~59>N%nr&)sB1+(d+Ar3VrP z^j3UE%?OiFwA5KWP_^8z4Zn3hJZ>UFveE;IoU_~UGtS8-p=hbIdZ3Ce?ZC%Pi-(Ai ztn@(Q@VJhA-ni+ehoYs<>Vc}zxj|eEjE9Jjtn@&lS6C7 z{`bCk2(Jec^4h#h_pRxnXkQOhU2ffh=U*BR;q^d5-edmLSDPM+_VqwjldJUBca=49 z6J8G_7&qd}nk#L<9k*2NJT~mFqX<)2wK@WoylV zs+1#&@Hf}vAxuyfdrc2Tdp*1a_I>WQnV@}`?rxneJ!DJY2UV(nExmn+ z2r@B`9EqL1mupLh_cr%R(U!e3&n~LeD3|o`A-o<)^k}kA%NNz(^iZ^~2dY$0UwZfu zUJoS79677~Z45I#6z%JQDwRP<4wTkxj zK$RN5kRCpS*8_=mY4hr}J}otmL(yIjSuoEPs??Z_^zb1f2r#b)5(E1d&=)^hVR|T9 zZrR$)KvliQdGs0w;~~5rNbDU@NY7O8JJUnaz8DC%)laX9hwyqJvCf%afA+!M zaw^)_1699`%&liU6A$6_Kq4w*9{u12cgv}0Uk_BZIFViNxI7-h>w&~ZBfCDkjJq9F zw66!Me*Qg^{_L&0t@R?dyT6fbwbeO9$d1ydFqAEuLD}(z{zV zMf-Z7s_FS;de9H3ZGn#@@f*Xg^Y9wsxm;xJjr85-*q5 z))SXcqHC$;_g_`qQzfR1t-pRF}ast4?+{PU|0aIS!|4WVu~cmY=JcE&5)ZG7F+sckXPQ*!IaJ zR0IiG{!;J$mV9Qw?Hxmnjx!he5K1M9FSY2AnoDfmOZXYdu2(nDu6jD9N*#H!OI7p{ zi!qN*DY>iSs-RLLX% zG9uh(!%qRbdTYjofU*_>RkHkLMA)|RP;~Cw^o^m(v-%K9B?&c8Mc<2aXQ{2jyEewH znQ46prIKgiOD(!>WF!05pVsS*{RW$ax_9w9OF~_L#tzLFQGMs+GIn16%5o>-xxzC| z-?vn9Rdn!?en$VJN6q$5x#PaevYOMQH@(-5w*`zEU~GQB&xcSd>G7q-89rrF^gnaQ z8m-fpFbNgG?aH#6nMwooNM$38W^yA6bjAR)`@bGOH+{%MTdd)t~GDuOEMfw=)=NT>)BvaCLLd-NXk zL{E~dhv}grsFEI-u`q^&iXb7&>T|cpKVuH+Mg9#lJyZl$(gQOu`h_kaR0IiGR-d~) za!;PDKdd*x^iUC0Ne|2*8AC!vkdS5dx!WUu#e#bA8)Hom6+xBsu(r-fs0b3WtUh;p z^zYnOtFVFIvxRM;N`9_-2EK%fAR)`@b4h&3KhiDj%3trT$lqL=#bvqI4^5o%TRl}- zex5KfuSTeakaWUC#^>eD?|qOSicXl2d#LtG(UOpJIPNhM`F%3A`!zFFF?VZmRaT#? z<1is}JOd+0sInryoU1g~i#R0j{?^kXjvwaEin-Ld41Lp|`}1kNi^V!}6;Z_Q4h5X+ zOI9=qMSs~NS&B{Md_U3I>vUz4P;|mX*+MbStI4aGgrXBB<{bUgx&M1Nq3DDOxhhZ* zicXmLn+%C^}(c{={~C+t-6lLeU8m zw-yBP+(}28grXBB3heE|?;7JxLeU8mn~!woQ>RTd2}LJNJlxvTe1heBbCwFqpvfmH@9hQ7_si0nW%c>PPRBIHzD?TCm3@A=D0Zi@4OP2OZFTzK!I&1w8%xp`!GZhyWzQ zO6bmMgOi$jg*3hOn{^J4+&E0^ID8=hRZahC=ZtxkTr2R%rCEtz`kdsyeeNqtMrDpd zBGvc;&Jl?cY3FW6X-G5nvg2#M@I+Vf^4yOWkIX3!#1!rI!XeKa(u{>pea{cp3KsgT z&;F?T_u0u9SLxS|Q&;zDR$@h_?BYbPW};S?Er*a8m8MqAP3JF;qL;R5NK=2|q#?>J zEG1S{4zz`J&ti{wz1J}=WSO?0XZ?Uy8BRG)rCF=B?>W_;s_`mw4;f4Pu&!9zyRf)d zrECDIp2SRw`o(p|R9T4znaYX#YaC*KrqhRzz`a76-giFHN!&d0FTZrUiLF|l)As#8 zPjoE!9IlQ3Yo7ha*kz6n%V%jxyS}oQ8yx7_t0i=1pV1la*{gN{s&G%NMBg8qiSNf{ z6GgV3ID`bA1*GZier>EMbD=yJ!7;YNz4JR#&i>YZta<~-$33|n`~N&^AMoL#V{N+v zj;2Ag?cIw%+D>^?nsMUKJbC!xU-nl*)p}BuBGs1HnYoonL-%bZx_|#{QNL=lOF11U z_#L~vGkC}=`;Cx5$F5!7V;y<=fnh@H9LBz*6Lq}^kY*m_RNYlGZjfaZt zX_xY*Pcm7Ehm$foa($b{;jCLsLz>=1dO1?;dJx9XJ`eIokHz*Jj*!wX?fSGN8q)Mj znB~Wau}ACj^2vrAL;}wO(v0o;ajXbJ5$Au;OrLXL`M z?e^h0@^hpa8@ZBx6(~5^mF!<0fW(N6MI2}5^s(LjrU*xx-hF)^F51j*?vyn!5~?hF zFG$mv3_X8|=sCQf?{fe?=lB%i)5X}6b|Iq5yKB6y|N4FSMBy`Gy-VcYsQ##`k>#D( zXsth&^?Zu&CVR{BbGJS&qDXExG2lgnmymS)#LNlROpjWtM{}g(Co4AhS|4)R5w1tRJ&!Fr_ zfy&!kivJmu1nj$oHa#L@KedvO*@L_uv1!X*F;uBCol%RQmB2kwWja4Td-Wx|lQoVb zSv5_rn~z=l$j?<>k}wgw?vi^IKS5{P>{%#3b#~(?+WZpfB@~^oN2i~^5Q_e9LT0~m zuN0jy;k-W05$-p~OZeu_vCnS4Q(=w;ZReSUq7(M$8{+Snk!pcSC^}(c>)BuJ=L#+~ z2}LJNY`j>&o??QVP;|n?Pjg%@MJW2e33ZPtn%?fO-pCm8F|Q%n@UPcI$#IeXzmDOm zEbk2G%I7f~&hCnlpIZrx#6`I8t6xGLMy;mhOb;YfS*q?d8{#aGRJXf5kibY>gxf=I zUsCcokWgi*>a^VDoIatf!|j0tM&cse9s}t-wW0GRJ&;gksS2)>#3k=`w+9j!iHmT1 z3?PrT)f)-vA&G~5n{l}-IIn5gYA-Ag{aS?8hnsl!2ggQ(QBve_d^ zt%k<~35>)=xIOOEwJ@5NGd++{WvP-^)0xWO4AhQOO?DU<;b1; zdLV(3xCpn0ycUB#<`vIZZm9ldNms76CC3oeh+vH=9r>5zs9dd)c>F1^+^YzT#6`G0 z=*WfcK35h((Ng8Vza{^2J&?diT!h<0ZeLPzuaHn>sX9}w5m$E)eHRiC7>SE;d&u+T zxpyOwP-UsgpQ|QU_cUWjU?eWW?J=*(BiHZU#~bqbkRzt5ols@j0_;D~kiXkK&67JL zfswcfcl*&K_h#OH%^=eQ300P=msOhc=v4hZ9!Ov$F2e26uyRWA_-K360|`}@s`M$_ z@{^QzDod4`n{ay|fswcfw@1+%V};y)`-%n4ZN;AdkgBCWbus5f zWUq$49}WnNC_hEW*%LRBI9CtTW6+={mTgH|sj_V8YI9k|vgbtKLJI^&ViS^f6Q>3~A&$O9iS`Z&SyrllKeRPHWM7NEg%${m z#3m%|Caza1XnJI$vy6l+E7e0sOVdO4wHQMJBe4ldy9qjk2zeFdHIHlNM_xhs`Gu`b zx%&#nCR7CHhh$lOF3%E+NJQspAYF6Z7OLdu4aa@O-B&O+p(04gvijWZk&dq7Pjt<3 zTd0zsch1p}yRV@1Kte^3kY)9`+v5#g#X@u}xGhx4&#PXj!`)X^~)16lL*)6bNsL6*-Q^4luCMBPLbO=cV}6T zha~>+5GsP(mF3SV%Q;6o$`CPwJQ`*D#OppuWO^W>RMKNYlie}P_LU@}9}#Vd2=Ndq zg4>nl%iDg5c{I8N5$B95qQkiy;@_0t>$ojcjks!etXWnsrud8^L|n}6_Ats8sxc^J2H@CLzy>oClUFb>~a^%Pg|3`Ur8V%>n1UF_V1=^*kcYSV=xY{E?^% zUwzi!BydmE9b?_ADxXG(d>b;rvZCo%7cveP+lJcsni{Qr2&KZa zz}S(O-|~+K3JT+GHACJF>VB11ZSMJ|PXCW(xb+HdJKCQo73D;=&VD|Gy3Tl4GFF|A zBkAzVuC@hxn|q~Z@8!O$XC9A#I<#DJp!r0`ztNHpSFZucL zt<1er&$it6Tfy_4jdNBok3$_3WAnOp;U~+a6Mv*{>O&|Mo)P-xEV_a>0w=lNj2dO` zmAV_`zN@Fz_QBbUda&In@#j`iow=8xlJ&J8pPRU4p(B$PK}{yWl%Db-2~ z7RpRQJ=^%yT5F#l!&-~_`|fk&;dUJ(_@v5nrD{ILp4J;-_WJ&rWPPIK`B5t?B%z)z zD}j;NgrsHrNPSUHKk*^0i9!)q%;vmqhqcftA?9Tl#0YAzN}$sOGo~8 z7yXuLmJ#N;Qs3hxk6fKmxre`w9pSo}QTCSR60w?yv_xPeHleO2V_|gUMR&Y$o_STp zLP%Pvfdgdd9KvAi^(Hb=S}Y6ht1!*+E=YgL^~on z5D`iQMq(3R&h7|0@_!fXciq@p*+NKKspKBMOZBa*Yx?TsF@T6%3-`Mo5P^}{ggPVC zlc6IIc%Rhu=ln_Lxl-Gbv{K14@?|wuB_ebp-VuS3*uY zHu8{Xw>}Xqh`>l}LY)!!GZ?lw$h9kKf_bjgwj`}o@{D|0M<&niY9fvhfsxq6m$U1j zBiG+X@~zH(=DAWejy!U8-sB#tdWBX-6VZ@}T|{6cHu2@`9-|}g7TkjO>0Hi2NLs1n z9;$kUezA}U7ZLM_z({ODoe>&mpd-K6dZ}ys@8isKrM4w$rIKglOYKvIh!#ZTCITa| zi7#h&(5+Oi$9bEJ>sPWGd1~}@9{xSG)@k-p`R%06@LXxka%8gV&fb@kYa5aurV*v^ zwryO0)Nd>D4oD-x+tRM71}5 zx>Tu|V_cbsG-DewEOMQjJzk_9w!*T0@5R_H&Ku*>YrDTYX3lLZKgNpn$t0d=(^1?;Oic*&*Sk~{A{APyJZ(|xQ-_0YMl~~h#I3IC;I34+23xR9- zkfz_SP4+ck-($FVSYnc8#UHQJ+9}Q@*Z$#Lvl1bnxA3Gt4iMdbylNqEEg#a1{hKO^ z2Newy;dv)oR{V`AkjKgQFzwp@Xw6DYuXdg1+1X2sx_iSy;Oal58OvsS#*gNuUu(`j z(y~VI_ykwXo+_^#g^upitVFRyiABn!fuhQ?A1nl}JVKg&=VyFc@pMERk*~~P4OK^z zl!+Ob`?e#gYrAG8g05y0Y5r;=J`euELf|?=q-oA0Q(=*QSzR&uLzrb1I8!n!S)%Sg5sS-DAGLHrn^5Sm3C)ewJn>dTRAV zp}hq~yYMv@0@r&XO_|q&79!o#Okz}#&Kjx)zr1N*d190!51XJ_iRwSJ6hr+oio!F# zu@Ja+3~9zTHSQ>`eNHO6EDW}+L!6)Mll`lEtsKFTp_-K#x-C#>OB0Jyl?GS{T$6}2 z<>$4#inc$!=7(N1x2#;uIVg=IU$;t*=teCyE77!1R}o(JHNV@wgN49Vj7T$dmYSsiuOWOf|x9-vu?$P<0Ui>?>=AJ+pcM5VKN9JM#Rw2x;6HKZBK zn|r8utS#d`PoB58s8-UEuU~olzxfAjuOmu0n(e4*uOC=2)(X=FnTLw#{>%8~>u2q# z!u6@v6{Z=k4HhNOt>(p3E^;7IDqC?!j(8`i6>^KcC}y_U5u22d>}5 zW1>3oW`A+3jgzljnMXra^6BBpy?iu>;Rq@G1jFi^j8hECtLC^tBKeDz`afA( zIsScd&0b({W$mYRcE{gUiaWCA?X0bv?C*G&_78hc!$JM44VkaGa@-yyLX)l1QMGSW zS;wl*c^&>8+r%P%eqV!My4qJb^c@z$^|_2A{i^zoE|G&Zq#3J|?Y*l_i!ia&f0vG` z3fJ>GR!pkpsC2Y{EaGs`Ri}bz4(X1CO#E&&T+SBHo>3BIfQbU@4H+)+lBa+H{D&z^U)qhx{Qv53Y!PP(>-1dGGT|FjT&-WRqJDlt$yX0)cZgzBJBGmuG25uirGAsh3G%=UQGLUA06BGL~BUX3|8`_Vt_4B zxQbu1JZtzAbsS)GRJ^{{HhJXmZ8SpPI*GWpK2W4ie97{xHGCD|Sn=kZEk~Nd4l7Y& zSQ3%rOh?hY(zhCJH|LneL?WPDM=?leIui4PS&D2rUUtU2+B6MX<$J*5g?Uk1l){v&(U261}r+pD53T~>PqiSunvW|Ow z&fBw(EEJ1aeErYKikGaU>$`tjeZ!<`G6xq;?}e_I;w`uEb531PvV&H*``^E zOnZLk6{mI-ey;{u2&|)!W~}wH2fS*bP9pQY!8)q0WY6vB(yplE;^$VHl^7cQh(G$F zqxiMPR11N16w>sj#nK!6{o+o7&HGwMRnfv}9f$vH;D~J5PqPwR*8j}cG!GOL*UqyL zSVtkv*!Z$P@RB7vi=&wq>Zl6);jR79^MQ_l#}hOwF>}C0{&n&oF|Pr&A5e2*9fdUA zx{U?zoibPiCtItdYHKcTKe~U8qsYui%}Vr%IKmIN>Lki8+-xDRjzXHTD(iOemJfo( zqY=AwRJG%S?0GY6aZGN%OtTW-{k@Z4Pa7=Kblz(ruvSBw@{hbL_~Of5M2~e&9aXz0 zOtXc2cg)c)=X%XbOpRF1#}w`=o^Oq@5Ll}rO}}h?IoS9cjY?+^2$L(TWi!{xKM^_iAQ&te^8l})tg}IZJ7*fn%%sf#}Ty*5H z5LnkDP4nj&{KSbHmBrXRxph=wMrS2jMfi#N2mHkO<;5)o*0o5}Tx$C=;zi8>@lE@( zI;t=;wGx3bWyGKme^F^(6$^oNEz9Yg&DS$2w7c3B>GJk`T%e>=_t|HT}UKRptXQXLOs{dg=>QQ&` zDEnj`RXCDnB`SQslRwVgM;Ok&76R*9q$%h0U&XU;>m#Nu_*zF5jtE+bW8BzuenBfJc2b zSj;*;oVs}nLlbgi#8Oe~r8wT>zrX|@t;{0h77 zbsQnObed=(aKs#G`bE!yUHQj_BgN1hT*Hw9%o8v#p|Pb}7hNA3jTOb-q}Gwx8{ONn zux3&FkllA2NHg}$ht|AIgAu~EBA+GyKmv0H`pwA(dHML#BgM+38g2h= zPby0;f;6o>E7E}{t2$JiY2Cq+e;|!n2EEu8cL z-W3=qAz4QtGi7Ng z@(#`~x&$_>j6`e7$!TS&O}-V6G-DY(#QPGhDx(T>aw{=EQ&O?KNubzzsE&mwNTYR` zX|zsyAkEk;BEBVJT130bsKU`YD^WVBKQDN7jF|r8Ha{eG(nw*T-_^C!18K&}6H$nW zc6~Scp$f+qtwfs)W5lTRe!NABgBq?pnipEyQK#~RL(P&F;&N72uG@8g%gv5rqeaH6 zb@|$p`!!VI8{}3ZZHJMfOq%|@K%s>eqT=mRj+Ygd*s_G@i}n8bw7j$~BQSzjX}m~7 z6~5Pwe)QD-I$XHAOyMh{t5}F}2TMBi*4gc4s^^ULR(!e_L&bxk^LdNV5*n)TZF}^i z`s(;lvGVLfUT^V82NHOXAx*2ovJVx#?aTP>Us^a&g?GM{7&)LmZyM2AbUpmU{3XoX zp7o;3GYoUQ%2_F9$<6{C*Obwij8>b^{j;<9Kg!MmJc{dU;}e`fa0u>J+#$O=ckn=f z;1VQ2a1CxDB)9|;AV6?;hhoX@&frj>NQ)FGTHK2lD17(anM2O(Zo~h}^OTE2+j`-{Y%N zT9Oubu&CLy4A;JV?!l-ksBSCUyZu!Ugr0IG-Y%-HZY>z56_jBaal~QYIQ@7F(IlajR^`$cwP4warne^P+R|~1 z|AsSTb8W(r6q>YkJfkW)cA1Hm2b*cfLegoyt2Zq zU1q{ovWfQiM0V}%@pJ%{d$XcQV)!}!swh85W{ch-DkgWC8!Ewm|?@y zd>LZKHwAtfg0nb448(uU=m5v8NI_5)jj<-76zc&I&KdwSH$bcnuOjabwTt*oWRdp`>fIt<{!)|nwOOLqYfxrx?C=nerMV@!~-VX>=0ll%|4EenL z)&qeVP*EawzzX^Ko_9YWPz7|iVQb~ym6P#z?sz+xwk~EsMTrt666BxWdHsMu70{VW z9F%+AP2+*U45%oP(Q;YNzby3+2vh;RF8d8RDpv*%1ZF@*iArtW$dwPL`vHL}pzF*_ z!(!Y0$OBbCY=8AhjyRRsg9m14y%2xi=F4ui%lHEVRX~)Fv9Q?VnLH4fq4h#s?$_eX za?sOyPy$szROrx<6^%=u=n)D1g=T2I5Fa>Rm9?Es2mss&Q~{B3ZCkeWeyT)|?*wLO zy%66Ht;r%ff-k#L*^l@ z!MGPcAW#K#%Oj&$?4ZjY2+V+r64m(|sJWh8`vHL}prekCXM@Wf@<3n)RFpW=eiA$X z<>(IxQ~}*$_7qm-*d`AIW+D`N9riy2T+V$IO`EP400KOj&A^qOq**n=~JJrI}?Dx+SAo3CBK z+U*_w0|He*+#NHIg=U#p)O|n446PSp<{c--5fc$f>!K=%jiq&%2r*J)#+5LZ&`byq zN}vj8W2>79;ei=YQNq~LWRDRX`h~l9>=5m;n_fjB&+G2oFl23TR_= zH50-EGoYe`F+Q3J;Xw&h0c{*5%!Kg345%n!jPqtfcu)dWKpRIpGa)=M11d@w$15`- zJSc%Gpp9d&nGhbB0Tm^TBej_j9+W^8(EokzgBeg!0?(q{_b7VyO3xW{{+yl_dzw{s zColsZl-S<8Gz;tfBLY=G*Uy}ntsb7u>><|NSSoS0WSk+3*ti1laDIgusFxDPIlP$= z9+W^8(8iUFnGh|A8BkHexU%>GfhwSls~0mNmWq0y3JBvG&P<4qA&T!QaKKmw3Gc<@k}-Ki zlI3+0Ld3?la+(MURG4uk@La+~2oFl23TUI9Ja}LRRFuGT33m@1aeyfEbgsO^|Bh&X z93@PISP#s&5|?&F%FugEgjf$spbBUlB}|0yzznD;@uo*-*{vrE4@#g4Xk+g(FO~4X z45%n^u~<#nb5EoMs(|KCE@jXCiV~8;DP7brlk^nmlCJ~0?(XHgqsJdfWR~7qzP03fp;U5CQtNi=+uu0fAR9 zNfW370x?UjCMaDPz3~@WhT8Ir~(4dYTXIrtj`H5dIsq6tWWfIN}vj8yc?ag z2daR;d&@}^r~(4-6emrf3JARKn>2wcAmA=8sNpa1J~d?Mnxl$%nD2|aZ7aMF3k2RT zP1*xhK;YfaqzP03f%h_#CQt%*3tpTlcoA(n-5>U7s%l z3Gl!fHYg42!RK$|#0Z0+DjK67|0;Lxxz1EU5#l+0|0j2x<3|)%VYYgVVJ^;|&EGo{ z?8QX6nV=a@gg%q!xy?apK=CocgAy2nDs_pJYNePWh6g2R#uK4?BzwMFeQ`Zhcu)dk zP~~-GP}!FPh6g2R#uK4?RPFLkowcKj@Sp_7ph~gNR}Ige$MB#8&3GbokAS|pw3@FP z3lBU<|4TwacoO=_w5lO3;iaLidQ{ZIO|;33yNfV^F2}sgk-j|36OX(|nI51kHFN zbdOiOPknj@U&WRrN?;7CFZQbH=(qO`4@%ICCqnmted8M6N5F#;7=vokqw4B!A1)Xk zl%N?;gzk}=@8glV=8BPv5*ULDzS#j^sL;0+C1}PIp?kpc^P`Re|H90?Fh@Mhvy3s! z-;LiGfpXBnpH9#WCD!tp>v6VuU2hPPl%Ogs*XIj2m`FGt!d&O9V!~bdP?ZATXDf#_q;rzfdA%hmIVUPkyet3B37Vlq&757-57m#`BgCBK z@7{)JJLaB|FZw?;5mc3x%mmKA{LYE7oH)!0nxTaKLnk%mp-Xmse(IA$s%VSWua<-P z|0zLLbY5@%{w`O(+OS%l!v9Y*lvuH$z1siHbGtr2b+#gpREN@BetxE#iJ&SvueT)S z=fo&ZJmmzI?r}YEM1U63%U}h0wVDnJa^JQUO6Es5!+D?4r zd=RQO>seX}tgG(!p6PLdSXG`A{8{K+2k_Mik+rC;1g zO_pt=(Sn0G;m3(5oS+#>(01ZaVsZyL`{&KW=5HTsBB<)}3V&7Ub<3h3KLVmsX$1;PxVIqEu@yRh_?qNsOnPX zR%+ZyAEO1!7{qx_&R8i&+nhjJ;=yag#iRfDs)P*cx3Zq>)cu6~Eq^_=L= z37Vk4{R~2wRF4{|K?85a>n+&+LM3g&g-S|Q-X8S3BD6KH1h!XCHc7DRN45T(7|sbe za?%VXXgl#){v!%$(Gi7|bG$t$K~<#}w^LgmkGASZwY8j>%83|G&OxCS1asmhCuoKew4EgBpUtni3YsQX@(NCog`^*NG*-;hwL+N4@ywg>c<__jMD=X^cFnM zi6)$Yb03}n3?*ngNz&6Z z$J7yXN3p+ndr*R^YJY8|I)_ZM>n-?#6C*hRZB8?kpe-v&Et$94E@7LzobQ8_psFWL znyL$W54Y?4V9wnGwfyNfu$R0A>DeT0O?n2%zxBe2%jq_-w49(BO3-%VziNzatDV2G zfF0-UK?$m&XMmD4f)gJ(k+Q)13x z=~rHN_?O0>@h^=vo8>FM778=FLwqQU<~Vn+g7{hi-1X9Dd|&u;4g1mwzd4t#)d{Mi z-vvk{TKCIst-o=Js@@qYJSc(R1%TO{tM>&GF3qwnkBjTWwDv4aA=$5WmJe}ANa!b zyHvUr%Elg9BcpNTD7r8HtjYy2fE5RXP)w*Q;6xY%yE4f$`}_g=NO*xOhey)T!E zfHuJIW>A`cZ@b%KdsMDX>b_NjO)UtjcLk#yWml9Fy#!lRlCsr_vaZeZMZJ42SP)c& z-?RX~M55r8^Y)dM(rA2IM-u@aZ!-Eh{GO3CN3g1`(VHlJDQd{R7)mHI0eCyM`3KA}M6F-jJ-or$0-d(9=zh#?DE zliU~i(~Jti$*l#yjZ=2!-YdswbDVVwE@DHQPP4(1EI7K5ZRx(pmTFzBv&6tfta>B( zt^3DmL6%I;ampv3(=yFa0^-9Fi&)U>&sIrlKfFT1%EuAP;CGiybx~F6Jqw&Maf{f^ zgFbeCj4D^wy8dIBGU!DWHacpSb9knOY}@#^VyW`CiDTiJv&p0P#W?3|S;#7_R{2u- z`J}WoDHNuRIa#0440s?xmypk;m!(7e^8?|^s(>_Z1g<&VB7By#(9YJ0A4VtvXQr^5 zSEe~%_g=uR+seyOZ$kC?tZZy!d0NdVXRoGltm@-z{AtEZ$I%*Rsti|F=ZEUZZV1^RM zKMi+AMaQsrcj7p)`NFRFG4nepe=ka|(7LE9GTk8OKSyS<3|HXI%t>CSE#)eMoR-WUBf*CdN&U~A=AM;}38h7$SG^>vQF62(pr-NA`{$1e1XY1Y@zNt%*%fa%k+$_zYxw+9%H=yu5SXFFkXQcBm(RztdM%!CqWp+6 z2P`oKm6YB6O$1dX+g-~Uad!lpoZ&4eZgjt0!U{}p=_ zdP`C>YYMA>$}CFVdM!*IuEa;5eyprtGRChaA~#rr{yop`?e3$*46!?w{~XMAlugUx zMwfQ}-m)WW7Ua#Ke8J)7EW?KkoOoUCq_xEH3oLxHPGE)-2|bECD-LSK>fH6=#N#F@ z?G@(7vnp`|g$EK;RqRq>=ZK#I+1i$wI8n6wJ8L1Yb!<%QAtr*VV5xlD)@7TgW#z>7 zx$ms?ldWU*4FWTic(|f~bH)*WwkaYDC)V%wwZC~C&30cHE3k($D3?ZXZ$rt0o9Xl4msqw59=0t!g0TeQ(ku2he5gTuB-Bxm#`i~a>hF* zZ`-FH%oZvL%uoWhRj0bAD9b$0p0+>>&p;4IGU_w&ln)BVc(ZvQM-<4d%z zsmX6jDl|ihRecUPPHf2`2T%Tm6Wt5dw#FxuwK5yamI*SL^=H#UdBw5~Eti{oZWa?VSAT^&NjVDjPdEF&Fpv zNv_JztU3AFOi&fXEe_;22-z>f(X(55`IX(BKvita8^`Xfh1i$A;IZa-F=wC9+47g- zW`e4;?9Uw?1B#Ijs|^O$$3`k z9>Jx5Vp-4S6l;!K!AyLso5G$c?-n^Bx0#@-t`lJMp(oYw~7aZr5Z$20& zmI^(n3fg1Vl#*=nt(=@F*!LgHl>u2;m*8*{K~)eZ9-}_;dD^@A!FF zVXL>X9{2YIS3gn9;hg$JUvu=JD%c8N>!&xiRl1lJ2@%~kIeQn-w=NP?1zY;?BOjv$ z=ljmJ|Gi|MbAAgmK~>QHSMOysddc08T8>iDBb;%Q%mh_IADdVpi_sH@uD$Mfwx^17 z$wo6lRkY{xuZ)%5W!X9;OnE2QRADs0>vMXA4dw4HFJw8ww(_g(y1OPOyx1SE1oTQH z2+UC8P>n@Ssm>yHrcX~!q|S1}^6dUNrS30IC#{RBp!~t)MQo+?C%<+cw`zQXyfQ-R z7}&{4RrCtmOl((mi0&@qahy+V&k9Iv7d?6cO|)kQsdXtWsN@T`dTMB0z}7r?63aKv{U zt=_0VO6*bC!$E~-XFy|3k~H?f0LR%I*6kIj`~30(E#E$U8l-k8^7{nRO(4Z zZE-EqYddnaaU)P=K01ed3UJ(?l1rO@v9TcVxJ~PY7|#q~#FeC>9b~PJe;IK#kw(oZ z-x+aCTyyllRYCr=Ix z+SCsvOaxVBDg3joLSQ!eLGhEEfWJp2>uANc6*Cc3b@atr8+!9EXANj;ja}DM+gD7# zGf{r+eA@v2`!4$R5Ydl6)wE68FpzsxUXt6k<9>H7qvgK1&+x#=P=bEngnyB3Vk1kj zPJOh%h~G>ERnf1mNYaOz`>l@XLE5amJ4^)q{tGNs``~NV&pBa+jamD@#9x0rSnCwA zK@gas1f4TglJ*3bvxH_JrM=%a)RO_fB;aZjDIZXsr!BSoCQOB}v_b|RxW6Bm! zhz<|es;15;2+UA|&Y8qBDo;efMsr#@f@lxkcZNnRLn4$Y-1I z!~SaSyBRlx*y=TJsNK(*-$YQ=9Y>Vy_jT#y<=+nTUb5%)GVA+wjkE#z^Oy*#qIbOc zOt+~+_FPNWL>tgNmx-V%djDFI-cOrh8=0!M7X7-oiJ&Sv>n%S&e4NF$dY`{my{LXS z3fG*f%(Lm%SvK4{wn<|xWo`4eqAL1@8cC{kJkZiObu-OgDZ6Q@sEU3!hhKT^ubhzT zUMp>JnG7a^s_2};{EV#BJnQX^?X}hgQqF)T+J#oT#>!m^MwaH`61XV###8HV~ zrH<^KuxLaVja7JW`j!wKeayt`Fz^G<0cY!!q<(FMl1EU;xGL++QRQ2_s1ZLn@36#ciow(oE zrda~Z3J=TxfiZaCFK68e%uoViEY}HMzjm*$O?Y62s=xz(0qjm-h7u5CxlWAzl2>a~ zJwSM1hN{2=fBWoCV1^P9W4VdYNL}K0Mfh7gvK~giGL}jZ#!{IG;%5-XwsIqo1`lH! zdLS@E>xCH0_4P2?TzFuHs=&i&f5U?kn4tv3Sgv~*JyCdIhN{4W{@(d}Zx;k+C;>5+ z>mDt5dynAl4t3Gr<6sQs=HKH`0y9uA5)fm#?s0|p+W_8wX5+3y(;H zP)J?kH;RTzj92uRdXkC245?SpSgv~*+e&y~hAfrvFt)DjPGE)-5M#Mc7;P>*Fhfgsp0Rrk2f z_oP~Uk9zo_Z8e&qL=8?9NWrYS#}&SRx8eJF;L(=*C_z;}RS!^O$Ck0_9ttP!a-vnC z1J!7T5~r#KsME)nvFRSRfAeblss$+7kIdLd392&xVq`EM*;?`u?x$-vtI-T4@YgE3 zNA`@_w8mGOiC@=Hf~qjq*Ms*EP)9=R!}$lka|1Db7w232Yuomm`FML61O$ShswUng z??@c7?|YOIAE{H&xPkaqWwoaN*( zAytIxpOn4iCP%7^*gwF+ZXBzUxaN_#R8*B|g3Rob{5%r?h;2oQgnQ9)!=W}oAPqWm zdr(!IC$-p$^0H?FP~ky|$aRIqt4$IcyaRdkX^3ufG$K5V;cTnl809`I1!-NPj0Fa3iqyK}|>}P2l@*Kp^c- zTpv8p=K8iF5O8l)f7_6>pjdNCU|#|P-ziMm76UZ}8M z@c7>deA6xIrJ^2me?&UzrK0;F(n%AM>H5eqf%;yHbkancdgJ6Ch4ps_kxrTzS#X*> zDz>oLZb&ChlsX+PS9qLH5J)FY%=*Qb#q`K52&9uH_6HYZO;w-JzWeFE}Qr-H}QVQ=e>=!#_!hBOIV&kD|owYPaMr)zS$9>7+dd^O>JRreqKV z(n%A8YIw8tar&Agoiu^l2i6H`cfz-KFV^$(FtH@>OQmBkJ`ECaopn`Nrug|D)|?VM z^Cx54jvgjDX^(2TUdde=br1y7NfT9lugL@MHx~rbNfW_+4$F078wvvHqzO9CBb_us z$9ANXCYn!f!OHc}j~_@UO>|ux!WvxHkDN%G2r-J%_PAVP2rK$g9}|%_5u)!>qQ|sI z7IU(c*j7lp6WAM|FL_T4VFfo#5CqngG;!$PVAlKJ8G=AMX=2RHj_kl2m`3#af@h>C34Oe=U_7cwx(p~As?lb)v zLb+Dm*{PoC*v5?`tynHe^FQCTXBZoy1Qi`G?#iR8%(`UOsF&T?>S;bML5cpx$F{hWQ{D|KfF-=t%d<{l+eStpztpzL1jG!bz3bmfsAti`XX8KwE1?U-ba zIUR>9cf95b0#)7KSF(56*PYEN>g__b?lL3cdGmgX_o81+MEQ`T_U>bQux~BXFiK03 zEzf()v+zKrY;#|6XB$0WslNI2W<|H9V3g)>l82qL-{3EK1+3QZY@;e;-y)8AaXs0q zQK?*rhw)1+|1_wrjQCl9Zh*w#2~!-Yw)AFeGNoXY=6C2LlG*P~$fIOw-$WGI z7T>agUc!H^m%gx4vs`_#9_RrCs?3Df#qL#n{~oN&Y`sCH@6AI`#4)kOf#uHaL+7x) zH|FsBJ{M1ns*=+nsOs?jCC+!hk7vmm6;aJZeBUvGh~gfUfEY(kO6%*9oqNnT2vjXz zw8)9EJCTDEb6q^>I>A=Jb<#b6h;>j)3bP!)L4t2;@e1ZF4!F_!Bd3&vE^noX%LJTOC5;6blB`B%CLff-6b zjODsVisXt`dT=S>ff=d-kHjnCi@SeYO9{+S0%G$MtP$gqv2BmTg$G^_fC^*qNW3<< zn~~YyyyWM#_jLj@l<3giF8fw3!+KZC#LtlXpX+7))Mtsjymo}}K!U0u{+K!+%Mq-9 zeMpkdAMdHkKkwiGpic)6pFpMTE5T11Jh!h;g10*{!u?zR=HigV&v)7h4hCAO*xry$d-`Vl!* zCH+bWuWO*Z2mh{kp=R)S)CiK6PST5iUh=o*Ekm@&yT-0f3zCqKT3E| z0#!iJYaISINB#Cnha)L9Si?DsXEMI6oUkMqL;1Mhrm=`TYxzjMJ#AHs&x;@>rbQ}2 zV1^P9cUn4)&1$ob6Tf+vN%;L56)wwL5_-SSsA=k`&V{hxP5!8|p^hQ@|bTr7DOcj&G1NREOua zM}E#}U!OIZ78KsmjX)LDPCS?!YJKTdgZ*+bOc1zFK)tETS(!4%M};`C zw;%qemA&#W-Pp?cqfG?VTlRfTw&7DcK_Jba@a{hn-?;8zEq{eA;=BZV9}s6QgxGo( zEhd9UVo#h=`H?w+xol@!?u$|1`qGJKo#&ak9;%qBMU4Vlzv~dM8{PGcCFBzcQVu_pfZXK|b5&b+qSq4c32NoQCgDzD%UR|`O64xW`_jv zt2V3`RK1F%uwA-7Q_xtGB$Z0p+u~IxLVM6>iP$IdRL)_0a($iyJWxex{mg_fTq6#iS>f&LpFcgs>SI9jWzM#G<;oV`L=er_Ndrw;jz8;MB64uO_Pe!d>)oL zdlI}J57VAzoUhUh#Q6qKwLMr+U(i?+|IJUD-Igmy`fDxr9Tpz9X7953q#JEgQCgDL z1)NOyytbbfkoBbSznAN1YHoaF?vDad~ppqNpljAP@ENHArl32$lmbt!lw4R5G36D7=6?yxb z6DAd<`7c0seM@*Txu!PCUQ&2qy`b9iw4UscP74}q;_qMG{%i@`T|pZv`w5R+ll#d% z*Z*l!QCgDD3{GPYpI27<@{>(?V7;KKC=Zn%JiH}ntcf2DLQ+|ecgm~1*%cr>HvBnD zmf1^_iqd?fwr8?$+>ujL!kP#VtQS-`a>Cw)HSz1s@foZW`O)U-^C01YV=YxtT9PI{ z_}y}D*0#)E)z2L*V`CV21X8*Fx_Pu?EI6usc5FVJJ^+JsI7WwGYuBDa5K6OO% zQI6I{RZyOI?vv?41$&jA>E)VNbpkV#fEdrB`0t9=_Of0oHk+;HqXX1+^khR;w_;kc zci~Y6wk{rhBx&^S0Q=LotJ&@yLqrQ=22_7<4`huxrxrBU#Lte?cCe<|cbLWU(E&Vy z|7^>~^-6A1QCgD99I@Ir_WF%g3F#v|uwGDQxYL2n=jjl}zuxRk$Xh{UO_G%2LS<{0VVRWH zd~^VhJiiTQnae&jsVFT;&;H10U)4CfGV^Uy;eqvnDtp;s>|W$wg2tL8$x=C&weg{1 zN;DrGz+-T~aMpk1?r;>cx4bisr{1aoK&)<(>{JdR1Pn0Nu8K@Tth_PJvsGD=JvV@&<~+vFyZG-7;ExiRp#;QO zt`q6w!~@J9*EPy%8s*NN11A{3?X5}DRTRZ#BrXddI|UHr{u_@e}7C;>5+>qON{VM!K6yxVzh6g1uLkWnnT=%%tDX)^1kEFCN zs)F*{b^9}Z-eq`D0yC6=7|V5!g)LGka8*z1qADnV+q5&|SHgw|B``w?h_PJvD8cW? zoZ;g;t&6Ile0*GU#_x(ScLFn%fEdelBAnlk;rC^P2WF@WJd)L}!}uK*!-Eo-p#;QO zu6x{DHkiR^P3xj6DBn7=3gc&%h6g1uLkWnnT=&?;ubWfx@txL1RZ#v<*J5yHX?Rcq zGn9ZB%XN?F*r&D!e0-;MQ5BTiO6P#PYK8|TFhdE5v0V4C^j+eF(VEspRZyPqYbv!KUHDU4!wqbU(>6{VD^L<;v#&!K=% zmu^|XvLEX&&JzXk-2*eO#LcM-Sb<85#nv@@;2l#Sm>Owo+Q%-=QSn|sEWMe)j4QEo z(m9*Y$V(nPD1j=V|9k6V22_-wZEjvF%(xO0Gi8$}j(F~2sVIReplRPVdte4sl<59v zUAfKzFEL*IH-Rdk={{&CFas(|(2>DRV8)f$v2C<`vZ8(l@ZSWgfTkmynZOLFD3RT3 zkz8m5%+}-DODKUVpy^0$_P`9NC^2TkKKWT-ZVw)mKo!vRh-3D^45%paGV+q#U`qiH z9+W^8(DcY@_P`9NDAB#vJNZj^5f2`eKo!vR48ZJx8BkH8;ji9oxwDuD4@#g4XnH1N z_P`9NDA6H*9=57`aStApKo!vRjLhtT8BkGTN59gn&tOmMK?zg=P0uXN9+&|YC9=-4 zvL+7-dsq)jpbBVuhHUo045%n^w0$Es|Cjt8JSc%Gpz(a(eUHKns3<|NKg>&o8CT+$ zZS7e|F_>G#b+4ras(_}~QDzU!fQk~Gy7XboQp0Rkt{#*?70~p0(CmR3P*I|G;7In{ zc>P@TzX?%spfPz5x-J~tDX0Tm?%mYT+1mx39ZT(=b^ zPz5x-&tUez45%paGHw=2b_`})aP^=Bs(_~VOUxda0Tm_aT^uuk8CPO=kGZT<$9*1_ ziV~;-n%<2vdte4sl=$y+A4;GKXnI%8?2$jbr;RVKxQC3-1c8XpebC0YuG4+%Vg^){ zNPODo+8&fZ70}&Ar;~Xv@!)|OP*EcBX`ibHB~S%);h2UWgN)-MM;D z0#!g<_TDA)ao2+fW@x<-<5NKQHKzosfVi{soXn3n9y~BZ>xDS+Z4uY?paiObsMYwT z%#WNNJTOD+g&3brx~~T%Pz3}&n@pNO6%bQSq=s__4@-p^S}(--Y|`C>5~u>=TDF{U z?&HA&Gqhfa@!6!i2PIGi#M2%n;T+C`2WDu!5GTG_45lt2{_BW|^2{Mx{S2WDu!5aUx)_w}Fz zs({$MyC>tGN9iSq3Fg1q6Ni`kjcR8Hn*I zDa2Tl`+8u;l~{UyKASRYg@^T^XGnG4E@DG`M~gc}gI6zQGrC)4cMnRS3j9t-EoaJ! z4~h4$02TMhD1j;<@V=J22fdR<@5#MYma_-HruMKNlt2}DEUdVcZAjt&0|He*jO)CJ zbuKyK2L!6bdU)Epq6O(vVH*H}t?9nz3zXMZ-cq6s=$*U7_Y++oEa$-&cM>pb7|k)x&naNBw|66%gg> z=XdZu%3)d$u}9IRLKP5oYSwn}d&r4IB(RX71gfCC-_FJkerMZ~vYJ9zwWS9i3RB)(zlx<_FK>ZMnA*kfR+`1^x>dMf=2+)^!j zPRexO#u&`4^GG z12a?w9yp@96PTd{#8|EqRc?<}=7$#$9+;sj@W652oxltwAjWc?_&Pg6x!ic5lh#F5 zP>#=D+zHH30%9!Ji5;gS6g!{SoYqBEP)?6(l0*s2Py%8s*F6$q!j;vM52JNa6_n#q z)SbW#B_PIfo!E4Dlv2kLDm*YlRp5cgc6S0Zlzi=HgOyX+HVO~SP!)LK8HYQ8 z8A?Emd0uQ{`>rP;X5)fm#PW-kc zr4kU_UU*=Js=x#9S-TUMp#;QOt`p-5++v&fF@)AdRZx!i-rWhzPy%8s*NJ*}cCrur z7((l!Dk#UN4(5+>%^%Skt{hshS0jG3d-^6i93NAN4 zf^vKcja;pT4^jn4tv3SgsQZ%W`OW_%VdmMO9Fa?;W@kn4tv3SgsRI%9YX< z@nZja;-=Ak@YYGn9ZB%XOkbaC_|vKZek{s0zyQ3fY~&3?(4Oa-G=Rr>8cSA46zeR0ZYq z+L?dP>y#H z+zHH30%9!JiR!n<^54D|5FVJJD)7K7R(Aq3lzTLhGU`D97t)cLFn% zfEddK5y`J6v>N;vLhGU`D95XNcLFn%fEdel!Vwd$jpWA=S{GG8Io@+{Con?^h_PHJ z*4`bZMe<_^t&6Il9Pfm<6PTd{#8|Eq{Mex#=Eo3P7ga$y-k)(NFhdE5v0Nu|_UWx% z<;M_O7ga%desXU~ilhW)C;>5+>mKY_N9{5{hS0jGN|YNj>r2+U9dVl3B*g-p?!@nZja;pJ2Nan4tv3SgsSx)|S;8@nZja;pGUhBn4tv3SgsS}gL7+9{1`&(qADoI=h5y2W+(wMmg~gXB`LMW{1`&(qADoI z=h5y2W+(wMmg~eMe(!1{KO)e&s0zyQd9*u$8A?Em5+>%=U6?}}f42oKCq6?ov&Wp@HIlz!K9RY48A?Emja;pDw!-n4tv3 zSgsRr?<$rbLug%81?Bjx*qy)(B_PIforvJ~uIBJ#2(62%pd6p$x)Ye81jJab6HWQO ztJC}#LhGU`D95J`?gVBi0Wp^I+1|2+Y4?6&%xm~?=eUe(oIUz=XK!B*RUz(hq$>+5 zH&)Dn9yBL}rD{5qznxHm6Mu5z>oA?5s)u(wvwF+JTnO;!GOH%DENm@2kN}SdLprk# zbtVV`Y5sL!PHf^teS@H?n=?DHt|?uKLYyeGv^LAvrmFBj0zBfwIxFpyvi7V+${68+w7#vp_ts+>41%i8Z)wN!KZy1~ zJa^V-QCHUq4Ag!;*Mo#={5LETYk+w`?t^~Asqk;Zxd1Zg$fdqJ* zE*r$UtcepINbBn{mJ@jlf~wZkXv^L%bS1>LI_}TXT$^Nft(SSX6|;rHoc%~kQpGA6 zwC(c)l;P?G^_NM@oTt!ik}rh%^XP z$y~L$eK$64qbo6$6ITj0Q7%VyGt~=zwF-wYX~_hY(vsAM6aR4Hm_eWlmgH52uI&Cu zSE4m1ZZ&VJq$yWRcpw2DCo6VgE00bQ>w&Z+)#JodPDlnpRVVXwW(_vD5;Zw-p?GuU z#i;zk0}1emUL4G3e3&6Tkmg_8V$xZipeh{a&BV;Jt+e%xGbpVZ9!Q||UK+XDxp+~K=uPb zlUTAR8~B%!);RG9Kvk5Mq=5q`sm%+FR8Bq4#Oqw-#F>Zb9!2*wKCeidXw_@?a3$gA zA|`^Wpr*w6ssG```>1}()Y`LDI>#%-I8!#zcwFIMgm(C=Ro@I$R##hWBB%;tJa+M! zbRJdF`aPcq}m!51;v~ zIr@!Kif+klBIuC;2&5&+yKS^O>g!M?&*!(I1<`}H8l@#^>Lh>F*Ew1_-TS;Cux;t_ z!%V#T+h5%_e~j|1!59+(OM>G(rQy6?ye}FF0sqREbL;lv?8T@Y4C3AaRT+Gl8{$-N zeA&y?@U>?8rW4J$68!tJf;JJt1M30;Rf4vrWz&l1@Zizg$hZ;<7kabi2V8z-Dm*BG zDxmwfeJ9_%>_SL112H9j5C0%98=}tvk@#+{D}gE~e|Gi{d47IjDB*5IeZ%GV&ccHdr~-O*zv;65+CMIDX3`AAl(?QST|R&9jhPT0SQike zf;gG8o7^|=BQqh^12e8f=f~aT`eAp>gz%sQs(^mhyoUU^#6>e9JTL<)SAx$D&52U{ zN&@zhglu67d?OWRu7>>%V*Z628^jLFVo~1aXXv|>pcz*JXq`CVmqC1=s=@VE3MC*$ zRkyQygh%!;=moq)PwJ%FSH#HboP`?&B}Q4(f{p#;si565V9ssWhJ$5q?m-EfaV3D(38-KHi-h)YK*qH_Xgi@A{_jp;YYr+}PAnDF^xp(k zoxK0S+RRx;^o9Q>sA}1Z1y;XW{y!k7YEQfMmZ2L1e?U-Gbf4c78jKJ60YO#wRu8mC zw(j`@f~p4GTV}8SVAu}`syg;IqvLttrXLVgmGi<+j+JfVe?U;xwUI3yRVttQ0YO#J zdzMzcNQmGb_to4tyDOuX53m(393sDpC@1Fo#Td$WpN*0Ks$7ltl01(h63VB4pjO#mFu zMCA^CETTv~vF4o$`?2L^>M>Xsx42I@ru;yeQyvhp{D zN18f*={v-*1BZtT4@#g4Jidkmv4hoR?!o^e9o1vl?GrkI8CoyISkAv2K0CKn`YWxx zU6QIb{6=g&v&ca9bZ^0WHOU{r7B(^1U$^68tIpel%ARM3g* ze&sAJR=#)m-*qQYWf}d}ad%4=)+7czil<wB23AIgh^;Mwg1J>VJCS=+HA0J3SJJ za?UE&{59G*Gp#ohRJAb24ac1lKI}jM5UF=hv*xKh#_2QJOi}wt%K6Nf_9d*5-4!HayWQH5+)fKKJ;&*zx!_A7039YK{|I7uy+B z*b{-qKFw#}-;m96_xHc$@m0+PRY82@T}iSYL#`~5ztqx~3O%R_)+v!V`Dg#CnM*B| zE4dI<1>0@MryR>2+REUU}}RY4!ScBZh=6H8>fXGs@OME=$2ySV051^u|i)PhEDznf3C zHc9r**2maCkf18Mckz2N56aj}Ma8Ncis<_}9j|bVf-N1hey z^wvio%s`tX0da=w&*i!6>T)7Wp z&TuhaVTRTVabiylojBQ^t?@hO))M0cfxVj6YbN;a5!v*@GZy$UL=ZTVfeK@w>o4uZ zHYB(5rE(=OLkWnnTqpjiRZUTkRTdtYp(^m$_qGe`vZA`-K?%%I0%9!JJu=01SMJ6< z5XTA3P!)JQ&ee?#39f8-Py#cQfEdelk75tUD#d=yFFY_qRp0^Nc3QTnoZ&$U%uoVi zEa$V_{t~QZD;&#iTt36bgy(fME7_KX9?s6-ykynDHq85rFKfNq#}PcYJsaCRJNIxD z@1s>q7RIvtwAqxQ#EM$U93#EjvyZ#r`uzHrhT42zN%?E)J`+Jzdv86o57^j=ot+8i zqUFxF)TZTl#U}7yM$!x=f_%^0FW2tGY8M5M7QUslyZg&4Era7s1XT^Gw95Wk>B7E_ zgDaNzQz~f(2b5AyJf6yEh7u<>PqwScy09!A;2uE85lP#4ueFkWOo)k~s`YJh*eg^G zVe_iNd@{Yur`GDGY^kJ4-<;75C0^!UpRgfk2>Z7yY~7v1R;tl4gOn@{)0+sY+O)Kc zrNn@4tmZMeqJKVkqq=NNsN$@Wg3$~mmgo9nxzM8<>*Nnx*IwwV^IP3&GU+tk}d#jMBWff32bwjwq$vS}>GR740Qv!d|(MHfB9jB0Geb z2=B|+td#<~vg`vYGD`FBO$4XaDrax0EZ9@sl%WLeF_JXw>=`x3sb0#Y@tGOj?o>r- zNy-tnMeQ>&R9SuIo=jDgrmZPPIBDJVaZ31tYfgK^nJisgcc!&pXuo=Y?)MnV3oY-; zO8@HRgt4TO)jx8alFf2M5SXC^#0UCzWuvd_zp3Wu?#IIwwmy|g>!K?7S~}Lm&lBUe zCG>kRR;hS1ze+Q%M2!@k*qN^*_)<;kKg-hM>{#WPQb-V(p#;P;PIY8$?uBup$&KiQ zR`bRv2NpMXBTyy0U$D{ai;&uCOu6xUiP`QW+UqFT}&++puo~_H$xP-p&c* zR*Y08Jsj^wpb9+B_G`*Iym-NhjQ#Ri>P;J|)L1w{5SXF$LfqEclr6Bm;>4HQ1rjc& z9j4UUw%Cn86?haGQJ)=gWL5cBl#(a-{rq95GOxfAL12c~3-Q}l_1T@g**NjoVUOQ* zDO6dK;b%7jRp9X|hmCEUT%HprBCgihbvjh>s;d*2q4h%iDV>cyUJ1m-X4ek3YE|a%+PuvZaJU`oBpOdC+;-7?$>2SXXT^i zAK^g>RDnmzli8SBD+1P|K&6CkT4&|{iI0N746PU9HYKvNk}Jn?Vt?8ymd=@ilnwh+ zYqTz^g7S|UQnD?TXL907v(X9n>jWv;d*}paC;@TKT^%W4XYUI8GF=JKc6@UrVL?^^9%=s_ZRhutQtl%YU_u7N&IV)K;W^A-Bwg(Zja{+F73Yv}Hv6lUo%437K@}+84t(WpF{|M_( zC$F0_KqHZ5*L0R^`BS-}b2BH#7455ZSi9LGCp%{%sH#W)8LUp+7P-vtn>bN#+Catr zVv05HR=i3xl=!E16!RSzFIT*_o)cY~4OA}lZEv0XH9@5rN~G=@#kTogm!FRYV%DUg zO5cX5Ea#ssGZ9opd!;0`n><_@&|s>qf;!vOUnxO*rQX}6vR=x+DLRS0HlJ^AcDK!a z2OM`XhLIuhSSuKVpelN#b|oUk{dOQh6?3E)v*k!GL+stUJxiNVNW`yh1hbugebVRs z_)h{=K*tpcVXeJ({D43e5Mjl-Gj)H>9}uVl;=#4<>|;PO@okR(UJq0Of!ht%*Gymr zRCwkDG2OcVO;8V{!9$WpbRVZ#OWc=XyN^j1CvU1N*&vP{Fh?%lYpMhGC@hzx-M1zr zbnG}zs~_@E5LDH(i z84HvDwN4UkfGSG!?+J*SAng< z<4;AF%k20|c%TYAkd~wYduP~h@LzHaxVck!P!*+9`&E;d&U(f@8jPJ}9pUJwRa<>R zc+}6GL!R|EjS5>DRp5a%U-N&L+fPsIt95PitMH&IN(Y9fmk$?(Z=da)9A`bZpoiuc zc2{`(+VyuE8(Bbjpb9*YmZacQJMD3Ax@mX6JrW*NMd`IE5^VOi#kj}UtQ)QCw*_mV zv0sD-Ti?YN*0`$hKoxi(&5zF658CU@?WhI5@DhEOswmxZL_yo2Q&#S=u*5#=^HgoM z%1^vS-^D%(+X_|SfwUwAK0RY!(6f~`>V5{{K~<}N|~Iyo_$Q_A*`-_7F&AznzKd4iR#h%v)JJXZ|9mnBGvxw zX0k=!t~t;DJBF|Mpy8vGeTPfhJN-O@(F`Saou0{tZ%OIwcs869)n5-&Iz7yuu>bdY zCW5NckB?$$XTEe?Yc!k_L3<;V&3{dbZ#TG(?0Yqum0xwuS>{@_3USo=Y|f&a_}e{m zqFK5_*PPG3PUFNMHzSm)SE|~3{^BLm3?-VzN3+advpe4$n!$8wVNGY+}S0Paz%Wp8E8KOOC}(q1tURAoLItY6Sg88a=dBcS^e6G2t< zSiyPcGym)yCSv;3Xx87?OU=9>TBWoky`4Tn znbESU`t@Q{_SccAth+-|%P$?F&h9#$J=|Vh?f7(@y6KmxEbkzTy1DWYzO9-Ej8Iza zu&Jf~ZNjK3$Hi%^>itS;SN>MInbm zB`MXmVM?Pkuboj3r?b$5Q(2pXRn+Ky15L}`Ysb|8W9%%zqez-QKDZOy-Q6|W>A?0V+^SOhxs;%eiAG=Ml5g$6iJbyQlk?i_tgVTx< zr}-f5X}u8rf9FF4_sW}Pir9ZYfpMeXAP*u@{K1-YYDIm>vMDxV>&vNPRR4eU^VtFo zPQ!Dx3xhN@QBgg-a){twZ5K=tO9DRXqb?8jAns=$tR*kF*Lk$fR2#w95>6{hsgT}U z+OQG&!%Ta{jD^9XUZ$MJ?VMd~WlspbWXgd|M(shJp_lj^?XAt)HbW0fyIb%&3D`PO zoH>=!`1rn?VJC)6=%Zcy)?EK<=fK<+rvp>c+h*jC zk5)0|MCYl(c7m^0oQCJMuo@h2?1;GKxFq0-w8T^eSsKTJmHgjG33Ksf&Xqiw#%H8nJdy zHoonH-y8HTWi)n;H?F%Tiuh@(8tOOPWr*EFwb)_(jC0Oi4(>H{=p>P-ro$-QcAN+C zG|f;=JJ-Odd(ua6g3sEVRuum^!?bwks~gis-cq?2UrX#norlA;6?t14dvBz%#nEEK z6p^AqQRB_pDYlpt<wNA*W&i9zx(rgg7S(HM2{waR-UZ#CZE6s7yQ;o8ybxs5H&KB?S`?*{Bdl6oVwV#_ld z3BNqI5xmtnttju7jL_}|BsXTI{72bHE_l*+|6!mu0>YToA-de%E_`c1)znZtakJi1&HU0b6jW&YsCOHlFGD-~Aid73T z{2k}i>Afe4dRwa+y?w_TH>U-QIleWFgqKDe{kjH=ptH3MpNeB({rGTZh;}zt2jgV@ z4>qFy#$eH{V>P2f`w=!8ek;Du5G~#9u14Z`?`;HM4LGeRhh7cVv^u?v1Ic3vUMjw3 za9U9wryZhQXg|&vav+yYgRgy@hWl4f2WneS&oXkf$z&s5hffgQ-Ze0MeopXM2cuF9 z)|&Z*7>5pbb?{Q9sSqr*Ty>388O9o%hG%y(2Wd^OPBF@6oo&IPT@H*kq@@qJ_=iF|T7OU>gh^3iQ2|f<^_^@BsCeep#e#JgVd`Z;bwtMAXd?yS0 z!~?^%4zrFr_Z+HgBe))?;oAvtpP^6EUJ)-Jt+nm?c)s@i)w2G5v~{cJ>(`Uo#|Q7> zd>;(Y&xd!@Di^4r7ukPS@SQN=Sc!*S7el)9)8QE%+{sdvO|`F4Y*W&F|Yn z@1r)fT}|+D&aWBZYU0*#?MKE^dW266!M%80*@?)X1GKe|a~b>p8f&|{<5!dRt8MnA zArS8l`A)s2H`x^`?=9R3NTJUSGSlw61{M*B_t!k{Msb4fOexBppnh8JsP)FgvQNUx zq@5tXEN)_4xEo^JPdPy}U)IE!`gE2txWWXn;Cf>tRv11Lo-(bUwt4b;!+-blaBks5 z>V^}OxZ+el?Vlp+j0(l?+6eBot?vXec1a_ne6>kH%*oteYu{##(IerD zaBkrQj=`f54UEBQ@yTcszy8{-HLHzub?@2;?qwgfRm%<38q8W?w7z{doLe}-=M_as zK4yRx5o?L@?9+W;ZsEk=i6@Gx%WD{k4&c+*1iJ@m!}m@%5?sz2!3pm5N2N(3R|m~_ zIc`1>sXGtR+AbVxthkWNrop}V6#(4vS};VbnK&;w{W6Hi^*b!Qr@W53EN}* z{9&59u%nTyV%!K$a4){shVN4UIZWI2zb?ip-|YLjg%dOXoFY;M6f-JxmKUIvrlh-&rat>&m=s!|x{7*rn z-ra-|oZw!3uMKyjDv#7Ajw@z7`&QhSTR4&K^HlLIe^%qs?%AO6G!(wGv@EI7Id;kj zPH->2JBMfVT}NrZ)k7td z;pFd@@SVP?kM&nopZIbMCzfWKCUOo*Vl)oMZ$P{%2`88rU!k9WP$Gg8+>7td73Flj z0Bz)vIePpIX`S4{iF)g&iJBKa>s?=kg2wQjaDsWV-}IeFX83V}d)e<B?F#Yh_1!t*yy@3ba;d=y@vZoSU);$Haq zvKl^mf`T)FI0D2lAf{UcSvY~|!u3+=Wh)@D6Nr>4`nrZRZDsJhxEFrj@?<={e^Z=A z&jFDfi1rpi7EWM#$liqdo4!aq0%D|3XV;piTcrjk$O|<_SAXe@sEI4*Kp-XnamFIZ z!t=%Sj`Q!FU-}`@6o@sm|8!k;ypkH6ATQKdlval8d$mPL?-=Zon#ug5zEen#SdK!|5;jEhhENDWSq7ix6xbj^|V^fn+8LaC|% zan2&h!t=#+i{4iqM~ZC+A~_Ii+ilU8{ys=*aDu#0W8UEOYK`hh%z{!C17f>HkcH=q z>Dyh>tGU-9F$ahnZ)&P3zL^@FATQMTbh)ycBo-1+fyfL*Jc}R;&ll6p%2rX!c0dB> z#H?F=#qP`fWE`9zFVxr^*h4+|6Kl5{M1FdUuUKahWa0T@x>4<(>hEo^cH13xXl+u( z5vNZTbj2$%M|^MFO|7n&^9t$NH5$Ps^6X7N)QoWp*a)O^^%m;#INRimK{R~l4u~a9 zle&htIV{j?SKOJ-LXWzb^P{!C;^)7AIOKHR>K39$ToxKS1;-!Ut)vbzFuU;Nk(+1aU z>mX{(9g#>c`z%;$ke;HPELA~UKD3x?(DH;*gVtJJD%7CTDoTZFRkgUmd0mZrmvo?o zR!$_|mP@P$v*M=v8$Bp`0k9dRGc6$%!#z&8!6ALYNuP}cI9liNv^fD za-zn_z_|L4lc7?B^c1B@_Hx>LQQGw>?hr46ym)C9Wn=qlT7tV-U7!>oQugf(2a>&Bk~U1=1AoPd7%cC7T)w;TTSc!XYFa|H}4K&_<&*w#u7iv&xVZYm~vevqM zs9xu!Nzgio8gmb&Qo}25lNzK4Cx5|Q(*JP|BcO=6TjB(Hp$3%}N(J-oi1Ftft8x{T zrJ{8ZHE1>9dWy0Z=EPD5hUwk5755^jRH#APu&0KZy3VZRYR`$qBta_+*Fb`_6(#Mu zDI!6tvRaN0`CPc(r9QY%y%1-uytnyEwf%< zYH)(QP$OH0_3Hk!_&xnUA@bcoWUvUb@O&|yBi07BeRg~ope+y)d$VcBn>wThC&&vm zsGZ<`A`p>`APdhI)6{zuWpOJ_>ydb;_%thp-1}q?U#YGNGG{f%yV+{n$c?fuP<(JT zakGM!CGdb~zb1{1;5BNG{LQCITAj=n#k#q%y$FiQ-mi|A723SdGsJi;v#kZui%Ny* zgWW&Afh!m(K>N$ zQPJolHHh}s;9i-Zo>Y@B>J>8)t-*<27aNJH&l*aCXm1Vfl_MZRjqG1PW+GaH6W#hX z6QlkqDhZ;!HMrNkfm_r$6$-~pL~C&3s?k~`4oe^jqP;b^SCizc)SoNk#!N(Oa3bUK z_F|!?!gU?M6?Dc zp20gfU*H`ajDu)z4eq6novXIZ6XqKufv6l&oY;`lU&L*b+=&Fy-WuF%N6GnW$=aD? zCZaVs@&0;y5%MNX5=47zaIZH1gsC4(uZ)?9*5JgFv~5Il$7@Lt?XAJR?nJCodl&f_ zGZC%9iDvhjiNmF`=~!1pduwnn*B@KeO>c9=OhjvNqC)G&;!DrUk|5e!gM00n;Z*xQ zs2Vd7t-%Sub+v_KPCH2u?XAJR{>~GrcG=e;p8M8(;?%^>6we)bnYpBR{xr) zl>8iauNJWj2yWp-xhrS&(qk%08s2v5Gfu3|F+|(#NieUhKMlQ7B|l4JAP}p7Fo56| zp6}1v2lVG{t5_Ouv@7E7?Jn9O4}yDTzqLh=Q>V72aT|z-Kx_blTR2ho@HTzV^@f&4 zX;&(3#H>bM1otXadzoHocN5ZnuUPl>QMmIe|} zfd~hJTR4I3A7}3?OJgMT#FDO5F05Tna4#GMSxWr0G=j{&>sk#2w{Qacar*<`EsZBI znm)mK-fKJv?uDcI#Jza(_cIjbA0VCr(H{tI;RKGy?0w=IW}D;8FnU%aS6>f;d*Q6q z>_=it1IHi4;u--2w{QaIl_Jd(SsH~a!DzbO#WmD};9fYpCO(kd(s&Nz58A|qV~|@o zf%9Yb&q*zf#xR=J=NRHT<3VsQTqPDIOKE91fY=Dc3m~|K6FARD7Wc6U&CQ6<})TRe$Rub7688rbGG0`euVJ*(ccI6yUIg=6*FCo3ZjUlRYytx3U2fs|?mZIAaJNV0N>_~2(1PbY2=0|{L}J6; zul|AYcL#_rKyV8uW=u?ExcgNB7=L4-CwBHAxL1~=DGm4dfWGS*14KU{xP=p1ND9L} zKJLP3`kytTIKjQH_+&8L;~d8yj6>H{(BKwM6bnmdxW_q;ruQX4H;hwLM zz*uk$atkN?CS*3;^VJQg*#yugLp%uXmEmO$gJxGaBL#@qK#T^0TR2fHZ+62y?_!_A zzBST=;9l!}a~lhy*N@FW6a``x5ZuCv>#cGc8Kc(^98JBU$FKAtxL2uIc?|bDhy;!i zoOii}6Y;X-l0@`6h#IOV!M$W@qt|oP=xVLb+`)fj za4#GM?tLPTKO(q=6WEX4`^1MZn!duyHXk%N!M$*7y7#*eECP40+`;ZyXIDzxL`#K7))pXol%IheW7x%)|hpyq^ z4IYcY-4eHW5_F{p&uhCR*Hgf#g^{IYjQa=tqDMy2vP50=Rv!G7l8j=_qH6G6hd+## z&J?0zx>|4#c_R?G7sZls3nyec1)Qb7v@#G&fEWPL2UpF+=o{5B*+UtpPpI~B`%c!Vm%O_fw*lEWa0T@I&XY9 z$E#W)AeIARt!z?*6Xb;&C1<@=-*wLd1nj=`LePI=1V5oF0ee!O7x%)?6J(B3AAiof(riH_@S2cYIDzT*56`L#>-@dKY!6FA z_aw-RX*=DedJp4}TX?=q&mye4GCT<@S|@&P)jAN^9#~i1VdQcP&ll4v%=Q2R+rw&e zFM_-na-69*FlRI12YfYX^|Q>!tz3md_IM79R$K!2L+BpZsGZ2x?HzHxDEng zt%Cwbl_x=7`1$JWrEwhu!deFfwK-XMzL@qYS_;=eAh0LGu1v#G#q;7``1zu4z5>=k zAmADed%H$`mn@vXv{AC6fOQavDL}wAp@!FlJTLBrpZ~e5l7Mv(2p15zYT`KL7EWM# zQzcEnItb(Z01$9ptL23i+LItJ{QS}B-(XJ^34{}faX{b|F}Lu1F}=SK{9^5*BS66Z zP{+M!T-cL(66A%S&zo6Gz&Z%T5g={?@e{@&xA1(W-iaCl)n66XeC>aKKwz5Qn8939D2No-fk_;<3A~1ka0m z;pbKz0s;3!sjehJ7EWM#li40X!2M8ab1#CtP{Zn1Kw!VJ+FTN3;rU|P>M<5!^<9nU z#l7%zYka7Rau77EzAFi`a6;;t;{!C{X$*})FTxrh4%DzlGiXc#0>|JhYxhbPo-d}Y zaSlWX5Y}8GH8??DsA0`YKv?S_&Lxr{3(ptR)_etowGQH(=tYnhYFP6w5Y{?~bD|{3 z!t=$nHKPK7Gd0fbE3IoBPLLOBSaUuQJAvp41YH%8h3AXuh33it#10_n`5n)Td*SDF z4Hvx*;u=Zk6U^B6QZL0(AEe$HEiEIeOE#Gt_mD{bC$h~D*iMov3Do-d}Y&tuTw z1bIm!de`TrVOe;-jEG5t6V@n_MD(uDOT)78d>Ijw1}Ci9014X9dAA2yc)pB?L4y-C zUm@Y%^?AlY7M?F7V$k3O&AUjrcYU53Wa0TTA_fgk(E5P{?dQDfiYz=|M#M1AIYH|n z611Q5)*uVdmk}{&aDrBSNk{McJnPEZSvYyVjEF&l6SOZug7$OXagc@Q%ZL~>IANvb zyi5Bzn?@k!MfYAyGG)}4R;MA`B;A&px+3HLpHi;)_fz%+UB zC(3pWZt*1C_w>02CooN3{E4z%gIhca_dR{C!3j*07k{E`*WeaU!hKJlYj6V7AGQ6 z!JjpI5bk^WHVsZdn!NZEWe*MZbQ(*-2`XVU5r|`u=f$5i@F&XA1SA4AZt*0jrlSd| z!3qAvgg;S^CZq&BBGxOTa47;1b@QIpD5ck_?p32AO2k|B;3D<@TowUSRa{Pe14Kx#dK(+ zlw$OWBr;ucQ$F$Sw^-&*Mk6KkB8w+cv|VDc?|bb3Ajk{pRd5E^n*xu_)!C*&7WCpo zh)-P6?A??9Ajk{p+mlPe0mTPmAjpDVoQP`jL%neR;C~S0h4lI0vSRs|*)b4gK`&0! zz4<|1);aV)2=YQYSCa}NONQTKAjpDVoJf-WwVHNM#s4743+XFoDvF7tcX|9a2e)9F z6BAp#P%F%t_8$a!AwB+8MKN>X0{IKP_MS)<^y0+UrH|ADWi~p!`z|NQ3+WYW%ZWd4 ze~f`33wm*4!?BX0aPhvnw+2}}iQ{Q*sckAb{(~Sdr0X6!uNqHg{0Bi^l4wv^l+Cy! z2BNNI;rU|v(zYXNYvu5N5afkK|LVELzJ||ZAjrb=#dPB5JJn>BKl}$lUPzSQkx{fg zkrLi;^PGLi!t=%Ss!_{SXO&d{L68>`=N2Rv^;#5-fglUd7t?KrOjgHUEchP;c_Fbc zUTjghdd(OJvhaK{ef?ZV^~>Q(|3Q!!5_kXiSUoqiLkt92c)pmvaiXZI|NP@W2=YQ= z@Xv>iw}X4Si9l=_Zozc%!1|7LQv(f5lQ#O_w>@g~2s?F;5M$pav&GQta@n)i&fm2=YR@?TKs-pY!JLlG)=R z3wm+l(7Stn4|n0&RR310?~gh$e zOU6+>r@FdQm|Y_fExeadU&7C+S9+I<6Xb>`pG9I?=ab(9wN=7rn^hNwj%&Tir4#pIIuK1}Df1Y5G==O(PI3{jNM$i?#BT zC86&Z;par#2!&fP&50N_BtcJQkoZ;z`7JR24Bt&I$5Dnx2JuYmf!K zII+5KO@VFm?*w@vP0#ea39FrT^rG*^VA`r(b9J`0AXz*K`fiK21}Df1Y5Jy$jgW0l z7WAU;n*9Gu#R;qT#1Mzo&N6bV{bky!=@HdzF=Q!sCd7*~&{jwNJ#R>94g8JCM zmx{cQpdK1c1Y!y;QIT~8#ldUg-y(Mt6Dc;A z6A+7>;rQ%BvyzRFC&&v4dXD?=1bHDrPi4J{T1mgC z6ge;9|BoOq)Np@)*R$_(4e~<5{cYTTBghL0`aY~J4%r@DgS?QS)yGE2_TU70AwjF1 zH(~X5IZ}DQqVI(KJ3(Hk;k6nBB8wKTL0@qP+?3#doqX z6Fr;*4Jd&~@^@~XrBzJtT-*nL%h97Ja?39WkMZG2SoungHH*gmLW3-f=7iM1=n&4@kQ$ueUi|HBw?AqO zoW4+xcSMtU@%O|zZ6~;e6TjBrZ`X`mk;WiB{$@|KMj)1oTR0IsFOv~-#%VGkNz*g%$D7Jk6l)vMQbvU$pLhHR$w@RSKEu6rX zb-xYBH8{b&_#4M=1uPY}@OOrJPIiJ@IDx$*u^2j;Cy|8Vl*6nd{3n#E;W3F9Ja4-ITWVD8id})Fqdc3{=$PtCc$8*55V1zb3dBU+wG!??1d> z@ppTFO>i%-)gaL1%<(~elzZXmih0GsR;%>QJX-+UgU%Vi_IICa;4W97#tH6)ea!uK z|E~z{h5gw5uD(SC;yC9T+>6iJZUs+*d+}AmPGH}q$oVS6SD$D?mWmVHi=S8#O+X@0 z;{^BO=TH2a;9mSRiC+`ki?`;l3GT&f-A?dThMz6N*OFfod}qmNJHfqh{h)WzV4LTX)G=M=OLe2$pE>2{b`5UvB*q@S>qI)5kQ$u8Gt;M(cE&~^OAm54(G`{Cw?g=H6?%$@ zdXeR>`VGiA5}ue~a_B zT4M+hSXU{5(1G9r63g$ubBqb84;tMs_0-;USO&i>+0sTJOO(PA9*q?+rQ#9bg-0>Lew#Jj#V)eYAjpn+|ED0eL*MVAjY0%`K%B{bW79}u59 ze~^8b%I-;I-CI;Gm82qQkXaDA&SBPRm$B`=IT?)S@%urAesz&3Bvdy1aD zR$3W3MT>FJ_W-z_8F@V*QUk#)p2S3Bs2aOoKG49v+jUd}V`2VVHUeq#;w3bRK0vGo zf?GU^KYd%PNv`JtjYa(-^0=Fgr=p^aoT5dVyfE@Ir*o;XUljua+dO`)>H5+K@nqx_ zEyh9Lvfz3qkr;?IKyZsE5t=Ym-IvYBiu_E)-;ER6aT|d&dGQjOz2q_wSAgIaPa^#J zSoLX|ByX*@&w^Otj2YrWy z>nTbdsH^lqbOeH1Jc)mDuT~Epc?D|}_V%$&TNuv|Y?YByv`CW|FQM7yqky;z1h;q+ zsrSxRUv+y58i^Y9)GDmnV^oiyT1HOMB28Wx`OTz(s?p;c5ZLBVcF)oMU!9VXQ?wWd zeM5-rnZ!dNS^>c=p2VjWyH)r}FVMi=9(JOQvDZ0IMo!TpOL5HEn>7EdB=$S$>Z z{YjvK<9xvzr?H{ZMH_)Md12(s7OqfRW}OWLwt1G;3-vzhC&|buT8x9ftH$+AA{`Lz zfZ!HSLSJ-R&FfbVG_cKc?dfE+zFt>GPSGMwUc7{6UF8O%4G`SoNn{)2Qa851cf)aR z|Lrfsh|0aeMj%aI7pRx%Ujd8+&Pc zt}iw^cWG){Ymuh)71M5_*418G!~83aR^=<%)+qF%b&1pP-u6Gev~_9L8Iz+5+vaxk zqWPTDin2R?Z|&IXO@?ot^tL$>y=WffH2g9U5ZaAx#_+PSCBbJ-nm;%VZ~a24s_fro z)ctf-wg;baXxt$|w4z|-o78>Anwwi}eHXo`zhatb_+=od-SXWdj4G+e+S(kwsGT{j zDCINs(583x5veBYvIQ57DC1%2E?~|gS1YE?x|f81ltJiwR+ehkvO8TsClq35VtZ9 z)3#meYNUIbQN}^n9N63G8VBim&(Ej@ZZ?M}?k|8?aj~m0@I^+ITR3qQ=uTH}sZ-NC zfOrPPwKZ*xOks0v1oy(6^jMeF8g17D@f?UtK;*IrvTy>^Tl3ymzh;_g5kA`*8aGbxbWNR7{}Zu4#Tfpa>4WBUif(u zpGWGkrir0;QDZtI$ifLs4+wdys>XAxRPi$8HXcteBsDleUZ@dk&Rexrn;f8lrTSm` z+{P1&APdhI(;>CKscA+fw1}yz;u(&>DpG?JKp=cAf-F2=Oz$lj zNAxh#Tg0HDC-kjdf0r7ZATQL29U5QgiLke0UCjYvmqn0;=ZopTY9gY{=0RiE74r zSSt7Ivtnm2?Lz)t#&0X%*$D21X&V3VYd5WWYJZ;EZtTxhK+e0Q!M#wg#j+?h_S-iw z28;RyXyZqO=^ftJm-`aBJA~2Ftj1?MI7_cefc9W;FmcoYGuaSh;QE)38g|o(RW=smD7q+yj*}*qs)9g z<^LjOsd!0fPPCUQexF|2r<+bAjo2EzpV_u)r+b)#-V~)Ev`5eUqx2SqG#NR)wS)Q6oXGXe+FhD>lzw_y z883oLg&L%-C_}pR)RHt^ZWQxvC&ve^1{nE_HdoYv9n;JH=I$j?>w0M)YppZB?JDU- zkQeV`igIN@PwmiTcSTC)m&wS&rHJ!W&@kc;5!#Z^KBFGEtifSExb$U!s?e~RU zjOH1Z$WqbzfpLu6`9a+=x2BAPVuD|tp4LnIaBHk_;fWbJC&&xqpc*mb_?$VBe$;QK zEETl?C7+aK{ z&|JnrF~Qy1fL>aT0nLmoL5sZz^1?VMKC|zpZNAl+rO$j>D*Em@mYvoQ9+TM~InGBo zZx)~JMNs4z2i1t8OkUPgi(2_uAHOhMmWtLvjHA3OiTJj~U&cW(!7on1I1lZW+t`z3 zvll^L7zfn|tj^neYCZcl)|dTuP!hBbqQ<3EX~o4u-J}NTDa!p;y|gEBF6vDh?DHbX z3pJ>;=3KIS^`Cyj2Q8D4)A#YQerS!tG_8qdUH$m{AmZSOg$J!>_U*>8Zi( zNXNXeL$Xw~)?yqjM`RO)mvohJP)v$au~siF`IK_{^+>~uATNxAYQ&5qLBJTtwt90`0!N_!uX}K485fnMbK{cW%eph;G-8;-vk1aGyMe8}nLDvR6CPj%` zrkB>f))+^|&hQ&+P+m?@tI%6Bqd$2qvMTuV|Kr83l zPR;qhzACqH0yVx)EiTpN0)dY(r6QPXh zFm2SM9wJrMC*hpnUby!ucA~O)J>ez1Gg<+N(GPnFedFVBZs7#RwDMAAQ9HqO&}ahd z`Mk+X)RosV*$D21^+xZKnsF5NtpvaCyjJevoL|a|)px7N9z)mBs2A&2Y4L0Y?%V%- z(Onynpp}T1bEE9LWWmUZ;MdfOGNZvDEnD-1qRxylHiCQE+XHKN*!;etPXBqbR9$xo zQ7X{9qeCUcQoRqaDBj1)0HwkfoCidGAh-of#R)2{qLhK!?H-;=wAxp}M(}8{-u?+J zBkuLYcf-pA(Ey0nKyZsE;qHlVV9#)@YYp{&;t_HONqHenUc4W}uaZC<5zY`%dBIp2 zdBc!uqI!cgvOTC4P_N_#AyWF_`{xCK*aSosAh-o1=Y+eiFpjW0MZ}k&95w=J^1>1x zJ6%DPK5`TG?PY;*0r3$CZt)~2KKR93h1#wIa z*dmT!%qJtynZBM#t#6l+Q!Sw0=Bm|&F)0j6RS1aRfp`rBw_xO)aMu;K;D<|1Mdy*H zFT7z32g+gH+$q5N2yf% z#qE7}WDhSgw}CkJxUGzwY60~I!@Fdy`c{Whu*f?GTZcU{SG-f@9ip;EYm6PPA1jGRs{Fz4NrJzb(n z-PSU4S~D;Xss+?@uOC=fKYF;tNg%kzlW^A+j`RM*yNO#LEHn1#mH$z5$0 zq=`Vij{Adr%f-RBm%qcEZR5ru<9N~RHiCO$sYJIy`!oMF7l`X{|7y(YLgHZT+y?Gs zPETE={_oyG1NSKR7fx3z4xVoy-G9;y^}>C=P=8<1 zP-<|3yig-${~qekg!o(7kAS!VL>r4B3(ptRf7WfQmJM8D5jii-Rf89|l^UENFVu+T zS5HmX0Dsf_F=)KFI9DBM5oF={V*29I-_)(MmRdyqcA3<4XS+%bPLLOBoH$xk{qzwv z@JU0fHks5@XH0@DJYP&tDOFfqn*(bXi5j1O^Nsr6Luzn>yijA$y<}?rFQ|bn7+I#e zZ`>ayK^C4bru$b(p^nIn8rVy&R7s-;`E-*SoFFgMxNzczBXM)oz!ubjm}n7X;rU|v zT!ZJ1^kG<6SgPj_X6a`#wUZj0ATQL2s<_NiFC(@&5=kD;(sx?~S$MvfE|_nh<7)`E zImXfS;#Ivyi$+p|6Xb;&5p^3l+El^FUji`}h@=)l7M?GrH@BGR$fe+j!uCj$inl*^wuW6j%(j(4Bner(8!)6kJR7LdYu|7bp`eYTvQ3Uor$y#?(6Xa;A+yu*^}pB8H9u2wbzX*xTD z(YhfQ-ldt1z^md{R~PuLZZOB-w0U>1%C^et zvaErU;3c6s(O#+~aL3ElW3rg%JI+?`SU=Pre3dXYqB5sbUEe~a2A$%8`O=(-Y0@+A z;!N9`SIt*A$crE^UT@}|iBShmI(pWbD+xNq1M{Uhk?WbYJG$RxN2#YXy$C85YEWqv zB>?Vhug;%TB%8EXMox1(Mt)*sD>eSyHL~}(d&${#y|j9_ONt$0ofkn~ypO@}lEIzr z8IDEjs^$kIL32B5Y?xhMZ7^=F)F3^$+J-yZWkcVqjYD>M5#)s$R9f?{TDid?pN^vNyV;LdiOKkDo8za5mNqBRQRC{^XE;|zQUlgFeeo8iuOgGS4I zPiAs?5fnMbK{aCb-5*iMocdC;@6xF=Saw=JcuZz{7{h~`j^47t~fznSXWes@SQujv)v_ECqwJCSeA;`T8v|#Na(jK za+!>SVp5b+aA!NHZAoL)&<$P$d0`w>BWB-i8`)Ve*s-lF70uyTc3KB{OlIF*b*PTs z_dpjff+EK_C_cEK2zRzqZkud0%{Eb%iq>}oorO|n;;2V&$$K?q^&6X;cjj0i1fzfr+aiBEnlPTJAh_zXS>uNA)?gN zv9jI^K3}7rF1grtErNQq`j{i?<(LMJM8m^mUD3RRdNf~QnpOsrXwWs49=Lm|B&au_ z7xfZM(|CmW3hrzlP1jsM*5{}b>z!6-Ow+kqJSIg+0C%?Uj9;ezo!?9fi39wvQ@;_-lL#Y1>mm1l)oz*4+g}y5!?&+KJND>@IFHqAVT`b zx4i|y35==jjyisEHw1zP-r0_<5u_K|T}FP}kn-YQSa0;shIxl2{*TQ@@^=MfFG+T$ zxzlIg9GRx;Xw)mY>uSWbwzEN_1>D(g-6X=OzbBjQyJW%0iLhU7hr*rhCVz}ECY4EK zBe<8nJ+OB3hwn2kmwBjTzIT5cV0)TMJd`)9y&?y&Ec1j1)-XBh`sc)cOv zt}Bc~`K_C=a%oZp&eby`Ptxt6QNLOaUo3m&t`K?3NiuS(1=Q;kE0;4ti%C!_d-RNte%}`;Bd1zGy_9GEj;Nm|2ug+HydMyc=0BEkkOd>> zguAXVjvHy)8>7__8-e+f7nX4P+Ng@YW5!x-ehY{IAh^Yop!m$^IF9%8^`Q4I89C*} z>kT8P^8w8`F6`NCq)JstVA*Mv!8FwZ>bchstgEX)Xh3j_CqXr0_4d0>jMIJ2$jB)# zq{$0Q=w3gtuId8e0)ksS35w5*JlWUjy3fa?HiFk1Mowobn)i?s7YouKCoHU@h1Mdj zXD9F;@|g>B^~a?q%RK|l8A#BKg9Pm#OpPgf7U>6)J`YC=jWr}_q~hn46YNFdUii>D z3-p$2Tgm&>)KW-LJM*02iUmrwVefSPcFTv7pa_wm`ayznGVg5HoZHIyd3&XfUbF&W z?b0f0Uk3|igR6<_E-~p?KDiqBY^^8O%=qfWHm9fWxckW8tGZ}&;+<1biUDyCh#Ej} ziznfJMt>aMP>A)ZoA7OW%E<{#lNatw5=9A-b@4OMI08goAhrU*EuMt?8GU1T)8a?@ z#cIM032g+@!w^S-KYT?hmyeA=n!K=tbhjSff&jt?h_{B1?LNLIF}c-tb=P=Y zotr@91$z%yx0k4_^Sm%kUKlyu34?1Kh@;}@C1P@gRx)ym7URhK^{INP-UL}%Dj{6m z0pSP4EFgGEJc&!jO|@U`aZoCZBVP5&B5C#bHUeq#;w3cO+y{t^KyZsEVLUjiz9@n- z_1KC5+S#Zeb%d*|jGUrHn!GS_IzQEnWATZVqIB-MGIEL*LNaoS7UP)PB%5efsfvt`N(lFm zf$#<5G7!8Zp2Ysm=|yNU4N8S^oX*umG<|eNMoxJlOb@L}wtl#gmw^J%#xA z!4EX*mkH43ADE#ootWH4AWdEvIh_iwD1{-8K1H{S8nH6U$SGQkMjRU%AA~L3ynb548!#7Q8y#gjO+ICAOAj@?IhiA;GC$jB*LjN`!A(&B%MlF9g}gl3x` z0HP2Oyd<7Ps`*94=JH9PR5-U6>DNkRi(Dlmr@W9RFJ3~k%`*WJ7YJ_gB&IdaD;n)e zXhnXr`8@Si?R#=nqiB&PFN~Z{v^V3p|7@@LaQCTP&na4rBSTh)7@qy1EG?DLtg9

m2&^ickOR9`Kb4GM4C2IRP86jl zN~UXl1p=$8V{_n$<3p*=6hBTx&55Vx!xE*udA0(9Rf|{Vz-!xoqnF{#oNgn82z;r(76G_DB~-D&8k|Z#?}{x1SX1UMh@%RUi3%zN7XWsYAYU9T&F5 z)Bdi5q}AygU9bfcNh5N>|NLfYt-W%8Xm-R?y31SQ#{&cct6XDq;oXC^Qk{1FIAP4I zvDbRkR~i?kD-c*UU|lZEj>(a(w^Z(^n`QAdxXfAl+#%E%e=DrAmUH3Pp(H84iyJ4_ zo`|Qr11zMIW__J7fmOTi^D#`Kr8XXlXJ~LKo<==wCtVo7?hq!hYWDYBnBR7S^fFrU zSNorFFFN|IrgWf{@U5^aVMHE8G^o_{$XEVW0r%r+4d>d@XrKKq*n$b;rg`vgj<>Yx zxZ*{jJf1!Zsn$4n_z477%{I@2PZoC4!FCEU@+GgfPyy<0G6ffmM$J^5C|$j-+Fx5P$gl$KpF{G!q=|9>N4xB~8eKJ`Ptk zpY|#%ju&4CEuNTxZ-rHOMOCR8HCa_BR|NnLa{P!5jSI+C%qiQ{jO@-~W3^j^$YgH4g7 z^ZqRYfmK^Fa$w1ryX1JVvepJi#na1^7ZCZ^5`n;~#4zsRt~??auPdHu@UPEr11k2TCLODYK{HpUAI-q5rLe|Nb^mI|t4@ zc}GU*DeK^_8evq`mOsh;Gg!hFJf1j)etI~KNQ{H#y(S0*R^e~R^8j9i(SrvTz;y2v zfxs#kzEbD!d`>p;Rhw5NZ5&Rkk`tiM_GAfLFoFMW{PdYw1g-mf7Ia>)Mj)_iq+bpg zy?H?Dcq_m8WYB6w!s(8rd2ofFC%^<&;Tgl@yXV8{P}5oP zw$m|zz^eK2d?prMCrb^K)%oV_FzUEI8f??fOW1-5JdgQVvVaJF7I{4U)BlV>U=_Ys z_&MQ%aC$Il3dDOq7YMAHx+e!NRGlU@KP&6`4Bmln$IbCjzNTEl7EItfnAgAh96`-L z`@o+$?*sy?$|`c8_p?&c>Z`Jz-&`L-S8wx&1Lai`wqOG90QuSQD-m?~Ja_1xp(kSk zs|L2o1>c_ANlFuCjS3kUNxLUexbUi`j4hbJ`%)fZc^pCS4sn8TpB4gvRpSQnlSqDR zNS9&CdhXUJn*M(0r%pWCPsZNTWMCc~{1jWbdI6=v(~HV*S~Sg{;ixWHX&k8X#7r=OCFdgX`EB9WV3ELWd zC!hR=($M5A*gF0j@fTQFf+lm&Wws>qJ3 ziodECW)A9ebLidbWdea!XEd3R_va(I*H0nb*NlT(lc&)uSBqtA!G!14Oen~DM;tCF zo?&sXAecOV8ZD8EWo*Gj^_eU%9QK9`8KDphgL}ZIo>S-skCOs{RdrrwLi5a*qYddN7<>5lFo(KFipGiGA&|A@;*9n;q878o*Z_g}2W#wzB_{Va@KX+L=#(HQhAo&_QzIJ|UR_IiEK!~f zEb}`;BhrN)TR<4LV8Y{LHn_#ECx(|5V$`WXFgwxO4TlW|d`^pf&yu&A*g_;;yA$G#6>*n$bC!8y<_Ih@d|3K2s9 z-b{W6ZBC662&{t8Y?w{QlaTrfakPIdq%C*?@gGJqY{A6p`8g0+-;cCkt2|BId1Mdq z!MEW4xA6jjRgcoLp>mNI89G8CR^J#4_Sq6lGMLP;1rxL&8z%O)CAVZ{-(E3fHssGM zgKx_wF>Jxa`@$T!($I{&TdNQyaW>F@auK+Fo+%JmWpXGRsuNq0kq!!R+&Bg5O;3T} z-ZL1sU}EsuY-ls72I+fDS#i$&^oA8Jav^EcY=$kEXn!IHyi5P8<8CU%-H<+TY4j9` ziwO}3tlDy$R|~y&S^Z#~LTqRl2e%9S!PIje!xl^g+|7Z)1;uJNH-%`p&mMm5w}+}r z;R1nGpUbo1-RL#yi7gZ&uKN@i;!^{%ox>TnV4~HVY)JUzt2THFoG5HP6Z+OxL9ZWS z3|lbq;zbU~?akGG?-inKwH*wNTtmJ&MGFL0)v3&e<4#vyY8_XI=so>l_OL5z6IC?Z z#_#9Za~zBO4*|uhu(vr-wE9Fr->V97byzGsD(Xf~Tn=a0f(bkxe-iGZM}4RJ(FGP` zWxVPa1ZKnd*XpW)NUDDFkx^s8%}I|O#ZZ1o+ifht4jxOAhessWr4sdye9Ie)OL00 zlTt#DI$xHt1rw7#@b!b&=?rcnZmKq2IR^j!E*J52$kB%H{Ouw8lVAz6*hp9Ob9JrH&omSS` zS3~O43nm71wWqN_U=?1kc&|pY`t*m|fDRjO%&-L$=Erk*r^j`~P*+)<&pxhCzg6nc z_NUDR0;}-q!{6PN)aSW_HL2SjGlnggnEjQPQ&2V4_|?E;ODqkk~&|R<$GU4X9l|-n00hz5;<&cxB)_%gznx;c{6S)<6h2DDA>1u(Xamq1_@UKx1q;Nk|fON#|i*v*S!3nsi)quqFDIXy`U?bBiJn?ht04vJa?-MmKf@MGgllr)>E&+fHulOGy*f3dLG6r4|9t@h zfmL{w;BT4k|jEK#F0Ac;WM3bXDhCEGO=>6}?S^a1L-ImpaS`TU};}rl$rm)xM zf8CD*Xrss`^psaq8Cx)cqg4Doj)M;^`_PCE%cTN=RoH9ux3AtlwBTAJn!kX`*n$Zh zbK;S^d>`6%OnrLi>QsTiD(toSS)9W@G?~<=GxkiCu>})2g2Yc$wHipx%WG5f@k<2) ztFYJRF@T-}>94ZdRQ6mdV+$s51c_IOEf`1-fBgfj*;;|XD(tm+b;_dyX+-fKs9n8A z#uiNAco5%(JNVMK(<)*4<6Q!QRoH8*RC@;d(q?Td!SUcO8Cx)cqdUAN#}!{1_w^C1 zy?#_6unK!^{ywV8myX{22*TDMm9YgAI3C2~yL0{Mk(C$WOzAa&z$)yuc{D21k1ic_ z5keMTld%O8Vx(wa!$H(&(_x5#a)H1q?6vtB-X4SK+eR^^l6bIL2n7}IR zwRvTuQ~vZ<%rwvqtjVwi6J~mO;JUjL>ENcUQR7<$P?O`1Fnyn{KwuU2+B}kK7C@`> z9O2t!ct1!*qLEej^ z?^@P?w_q$|3(n-gpTyry1Vz#vHZ@^R2FQ56Vil%&Mv84TT{rp`F)!^TV++nm!Jov} zL0-k<{F^(ZV70q21}5-4R;lXF=5gxDTgkdt<}$Wm0_V(d;%6lNwPqXXzRF7=unNy( zUdJmfnvQk|BY{_JWo*HOnD6s^a1?#sCzwc+2M7dK;d#tGLvl3zl--{(>3KXgSy850{ClzbqX+Mt^SQRv?XMRt$j^n~%Ei*BQQUL5=Yi+2CepR8%5zi; zUbBCA{X3e*Cq}5TYBtZNAptp(<(@%W#PC60E0`W632R=MFBW>h8{V>g+ zig>=ygr`=LL!+Z=tU5m{2Qn(}OM@JTYY`dAJbUMquVgq)MKFt3 zr)A^fX~(YDW7}kitag{zvcTI->_s;WQn#U~n#nYMx z$~1Q!EQBk^zl}2X_~ZMfFJuh=1^4m%l7uA>HJ5Ii60B0LDZlAlX-2&v|6ck3h${Y@ zubDbTqaH2(f_TPYn)fE>Sr&tbrf4oz9TDc0GM5tDe$+(X^#1o3{BJz|UagwrOJ$rr+a_bl^PBoPVnEoV`etATK-v@ zH*_4uGnB`|`8)bORl3sZ+%W=C+antuAF7nz*iWRG=Cv#Wn#9u(s}7QF{~Un`<=63KbeXj4=p>41zT)(Xr#YqbHJ5g-5C~V3 z9Qa$1FWr=bD5kl;n!z(`N>!R;E0P3a^!*&@{(Q02fcp|mt5ns6@ihHgh{ogK0D-{s z71Ml{EQqK4wS%NK>`L(89eWA!7i`1p$oT$r)qJS-CHQl%1n0tH_aV}P14F4e#pa1S0d`DrLpXaQIr|}0> znuEGe)L2zY_`c2mmgZdX04fsWc!toS7K;yz)8wo1495iiB>w(EBi@XZO-<@8C%NV?Z5Ry^ob+*mACuJG@X{D3Vs*U;(eZSH=g$L z)RQJpIbMcU*nfz`ii+=Gx|Uaav(J-_l2ah(i-CM>P;cSHz>Yd;u)R}5`OhO|zuPnM z6O7myz}~8IWo*G`3?45{gPHArO4&j7oY>53ZNBK=n>`%9SRk-UzjX$T>sMd?*-hEE zd*`;GZ)W#qB~us6*n)}ZH5pJex>}mGSsCN;6+7DfaCg>c&18YVs%^Xvmdhhud3k~| z#>>TabdioZYxH2Uj4hb>IVTJ5r@WVHe^s{OIq5cRjFT%%kW zqwtV7J*{KN4mNX@u>}*GerJR4h3C?y00&N(*9oGl_q>#|_BRm-th#lWXL3aTm2CPe z&ry!WW2x`gSMn6UrZTo*!r7VUGk89f#vf9~*wc3oJw9=({L}ZWgbAz);TerZBfm($ z4=Q6=f1XVp8WhWeKAe-V1rz4&`O08_2a% z=4Q$>=c8Ux^pT~X99D0Tge{mT*_OvUVxE^CXDDOT4vwdr)Jvquh6SaVz^XSqN8?hv zr&9gZ${4>##nToyGo)*E+LmDpCO+NDgAc!sN{#<2W2|*;K~MGW%`9If%2#isg8sq| za@7+bitiQkUg@x)Ya4k}k&?Omrl=7O%J5*`$C6}h!33VuJf?4GPba+Z&Z3?M2?SQ1 zGs=Ygqb=mVI?8(k-&1zf($SpV>NZZs7EItd&8vlu96%58So<%jr$AtpVPO_Lf6`PA zo2-nH%SXy2hRnp)QN|Wb;5p6Tj1CN<@oiqo&kxiU2&`K7I2%0IHI|#-P{uI)JeKyG z_*&jHx}Ja)T%tTBibV>)e@f~D!l=7CW#+>$4 zHQ_}%!-uTmY4|yR%wiLplXJZTrzJcALHtxC|bP7SMI#?jRspV zf#(8`=}(BIpD!B7ow{Ci!UR@1`R2g1gH7cJpUHUIrShS?Ke*+;RXqNy+<{jETswoG=GZ@$ zn)iPxf8X2o-6b2CpA@-^FuS1`nWKH4K^kSbG`Ysd#0;_X^Jg zFda;zhwHJ=D_RQ#R^fY-$Ch|)kyBB}Yrgww*inHl~g!dwN?&4}RJnMzm-(A>$sjS&h`fpvF|LzYw z`|v06y{LB-T|ah!yk>ulFa{>XnK;(jlC@js%(h)?s3GR2q} z^nKB9`1`Ug&$;6jqC>y(bHXjZS~98Ji8-YtYp?|qs^ogm;Mo}I?**lAMynDFwyvcM zTYsyI8WUJ$U)B=7eN2@MSAF1wrOKLleR5>9Pf@90L7%Ifi5&jTPx^ng4b`VDnNNLZ zR&aHL#w<@C(#A}Y-fZ|ITt~O?7EtPwEd9t-I)+@}#P)j5tbyl7;mWZ}xF*%+bSpMK z$C3RLy_B^4X#joyBuK%>9>IRI-z3+pr__T!g_WxtL5-(zQu4IBe2j4+Hf)t{Pu6zX zNP;bx*xv9P*`04C9m#sYiOtQd*`FglS(w*Gfxs&7zy@&QMU>P-|0X9Uo#kW9aA2n% zCJ}7G#3buawdIhqiWc*yh-wA!L%3tztl~==x%^U5+EP1_GY{7(KSW|e? zVzKnuu!0i>9j%$eaz}RLdJ}=bs&UWiL2AqK()1s%Iq}=Yiq%};#F}`i2);kCs;s^d zRI((g{RoAa5@X5M4sd1@LiejNf$t(r^Rt$JEtz+&6U!~MB-nz#l{iLTkrk`o)rtMR zbzhCI9MkvpYC%bPKdCC}J^xnDFRj_$+K#N)FdnCUG$nmwXE8I{o+ zwkA9zUte^k($wBC*8UMO8q}FaH?@Gr=_Q1n>B@I9HY0i6+9CGzo2@m$szd90z_UFE z$cdGvTEt&!&+e7m(ha_u0&%ml7nJ%xCZUoE#We2{Gs1?Ax!i*`Gnolp?sNvXWJVtJ zY(dKtyF$mg64~L}iY`uffs$*lN!WWM{;h5v6Y&zeScG6YP#uj2}#7oL*%)y5Rl zyyn1ITb5;NLo51r0Ib5-Argxl+Oc`3ENSbhYJtF4i)mghbgmWKGTxj{ewhULEIU5q zF8&_h6Rg;PI_9+Lq-4MrOspQkf7vcah|PB87wkIBnkBUAL0=7@FA!LT=K}8&R~$|| zv?cPU=GGuYeoeCAXVd%A>?Jek)M;6;+w_$bsG7#du;gc#%u^lYsw#63EQt8RPbjG3 zA4xk7&)`Hm^+1|1x&|w%xl$mo>eby$7-{xa8rx18w(7rTQCuuoB;{5 zo=L1)8RL{Eg{2E7u)_w|1OlrfTV{Y&jSte~f5+(g!yW3mOkn=;R{>ivv3Nx~c)M0e zjlU>k1RtkRuy+I-R`MCJ1rwG$CX-X^p>(cjmU88r2ZEFDaJFaK7r?5;W*Ja(?tRJm z@+>M6Eq&_JsJA`Y*yH5_fv+6XJVs_%kCqPY$zGo+2ds+y#>a@iD?KWiMMVPo45Yh# zKg)Ce>=X$63u2n@$bv&@d)qpio>Q~npl2F%h_tktQag^0_DzH1udOwkD`IJSS{h8P zHnXb8j^$VG=@&|SF4EDg;ysD5YI{x^%=q0^b3Rm?n6j34D|mNGQ+y>uAo@&5gKFD7 zn!+Wq6w@lzY}-(35pz;gwJsa5>PKN3>>ja2v)@>oD7_L&&-<826${e@0v4x%Yt33x zw^uO~(>(igZYZ@~VJbz}%LJ_2bUF>%bgCic#c2~K4u{gc{U=G*J5vRs?!GiwG0H+( z)G&r(n&%;N;-=>$DSAgLV3pU`G_d_@EF*wnkD+ z^V3e(L+QM3)zZ)A2~cBkIv796lAfDHP;cIO&&qF;WH&vGdf!ZkhflJlW6|M!mMr%R zqrO+(OWj(;09Jiyp8|7B> zr_D8xclMe9SVgX8!0EmxrO=OawFtwT{K^{}%4@4909FlZmt=@3&iQbO!z$Qx@0$PHpMjWSlA_;rY9TA3Hd{Kr`G?eCg)~Cn%x!Ys<}3CD>s~0 z9_lJjo9r$S*fU_7$Eg>D)6`XF@)E;-fK@8A;)n#zb^*vfrO8|#O}FW!z}3smZTxxt zzVm!8-+OVf?Awkw+UQ*h)QanE6}>Tz&yo}0qF~<)bE!{txS-nmDFv2Yx7X+`&?d}J znuBg)o}{xWS|E(-r@(=N0h%}IaTL=$%2_!G&i}5K=C6&QSe4o=1wvk|)bt&pO-wvG z4>pdgA=g|UMzJbQHv2$VeyH5@bTGxLu&$|K__~f%Z@xBBan%e? zu1b{aS%^f^fE2JbX(9Q!$5Kr5Z1riW;Bs`OyztRfidE__Jqt1 z%jL>3vnf_}8IlS=ZEU1<`P#&*z4mZ=`~f-S?lgh8yCenX&Ge8myTwpU^Elk$7?@!s z$(j)pc`eBQsd{Io!sUh|rKO9awTOzZHn4i}MR|nTB!TeWngU~QjgfxENArq||D$(7cvE4je_X>Kd;jHM0LANp2gZMLam#f#)~Amgm12L$Rv=tyC~?x$ByDU4#8$Cix7 zL1a>A=Ah?Hu`1(I8cg)qCpDWBszvx;=?*In^u$$1WtJ4HqK(tR$j@qeUF_Fb9Xt zKCJ7F#sX3Do&O%5x22DIb10^HKbAk1&@#fG&6`qJ*rj5XxI^w(9txut`?2(mwS~{Z zV~E7UBem(|HwKcf(Qsj9!7G5zp;QQ|>uA+=g0kW?*@ZwdC%(z4(A3sW zQ?oCxDk%_G?$xGg{&%I=`GEp~{W+$UOxfDBsr6my!J0t9hrhnYJwwz!&5ftAR3z%v zsYCPY+RHaa4HgLOoiWYxMfsJR*07hqEgdX)rmb0(X!`W zUxC2B7Sk$~AHVWmh0${OCttz8KJ1VNvsPP4btlJAkw{FeLmPI@mm8$^7YOWYF|AT1 z*R4YzxaP}i@Aen`tJBCdP_-B?We$j@A`$hF|E)$Im1}?KEfCmqVw(5JDPoGpkVAzbA}} zglQc;TBoHx>z&$3Ag~|AG=Cl(t4sCz=`*i)odnioc_4=z)MC2SQ5{EX_rPEBT*rn9(fIk;M#bcU3ru-$B;$q76)rXo7CG7W@)^x)%wP4t$I!8Perr ztpoyl98B}mfDOH92+xzba<`S>m+;fQNQ8NK(dupQCF6rF1Oj^;O!J;dJgeH^zz8+uyX|f!5ZL2jnpdv(_o6m`JIQG;n+bjiKi!MO(-U5FWIum7 zYL|gPV2^`oeyTCui{>Qy%fG4(1iyrz?nPoxD{s2qE?!=((H98paWKu_@bVgb?>5ED z&l@)o{1T15>OE`ic63st))6~)} z{8X4qAh5^5G>^lr_NE@)w#t7Ns|3G`7e@ zN^Q9UGZ_3lh9u;B$m=Jx5@dh8doIR9dd@l%*3GCHGqFMO>>Ur?G zT##{BAn-L|n)hiK7)EERcS~I-Edm^M!ZSmPONVir;-yrhNWO=wSH@$Os$0@X$HhW4 z3ac>9W8rJVXky?6$*^ubU=^MjV*D!gmlsVk_$UWFJ_`5>vERj!7oNA26F`@QJ(XA4 zZU?Nwu@jM);b_UOt#xM0%^Wn!+lA~c8zrUYZoWfTSfO7m=}&7)yU3lOX=#x(v8M8- zp=_ZQ>oCrVmADSqVAYlN-GH{-E%_%JX%Sm^<>A!v&J5B+1fsjQ1AOXpQhK_=kYZY; z`gq-f9sl9X+$udZST%WWPxzX8TDrKki5BtUpcS*d_hOM10Nz0_>{5mH4ShIfM$UgkzCSeu+CL*!Z%#PV6*|RO@tp&of znHfAU+bJ3RZl(3D=9b#95!DXNzpaIYRl~x%K;W`%(w%oLvF_H5HyTeg8mH1W48 zm|_Jf@kgbh`t9kNI^ALa(fv~9&$j$JT6)T=-kz-v-k>pZdHlGiYST zrsO{seh;&ju3%*FNOIn2OhuyIPaF2(oIU$JaGOBj8G~tlS~l2**|c|H&oU1P^XlD7 zfN|+}q;~xN5Q&-R`8(k#2UeE6P$2N#g=wBSpt5J{G?pyxT@P7#>%DsVIZ1izjen2% z?;XK!+#~5vQ{`>Ahp9cA-PVfTaqA@f9$1BG{yr++jvZfW#jN_93B<*S-q5o52kE(G zXNqZlDkasDt?c2rN((}} z2v>_giC2OiWW#Q4@5$^79S<+EFolWfo1{l_Q`&HZ2^{^jL5kkil-D@z02d#ulj<%u zD;-*;5St^NS;81g_TZGcKwy>G`4;fvTB`J_ zUOi4E^Q!WG7hD+g9j3t+OnjzI!Kh-P)Fhz}C)7K;G1J4qYVR)=2&^iuX8@y%qNGvR zbvUu-sWp4j)R7szX`;avOgx<07;2LUY4l5lP?^}UpVxb`zBPRX0;_N)mr8XY)RN_l zac0?z!ZbKb3+Jshsn;4ZgEOU-8*1}04ji>$lCBH$8WblGST)zFIn>BVluPseF>h&nC98hU#-~-9bU0+z{@gB;JJ%w9_4)8gJnK;VMZ%!3Hy>8 zD@@_1SApbyqzM(jRlP|TZ2e>xmT%Oj43CaK7t_4zP=F6g$G?>7uvU5403-`$i3uO%NKB4q}<7{X? z^PvV?FyYue7h3r9ioM3l7#n@Z(WiUgf`?(6gbA!_&T}1hl|LivD*AK6%yk?!eD@Ys zXQxTnf{C~MoL9N-eG>6RsnKW=?@lfHwxd(a9|#0i8S7?2?7X++#ztj~CE@P$qIWxb zP5+^UEtohrDGQzzJtdi2l`+;_gY_`p& z_me$jY{5kN4c^x>;3KKFQ^vTHvYBl0h@^ez3=;^f^0P~V(UqS`uan9wnb~L=-0VJ` z+HFmg_tr>;r-nKZ@!p62Sh^IxJ=2AY2mR^r8L6Rde}bVchf&FGjzD15p2Bo^`QjIu?5&J3(c=r8nioieC(e|y z1ru8!9d0_+f}f_!>6$O|O{ifC(1$nr2?SP!FVBRHXTFf58Oj*50!-<(YC`kwyUEys ziN!54VeX(BFyY@$8)aYJ>5&4yZ&o)K2&@8&Y|!-oK!!h1#+Z59jW&PXmX5C3O2!sU zJj~95gnK{945nPi(V}tm@aR`?Ij2m*1Xi^ho&&~*pOfx3%GssT-(%=;vnu%8>4t?$k>7jJl}ZF;(6m}e3v(nTu>zVcC5nd3a@jw zcpUxv>^1z*DH2v3OyC*Ht8&$wLnADAL!B%A1OltFH}KiM=qY)tugvx?Geha|Ntw{- zMRS3`D!iidF2@!T)Nw)-xDQ?_thJc%3*t4M?%X8b+AHTdT|8o`tK1a!{>pQ~pM_O; zXTW0_PtTG??V{=7Dc$Abf+TP=eM9CuyHfu-N#L>X1NofLhlX@Y0cZQyq^XB;{yb+! z5n;SG&fC{EGPYm>du@K=&^iycOqfgWd@>aXtcv7WlLJS*Al=3&W7yuxh30eS(jK;* zWNg6%UQ77Cy>S)PT|b%*JZK;gSoQuy2AtemPVUDkV>EjB5o#5WrU8!)WNg6%UK9CD zJl~OCfId`j_eTj6SXEKNtG`dZPbv$QF?>#TqzC)-q2*^kO4x!4yteZkNH=%dcTjtp zxa@#HV3ir~qSQ^kK`O2(V_12+Q(dq2bYR#430p9M_bB{iar1F>`^5L~;=vSwz^Xq{ zyw}#R^W;xW0cuQO)n&^(STjo|^Oh^SjDTOc zaQMtTT4`28E}W18Q#L#!jr?7N8Q$_j8sr~&LKaSN;l!c+xnOc_9(@^DL&g?7^YIMj zQJga$q2ix0biDO52@_b=xhD4mjUSMZ7-fuY8$QCE@-cMzjAs(IU;@uK{`|42Bkk6& zFKz592?SPs_>=`z(k=3Br835ywH;}qS6_N5K$5Tp6L^O5>aA_vsf%d`3Nk5 z@D46|m&w~QWsG_z?(|*T4)pu0bO~E9foCZ1uv#5NYvp_Zw|EDEz^cr{xiDCLim09_ zW4Nfs(YDh+!1+ph30p9M=No^o)-06D+!O0P&Cp;1s~QI9!J%Cma#B~#$9T{_ls@1) zmBtOzHQ0g)Jl}Y|@MCebf!P_dxql}$Ca|iI_wB2jevrIbrrfoUZO)SW+hb|F+8Sw! z;Zj(f^Mrizb)eU)li+ZZXJpz2Cu)$L0>4&0CXa_IRU!a}u^-0?%n) zhyH3Vbh;Hx3ul!I1Xi`-8A&cB56H&x${45D<^p{XOp|t&O4x!4Jf~HvCz&6?_0(8; z@?e2LVAUhbOt}B&A96Za8KXw%NAS2fmRdb3kgx?4_%7fvvPB(fRYNzrXLFK3U{xZo zr{AmS8rhwwjPcL>j`W9t8(p_QNx~LP;Jbi7tMTl-j>kICf!llp0;_)Tu5X`Sog>TF zDPv5j=}tFG9jIrrkAy9lz;^+E8-72CUJ0oLRij!0fmKVN^WUubF|zicGDgU=AZj|a z5-N7rl&}R8cusSls2fV%Omksigr5czSe2EZ2Uijfk+WBoG5R+Or5irv@Z8XW8f?J? zp40pc7N70EO3si_-`6gfz^dj4d9Rf2d&&KD<*vQFI~Q1L2(4H*L7KfI1@@XeBufIV zg&FSLG#y?z-y>p8Tb*VOy?eGP=5(qFo9<%uZ1+bBOSZUjh?RPA`nv z%S(Y96L`My%G`Vhu;J?& z;@V-U3nsAY?2|m$+ixc^N>FC|T2Ac!d4`;NztS1^JjZmx&pe2(C??^vm2Y)wd>no3 zSwX(*bS%RJ?y-((9xs6kvePGy-mbc$!Tq-J%*VaAdA;zUT$1AzPd|-H5D07ArLd;( zA!$==Niogii5F(mkp_Dp=f`LXKM&yN5AjKOr^!9?gN9OT`y?S=f}d;k0}|m@U@eHB zqdc)ZmbVhs*bsVRVYWbE6^@VZBkB>0_v~EYbsuA@pya>cRG&x6`Uf!a!l0NFJXU$KZ*PHHg`$W zGch#Z@q>idKD^dCTup)=eP58!56Ye)ofQ#XO$W z$A(`=OQ#|-d{-RpeJ)%eunPNNo>P>X3%OMxbbNY-2G43d9`@ioiqmi_$fhlpCP6p9;cLO!pf(h)w`JTF)9@Xp)q$_OB2?SORx5PWx8bfZ^Z8ELQu6WAZ~3Yfp_Xs>T}w4&`Ufxs#|ryPj=c#fP1RIa1V zeK(rS*N~O0tPHEL*A|Hjnm{_kT#vR2TB2FOa=}Y|l6)fnp~+Vh4fbkSg=rpD`yN8gHs*rOl#;{Pg8d-=Bwlm5?*&qs z7fgr#&6OR0E&+WXJ&0ZFFGOpxU*Y{f%FYmvbrIAhWwa1g!`=W#^mu$X>I|vdC5Be= z7y!Q4@I8oQ9K4f2^cj+78%J5EBw>e)XFJ}V^ZshzHk94ivR-06TfA=^x36UXl;Ge#h%|sJTE*bSz{VrEG=mq&#=n$b}Gbf3sdin(IyIf zd#Fw7)RwkXUyi_c5?Tt=h!+ z8H3dJlkUkz9+L&)!oC!kY&@CRyGK(@^XI4|6E*s4pUa6!6Bt(goXJo9whbobPolJl z`=f`b%gsN@&3Xq3M9%#b_?{X^I>kg$OsiA_7ERSSSNxGPe~)5V^)@RF%9kuA`)X?w zgYSTP^|e}T|MlSlQBo%rbn7LPQN@uI)BIFp*&9vMXARkKj{t^M)^@3|Fg%xhJsY7# zJe^;rK9W+OeNG<2u&T@9H2Bski$F8&F=mb0q4`N$vaH|U0`X=-DkLSXBlG_WrmJL-Y+Iv+A5u)K zR1Mnesq>F@V0EXsGpsT;NC)#@MP%!DZ6a*!=Q5Lv=IqWxwLq-7oC?Qd_K-`bLn)^D zdxOju&hA#`%yACyUWZg$`1$;~E_+DvWo=@V-;vTMAMII5b31_;ST_x(2b7XWTSF+O z`TN?SrDc^oV{5{5TZUCeq3Lk)M=82ER6)BSYNhQB3nS z>eG15(m5W?-@YBgs;1A<;p3ePWaz88T14GD9_q|AAGX`pNFdsuN&`K^Ys5)sF2yvj zy~ATleUJIF{jHlatnz4=0Zm`sAfIFAXc29%1gj-Bn7QB37l?Cp`Dt<BTRoy!Aj14IV3GP0Dcd`R zVwy+ps^&<~htFdhJ8zV+YEN7y?{fQv7|fZhMX1JFsW)~HWj-WFAo?!OfD2E)5F5+M z6w@lz=&U%6PH+S(93CcP)vNs(u)p>X;<;j?7SYSfP3pQTf;ok<|C2bM zn4m>$ja#Q478uPQj_D;37x-VdL&7f-`FlLYG|!>Gz$>BEh-GcM7|2*PoX5Y@2K^yx z$Bxq??)nvLei_HIf{jKpR!w!}T|8I)A@>?;6KxvXsxN$xWBvst5+)j%WJ1@dzhvF< zu@uuPRY|&!^xG_+Rdh{|uxdk27PS2KmxS~jqeaxa=jl>>Ii7t#)kYv5Kqf5z@t3UW zFot59_rVGtQ?}tpJlk&6UyW7ghGfFHtAEMJg`>2HfWX1h{H5`%4XajTRrf01ht>2i z+0|;K7V#u=pUbk?c-Eq5KEcF{>6uWk)?c#a^$3b-p1+%Pugqm!9BVbIf?(C~*i6V; z`I}e_8?Hs9Bs)q&3uBpXp$=eGO8;yqsQ5|d)EuToTzRn3rG0S>tF_EjAljv6Lcdi% zNz|1v0NtioNDMPh$lS)F4T%I+@Y83?E=GtN#B ziJf(7OVcjSX1xA}K;S;im{zI2=9*|;@0`QTM(+fy!m%Ea@aj|Svcq^f3s`tgAaEaM zOsiB`ACGH77EWQe9^VA4!f_^%sClfN%Y<7K*{`T40)aa>W17E-b6w$l+TM$W>}^eP zmt)+GSbS4`re9fU-P8S9a_=@2t8ko2B%U=Xb$-^j4{ONJb7BJbFUB-~^Yfl*hOP$I z;aoS0RT>@(b-7tW?pS*W*>t=kbgvSZAsJ50W`vbM;Qqy!=J|Et|$RpS@s!O11{$(Z+)io~~L?_Ew; zrpckzp#p*X7h{?~dF@EiT-iERwzZF>ScSV0i^SPAX_{e6rph`!BPmw>PR)a$5oPLC zy(tw5)9BAGu1y`}ORu5@0(T?EG+zx?9n!?U(3da7^NP@@n{oZ@Jh<0ct^RTss7U0N zel1H+(vibohy?CmjA@lhe|n+Ix+80(HxN&;3ilHh3ERV$HN_*LGJoc)yvNUPnAXf0jfZ{wN?6pO|tG{A}^U2MFm{qt) z^zE4i5!ScJDeD1(&*wgI)z;F8mBZN3dv$~{`n1l1{`c>bze{~6rd6to!-h#d&&Duv z@(bW^g;yL*^OIq>_m;hHJc_MvUPBlIuS=Nb?;v?GoeuP<=J>mKhAT9kt?|EVO=7Ii z+PP72M^2p3BCu-m#Z-v-zgkZ`!VFmBat|X%XRNnQ+l0 zl--y*Q6QS-r-FY=Q@K~xV2Ww}_H`N0;@A_yo=li7Vb#k%$uKpplYDlbHgT5sdDyuk zlno8pqQ-=A^HjKDY$}`87)CM8J6l(0Lt~3jHhSi2HCBz)EQP?Oo#dad0=0-Y{BPAQ zHiWebImL7J|M$7eQ&V6~eG|FEtdSJc{H=_CHhgUz!koSxBUt5XzZ6U&P32jmwTY7Z z>CoxsTsD8J6<}fvk6CYc(q7(hZ4AXU?=HV53%ujzvWeF%0ISCBN`lP;JIcxDw29CC z(&13iOcq%lBM`oE$&g*pRyH>qPcf}h4L8VwE+b~Lk3XUStJZf_Y1X&?EO3w zJs^O!L*5*WPgK5y;v+cm-JHRI&tA4I9b!rP{<2%44kI zKCDlNIusKVQj=h0XdU@^+H8txo`<|M9kNI82xn1kidDM3m%s)|SKd{uP1O0D0)yW7 zVQ0HE6Nn#OlVH}AKT=!Wc@)$9y#bGAR#)_49ZH%~tb)gjd1jtUcImE7)F@1Wq*_j_ zb2iW7L7)5QTq0~=@?P3KDuiNMr3zh@2G2RsrBg?WRc9A2hO~Q?QhA~_@pn)P@1Nd- z9Wu8Rh}ZKHp>o&*X<2$0#We5J&@~O>oO`gyQx+7f+V@xt&yycX8L~F9t!@e|Ol;4J zUpNbdRfj~F^X=UKSJ-(#RgtrOeCz@WDi#CaGAum))o7%-L)XtD`NLchIf3QT-NXP9M8!i&o57AChaEwB+7^75g5{v zv|7Iag)FzF%jdabXq9y<0qrbvP6_zakZ?IUAKf%JrGH5*1SCBeTclsmr{60x=;i5uGdEsGMpPjUml; zrF=?8*UMC(0qj&=XeIYgK*rlPE0+QdiQ|E6|46%Mq>h)jK-hUDqQnI$%JNMy7}87w zxgi;uhdv{fYI)BRiRkvWFlFuQSPW^V z|}0s7Nc_eH!><|6oyu?e-(+_7W0vh$3oJm(l~*Dy*{KRsi0RCe7C+Ay%ON$25+dy z&0d7u6l=0OZ!q5N!%p?gu_YOO)qN9VZ1JV2?(|4T?_6lrCvPFzbFl&G`nw@9@w+vC z+Mx%<3H@bAyl%M&y(HG8Tq7S0X{O7#XoEW~?M@qR_LQMje5Zw|;gtp?q^2P;BE%XW zDBqn%^ezyHjPDh@11G<`L+mJHEETCx~{P%ZSo8W^G@|~ z;7<3-VF+3UY+?OMh!uHn!R~|s{@A@_ z2kYS}72N39GRp;`XQhRxdgq$NrNJl+X|@A2u0GzEtfLKTvwK&8)h62osCBbCWMO|p z;%S?DIQqL2tyE{fK&)Wr2yd-xM*e6w8bg}h3-Goc?zqH>uCv{Tpw*>y$>`65>g11b zL!#{OR=CWa)^uRC^8&H0atccMRGEyk8;2pyYVG)X_()u98eJm~L93ib$;fh-30X4H zkXY$#h0E@?r{|A77Kkp37ogmiWysj#FbrvSM*K4?w%f^`?l@kEpjE@)<|7neo>&eD zHz4Heme}o6eLCQpgdy>^#RBAgzDTL=KM_Nky{pMq*!FmR+G@Cjp;b(e`KaOUPm0G8 zLtC;;r6#`(krGW7+QHho`?37d8#;> zO)((y8(89FLrthtLM?$9KPeeiICWLYQl?@^Gj-dqme?Mf&~)=!7+SSmG!G3oyP!7>(vp<@xi0SF@Qk!8w#U$F_3I=wY~KN; zl3A1ikf-laS4p`etueIvx+@78MXXo) z9x@~znbgIfrz#}YxPw3p?mr(5j89S;uZYHwX8Nnpx_D`nLi*{QFtqv@o`m{%Co7ZN z#~2VDu3NAjTbs$P25tiJz;ZtF{4`Q&bRz~snyr#GuZth(HblNF@p>AIAuUPs-dW&z&dDU#+5yqW5X2{qMEO zpte4^O8+!8=A$L?dCGTA2Avs-YlM6x9k(r$p;g~wi_y3*mL$BTArVj*fY0s!K>Q~? z5{US*X()7mEpp1+A48h$4R;!f59Jh-DN7#8(8`F-`|K>LOLmMgB;E`Tz`u_#BCC2> zB1jy+w-~L=G$+#|hha#wI=C?aKbiH8G+XYc009QKolKdKg5wsf5Rut=BsY%wHHYB#_{PEYJPl(mU zkpgk#>LT>;k1AwX>PQS}wof?GA6Hran5>^0jG)z(wW;X+k!qysKZeAjOh0U~=RTSH zJV79u4_<_ZvRhRTM}=ZYvl~6X`QZv5?~&>#0YR%4^-@ufEE8gL*O1ugPT1070vaqwI!+;+IObn})>OcRtv&RyLWn z@~A+JV^6*@^M-O@%p?qHcH&}7Uwr21A>#M^2!d930#neDXa6WZ)h8Pe)6#vg?%OWn zl%FRMq1_fDr+>~UpTnnMNV65JJRkf}*+oWl%0tkq5mWE@?YN*6HJWNb6n6K)G4jZf>x zkn4Hx1!9AJ3QF>vshG3-CLqmrpJjOC&D+Kh*TL@*w6ZKTiQ z=SloMz6r$Y*9*{-bRVTf%V-Q~cFIjK(+I!uBonTGMbK*J-elCT*>L4_jTi&sgM~Lc z{h}oy1In`T$A8m>{S~B{*4e=uzw6hMoNioJ==-K6B%``#9hGuSVJZ?f<-GB5`|4!t z%<=*Odr?SBQs;NeZ3B>AdU8nB(0Mv`Q^!tJ*>@pLAdbW=M5fYq zWga{69n!2MRv(Yg9PC48rfovd3f5qe=)rVi4G+1IQ)QP51gwvcW_s$Iqj0xpr^%3V zPH1FQ8ai9al#HA*95=B~Lyq055TkB^_)}IIifLMn%-S}Tz1;@36LFujE6Jq$^%1m! zeWFMdubzM>PF+TvmpBQ;(@kt0XL4myz5PfGX}0o{GXa--wv;r@bVSe!_K6~~(rE%- zGG`IlAKzObV(k{AV+YESj+H|(q$O$Epb2=U@gm}~!V^I&*e8la+biL0ZGJvEoe(Gx zyMA4S5*vR}9vmBkArU)O3N6o!Kf!vzN-o z;o~u+CF$AHaNId}Ht9cm8iH1^PZWuAayU+pi6*~|nk^8w*qunSV}Vk5A`C;C?Ooav zh8M4jC5wh7B4`EsM3Hdm6OOZYP9&e-%oT`Pxoo%n;XBIA1`{x(B?)Il;ZL*PDY@Rw z(A!UoP|W*xidEbg?9SGACVM|q4wW5;;X7ojeeGx9dA$pjoOBxmt>9Y_38P6faOYo7 zD^zJD5JRIEA=lOqlqnJ8F{IgDbQ@>j0dA+2)=g{>w1RIzB)YAff%9}1l`_lf3j}Pt zAT3D?Iz{1U%5%k{z(Hu?;JXru`;Q~>f#%PYx39%E5w>cOX15Pn&A^fQ-;|9F>I&rw zmVEfu*;y7hBXG0q`s7ekC!w^r*0KA@%YIctUxZ?j*x<?{_B_7wZTFZ0#V;e&a+(;G89$ z$@fjQgcdG~?fSG`Y(iGJ1Y(g`o*RMNm+4Mc85s)%Y=a@qPSUykO>UQ>XQxe%!*IoQ zNXks~_wz~0++J}8tFLis2W6+}2gz@B!!Wdh^Ty(g@I_-HuPwSnKAVIJM8fWwC~!lP z;yNzYV4k}Cf(LTZ+rLQnRiiMpf-~mOAJayeZk4yYJ|+#`1`34D<(cU0#1+biX)y+~ z=YNeWgXXULLR$6p$IzULzI|F=ShW-VqpF=i^iPyFSLJEcH>LVjh_hx#?DBM=ks&qlX;S0;ORgd40{zUY}P zKY7`kuH0S+Lo2v`3jImal`ltRr-;GS-pNED7T6}BmeEznQll_~)z=mY#d6uRUi8Ab zN*G$fbztaElFH@pm8Wm^qYc-T5eUEG2`F@UHDWw;oWUycpX0B}Z?+7lHd|gIXhk+8 zptZ&33juVnjjBdFzuX9!xs6>ykCb{YxVEn9ewqIU+}6o_RH6HrC>I>fv% z)L{J_&3qxxcsH6}wLXcUmC|$$D%a7HjIs$aAS&*9C?^z-W+xnzM^5$~X`meFFuNj}-e)2$c36v`RpbGdt9CY|(exk#;?=23 z^01JJ^sw1R1g)Uz0p?JWDs4X`SH3@$&b^W-5GOv*L1}FoklU^4J@M2@AQmi0 zLtL#wVfb5X~0cBJzM9|Piw{;k{|#n2CNyJctv6+1A8Y}B`T zpIql?EWPgKDiG4>xoD%MJ#jH+zm$Pmh@E9I`;8pYK97ZT-G<19)EUF2d$u1N%UdSi0PSGu7-QJQ6LfXWiE2vZAZSg8f2hb(s!+lK3$Hc zqrG-2(5i^dp09q_nB;i;VnFN}^p{-!UJPBDxKe>uP^ATPC`o>50@hGjJ*ua5V{kd~w|uJ=)5yLBXZ>=0qa9clu^b%R^+_t534>&VKDLj)ZFT#pcm z+*S8cyTQ2x`412XsBM5W+g(HMp&+MR@@vKbLC*kJVnpI_g$KxU$u+XNcQ1i}8VyJ@ zH)Gn^_I}Codg1EO(4zQ?y&o)Mb2AtV@)SPUjkRg zMB>%=2gvAgMf$0)i$Fll45Zm{GRNCDCUsupy!Ifi?_&D_u8ve$CMtrFv z5KvPFX-R5%`5_u&;YbHft19To;0m}%{L{SvJ=-bMyvT0|rVEvBkY;C1`sA}cl`<`g z{Vpiz;7Yzo)Tv*HJg;=4iG_Cs0&4sqElJfaA0aQ>?$r7DKZ33gDiTB@^-CctccL$C z_=*Yy)G9(+l4|5XLLF@T(Ztt>1$`n^R)|F4{l_SJ(qI~VBtsye<`U9uXPCYK)x9y8 z&d*sV=q#Z^L?piCJwfmO^rg${MG6GejzXF#0n-cFjHw^}r8r8^i$dLsNCX~!icHTA zrB1aS1Oh5rAbab0N+42~T-~ zro9+J>p!?5=y##=NF@60dX9cy97yYoG!qD@ForZ!e~x*I(i;a+*P69tXayBiBH^<6 z1-joikS4yUE@+*hwi?pxq>z!%(Eh?edh&A>K~D{pU?Q>7^9Aa1ZUo&IxLhD++ATy~ zgBlRGsQv~zvT6r(xNrNB6bb7n8QU$$CjosVfq)t&NVB~hHZqR9l25wsmjvAsTt5|wf9}e7 zcSI5StJy0A(}h|rNK4X_SavG+)gp4@%PRz};5x8K`1D5D!lo>3x8aUJK!q5j+5B$4 zjN`n^Qn$#vg7OTmXN!dH6vA>>Bf9tb8G(S>I7mwp>W}c4xL-2iN6ABEKKT zNk-ME*OvnV0X2S*mZZj)5xx*ojn=!9Dd_s3zCa`f-@*9wt6KEP*R=uxwTh5tJ&r%y z`Q=}mF1VH<=o6t%LL`bOy5sw=ENQlRqCh~+C8XI&Q_nE|9BM`VA0!GoOQ`n{32S2y zeBnDA^&RyU2&f%}G*eT}a>oU;Z0Pb%{(@c<>Q+P|e5(hJsM(O-so7K@prRGh?1aDi z9(dS>hSYUJGeP$X^*18%oQ?30H)%|>FBJ;fTBzlPG&?mS*8?BUZA{xbJ{9!4P)8&Z z*#({OJO?|v!X{oIpu!l^tmh2qgfq_D(c5;j1RXNeLy1K5=uX(;q#do%dy+s@__i43 zRIf*#e;Q<e>t}5()d+ITDt&N&Lx^0s&P7kY;-7ypg!()q2Ew{$)Wq(39OXeye!Al2dgC7Kv_W zN8_B|>XCZ=jtGRz)X^5Hvz1FNqA;W-XX?8+W?J>A-l@?^= z>0CiG;q;oFJbNHjx#tjxMWT7vvH0(P&LsQdeu02G5J;DxoPL(R^@FE9Ay@XNCK zs}VYUrKc-#uxN^*71UOX?<&;79eWOML|1vYMetq0_XF#SBz-twj;>XlOs9QZNMPPK zhWVl1^_MGYPM;90D@=uy<%OE}3a1wzr4bkdiIm7d(USMo$O{K4c0#@M!^o?+3nVSbA9hk?SQt8!(OL-$)V&Xl2%i?V@aNOAZ+IWVO6zW3ob-d*~B;j^_pGxqLHygLiS*FIb2A1sb7aMWJf=SW#0o zJoc&!S`uu8Zods>KDH{Sl((1TbWho7%`k@38nI`TgBlJ##tF|!l}UN40KIcoj6guE zjTY^Zvd;+l?&ZWIpVy>+_HVjN$4B6k8yl->ebj~Ej>-0@_?ohY+h=D{=R&x{-Y>aYiaKfp@Ch~9~(y!Y(Ng$w=n5)zeQ|OWI4|KNc zmLl_x=BjrkYdF4l#~f{bXNo?Bj=(1t)KdRGb5kJmF(-QxZEw2L)hu@-f-#UV9$E{f zEigrw5;+llA%vQ2pO%y7c3mK#)jIz==s+b?)M7;tBSsyMrFY7NyH;Y~Maxy;A%C3T z!W_-DH$ziT`Qw#gHPl=UJjAtwbBd#>ZM9Ulsg3Iq7y}9W{WZ|W9%jfiC4dp#-o(+n z^uB)NiM6?qfL2)xYM``%X6R<@Fh&@YQwl$$VJyp?Rx<8K4f;{Wcv$=X9>4KBs-C<| zR|b7JsLOGWqcBD*m7K_H=7c6D8lmB%H{M$P2JeeT3MsL^mfh{_a%hjfUsVVE=7<&A`l$+<=OS7`nvJjS zvvVw;KGN+O)eys&V}t9eJ`RNj3n{UkFN+4zveEbT?%Pa-7)Xfa%KG>Sb|2(RT^XO( z2*yAHmT9(+rAIWaQ|-DwEw>edr2&?9t%UM=!*m&JjWg%#3!QoHDH+DVG6qv(Hv&n4-B?eFQ5=vzt%YySf(iQn$kUHGwhOyLw*92g8(@mUH+Z zYMysj-{yrWoqEy=jr>>zjdt=DtRT(waO|5euV0|s&B_;y(Z2tls391p#P*CfVz+=V zzM-%A&{6OKiDUi^P}wUcsOJSfT8d?9A3b$j_nG;EF_6&8^ly%w@HR4|r~bI4AJTV_ zKtQWwPn)3AM~qR0gM7D>o9}Bfa@QkFlw8O>r+da)Y#0Lxt#dvG51xwVZ3*iK z<)$V5AcZlowW}1^S*?#HK3G49EbFQLpg=$?^WVFu{h+6MZ{IH8*Qm*f-*ju(yLw^w zi<%aH@3C@!wI94yFc{aW?y3I0Sq-5>$2zUzY3e(=m|-gB~kQ0C=|^@GBgO6%45SWEllh_-(bE@bU^vk0cT6 zT6lfGrTQy1`_l%-UTQxW_gXB8u!OQzebzVm`d-o1e9%=WyM?~q>Nnu+6-s zccgpt%d0xjV-@|>ez2aiw_pWnwI9U)=?5u{c{3?M^}*X+m=Y`Piw5C{jEt{z+~t0!srd?OF*f>7z2)tvz4MywvT_ zIiG#Xo`#_KH$E}-o}!_|OCO1B}t$6(5(tl$hdo z_#j;K&%65WFHEs}89%ijbkmI#tRSuSgZMxFAcis8_vhm)n3CEL;{Wu6LJTC{j2*1@ zgZ}GBvHEd_mE9UgZ|f8`hJ!JX&`LZ1UBaHj$PCxHa!Eg^?;wGIR&Q?gRr|s9Ih>fv z-qDiatGW>O&R`5Av^rSw8;A9S=s*3SKtL<8o+}wkQ5V(^K4C33jDdt!=Sx~2He{!~ zz2g6}tt+7VOH4`EkG@z751-C%l4XBy=~{(kcNxN-!;sKo{*8Fng1_DWkKi=7;`ECl zl}XJl{H|X^LW|LI0*S?J-u(Y3IL)m%-KDrJiEqqr)G_p-#b`N!gnjSv|AXK(x8ihi z-w(>UKl$%-Lmyg)^+ce>S5S->#oUZr2KpD2J=f4nIjFuBfbUQuye-NDJR-CS3 zepRWc@cW$&pF@k$asr8U`=|X6g45iJ(;+vg@~T#se<8FOEhmu3^kusfOXUg@Jj|^) zy?*X?B{iGhYial#T8x$xNYu`n@jnPob1P0a^G{V~?Z*E?Xfaw&Akp|JKc&DhSCHUg zZpCRwd9*U?6Q5f$B(xYUCy;17E$)91oaR=X&Ua|1cyHvlC>i?DVzitU(i_vldiSP&i<^vKu%&j;bcq}|O+5F#pXfaw&Ad%8~=D*|$ z5w;|IZ>!%fQ- zdv9(({T^zJmJ>+)^n3guc)Hr#W#3=^X}MBkxDP|(r{(Gg!PC`B2`k6)PwR&o!+jVM zKdm1>2%fH1+F5;+e_GGg81BQ6_-Q@=LGX07TFcrM`KRrb8pC}U5F542hq%yFUn?uGWgOc3%Ez|DnckABMzF`;Q+4Pgm;=Sbrt|v>#MsxDP|( zr~Tj$f~TwXYOLRtf7+j`G2DkC@zehN2f@?TdS^C%KtCOqs4?7!A@S33$q$03tBo?) zI0*f8e5J;4ABMzF$5%fHo~|}pV&ggV({Z92!+jVMKOHCjAb7gksE>_N5g()SHnY^| zRgK|33<*Ax{r?G`t~TCn=5K~dW(|Okc%CjFA!}A}w9E)nLJXekNYgDGaO>iy%8Z(= zQMu8lsuSMrT~W`UW5>)pa&bXZ z^^N|sFjJsHLrV*m4DMSiF_P43ha)Z9(-9B*l%e|2$`7}KwC0-;ryZ$ZU>i)nc2M80 z_HE%;8`KUX&vl>VRsH&~=csU_A9WjIh96rrQwi;EK<-1M7uM{ADkzo$Qb_Xl3N%f%f+)iw>OVhee{!94A`gNh_?(@(>7^6G-z~E5(2CiNSZC)If6< z>QLsTC-Srxb@1+L2>tfqk-XX63Qw#x=f~eA>1azOyZZPTY<8_0f>!(v*nxqM__aF&*C32umeXi^SRLd=umFara2Y&`PTxB60kmq-?trYbrV^-Ezy?3qGI2s#SwZl$$E@Q!45E@!jl zx@Nyj!+XM$h4u>GUn&y3F&Q>`3hvowr9i-&P$A838V|^HSzR252Q{26+z8EcrIkKd zD%refwI(|I?{RqIu0?uy>og~{{tD8P)c#U}e(m)*tZ!)|Lju-8NHeuaIZN05OvUlm zbfp_4cv!2ckY@e)yY1OYMiKaIXpHd9dAizn7T?vuXUEBF=R+iat&iH@*<=n-0?p#_ z^B$ehbvan+u_{je`={xN%GMNq!>S#d%Rk|_g!~@aM2LYztJfarXzMvjAM z?e~%Nmh}VzT5YNAfi9ihsC;F0mFaz!u@lTaTGGAwwbfG6bWD>1n-ozTYXZpt6s`7F-4S?y{4gJ;OKA`1-PJNL08T~S7aMG4=D z^&flN&`MJulg4J%@%#-K?V5X3Sy?4gwTj*Gm!f+-T@7orB;DKOOw&7FBCjo~l_E5& z@nhZ57Tf*G!~;<*SBsL{)A!@PlRlZ{aAqh%zxZBN4(*txrhAw^S8mmtD)?h%_j3mt zG2s!pTG^-+q2&tZmW@T1JJP;qjp${oXXvl5Zs>5QN6JX^DQdc9yvmT_W|IVe?A|4r zo#|}zja<%o>*8EA* z8@&_l*}ghmedcN@LbI9@q(j@Rixlhr{IoaIsSfn0l{HG&XAe5ih3oC;j!`So-9=95oz9qCat>8} z+zqTthBF;MFEN@wN$SpSK3$SyL!B3GDMe^jFtEMj7YOWxmSwY`yzZw~USAA|r z&>a)?3AHh0SY8^Q)gHn>t&ogw`6smPl+F_7*zO?O%-OiR|Y{&F_C| zDy)xU{ZL04>)R{aj>M_0Gn}E-!u&aEKIxw8+JVmqf6Q*J-|pk36tnxIU<{vg&d1bHA41KKd5)ZEQKzOKGz;j`Fm4F8K^Lx5{W} z-I#|pA0@NSmR?EO7p4tVR&OsMc)C0W5;%%X+jN0|Ry?e&Y)Dem zipzDqH?1W~>f};{X2t!Px%O7>Tk?MJLP|H?w)=7P!rixOje`BT^w5+v&lsV8kN?gs zO$zC)zq2Kd>I1yg8l@3DCz=%xYco^qOsAtr_oaUv-8W@fDMGX2xstId>D-yms>S9e z>u7LLu?A2v!L#2Byoy+KQPZnV2ornfiVu;Zui} zA~Y-R<8=6HW!Dov>KoN{wZ7JP6B@hEOC_`zm@W@%D}R#oOZ_xmqEeFv`}QwIXja_E z;lBG6zten_F}7%hew$?jI`>UCmC#~fx;(6{U^1ob+*Dn2+>9nvcP~X~R@{eq|5M5> z{|M$|k?}HpN_i(5RNhG?v>2E!4{Iy2Os9_*=r(=U(K07ml_E4N?&CtoTgt9qr!pVT zGZyPp-gKh}EgPtW76a4eVQod3&2kP((#<;Dn;Pw?TZ+)ExQ}(0pDSgRNz6xqM~Xgq zpBL4QH&F>K2Byoy+RC^jEzFy(D?h@I_Iy>Y6rovhAAYaDC|N7RnUC_mN&0w;VETMQ zp*r5xVqm&FtgY}%(rM=y-HFT)8oTRyDMGX2K8_wJPn^4tV?M54n5EzNEsXA-k);w^ z3{01YHKhXI^D|L*W$i>dw%v|Wgl5Hk_@)?Sfry7W#i!DKU@EQVA^vrpv>; zjFqevxi6@%OPV^KPVP-h5tCe2at^PhM?Nufgs)QB;)8%1aS4!5r z(DLd!Wl$hZ$1h6}nico4!R@{B%8#!b*giMc7qVI#$y!nv1JmVUUgt~J?zY)h(8*^8 z(c)iBOA(qCPbv6hzLL~~t6ow%R?@#=txsjE1}dS&z;t<-w_O!g4a=WFuUzHNUFg)A zjY<)k757p1?j>biI9I)R*}cmtVy){%U4}>T~)(@-h17l6rox1 zl)SSP<@2@9%*V6BYdJ>j8OprvrV?5VOqYjwUsAFrJm5{XtK?xryNCBEMQB#s$E|r= zmEFl6%tyOTxj7!}TeR5kr4m{UOqYjwpIEZCy{GM3*M^D_9ea96DMGX2KJu5PDBn`J z>gDCSbvesenR>#?7L0-E@-Xk)OV;S0I>))5nUzoW{Z*RKtawUw@F>NXowLABDOf%; zCy$LX8hj5^eP}T-T^{CRtrD$)UzJX-vn?{os>$J{2+fN7`0qGzcE7GUvl9}?MON2g N3{01YwK1wB{U1lCyHx-H literal 0 HcmV?d00001 diff --git a/khi_rs_description/meshes/RS030N_J3.stl b/khi_rs_description/meshes/RS030N_J3.stl new file mode 100644 index 0000000000000000000000000000000000000000..c3760b15dd8443955cf3fca6af59762aabd4fb55 GIT binary patch literal 430484 zcma&vby!r-`#=7nR8j?01W7?8l#pg;h7bfn8j&!u15`jlz*g)+#coCH7TBFp6ax{l z8w(p1yY+is@9X+qpL_PN-|Mf};$Cm6t|G)m*WQow-b|V#gwieRU`UkM(&U=cG%y4pI z-P6iz-c5?5-NML^TiU*R247YT+8<7e_8hN7XwAnX3iPayP8|4322+p5T~`DKh7<1- zB|f6Kd3ukc)!;%}^?MbDqTl*E3bi?5WJ8XM3~Ge5EcJQt$7Ql`n;5!dd>6K)DhqFv ztC10Ub}Vky0-Ri~LT3GS{@=fEyZ9YTBHDmAov)VJ1xHhuTDHZB4ZAlV+q(b6qS({V zfF~WS#Ytx)1)*8hm1*G(xZfQ_phoCnr9Q7tJcr+fMp2jw8sx+tom+?Lg6~)qB}epm zi_>=GW@aBj+z#x@eQHB@4_@E?Wd$i%I z16C4^V?l!0dZG*4Z+#W3=Y7FYBeWw|kB`?`PAZo7qA*pwwj2Aiw+^p<)1)M>_SfSM zr;d_sgZu>XbH5GS{pbnSFn*7rMkpyxho|ZuB1g*uC`|1;>d0naZ@>qyKUWgP<~qDf z^-W?k)LRfEsWm$k_!W=Rd5)n*sG^@HH~)T>tS*vKnDWeWU^XQm@Gsj2B~jE?lVAJ% zokU)67R3A#D^{4VPF|~OGuGj22WH-#HVXYB4xP-KUJ(l z>&$Hhk;pCBfeE@KCFU}Q8lfsbRUWL+qJc683R5K`y0Q@)w1~Igc_pEBK!rcpY(lS1 z?<5G@<7RC1r*>pw^(hQBLIcM9W`Eyxq|?4zP?#FEu?y?_NuRiMs#Fp-zkf3Ozg_9k z!)*m|y1Ww`?PW?n#vj2@BjmE|Gux7COY7a+Qp=(GXa6s8J(S+Vk47Ub;XjY{HK+t=)NA*H9H zzY-{#0gOzzsu#!w?Pg56~=Q$lFZ(=P~2?YU&e`hIaFhYwCw5{aX3v910w)Hj+F0Pwm7sgI!7D#(_%0a_S|P=9@%qr|uTS z;>tGceUK07zd9I0jnLEDbFA;)L~31kguv8nU1Rn_&y!s5FH;hKyicHGkY_Lw&=8mz*L8f4(w&9FS%ITK}i&?Il-(4kD#l+juC{$ zH!appGl0a~eV0Lv(B!3u*-noUv_7kVz*L(9hHT{rLI!y>Dv6@(y-auSSUU8As~{eg zwqzTfgUE>c+htHA#M4XJH^o?bqdt(p)Xb%A*~0DtWXXf2O2THuX13gH0(JlN7DM6S zqR#TS^&%Ustz}Rnq^McP7A8)hVFoP;Osx*oV~fjsl9ImPd_{5ododebkVzZ;M`0-L zFG0+8a46|E^XzaKV;gaYz`+0g z`;f}((kf$)rHn_-t&v4f?M7khl94|P9JT~c-*#I`oFy{u(djQ9yVzb3UOv9;$@)?} zv;AWXH9~#H`|^0p@7QmJ1BI!)DnEAM>UKPL+6^Ufd8RK<+KS17BesGlf9=B*9gg6$ za~m+!2$}W7e9^7m#Ob6pg{gt=e$1{-B{r1RD~UgrK0JKK2x9xeMi9C4e3(%I$4f@s z!%!pCa7L52bxEKdI^-+%ZMJ4bmfmD()*88!hAlJj^&<5d4)O`Z%~{D38L9ACDn}@w zS4&>-uOIC@GC%=SJ&nv*VKXK(995OX^7on??@FLGA@@C?Fh};RU91OrrY*f6fkxLTQ)|XbOILTpZpuZ*C)T~st4L!n@fYy$5=K1?>3L5r^B5J7EL-oP-m;8hn^)y0D>I(uA6xPR`z9d3uv6`MT?6k`ls+4(IF#7q}qs1eHe z)sZLahR_L3b_Ax>)a=<1I~TH}Sw~5f-0j4F`1(=xsC+>YJ|FNci^M3 z8ST*iDuJn~IX&2ed4^=)rZq}J@2DeRbT zLycma2uvOEac9fcX%p9=-AbbDkrU4eP^FV<)hQGPuVt*;v46Pv$6gFILdS2o@LVf3 zdNo9a!j!DYgYCMcM#^R%R}yn0U3ur`SEORIt{_G|!c5n<86WI>0z)mm4p%pBVc106 zqqQhZMIH8Jdy~Imuf!@P5j5A0r+mId>a*GjBEFokYhjPDd(bHiwX|l4@Zf8Q)|1oe z`V^+VRC=)v#n17@V;7YKn&-iL96dl@`*spUMJ8pn|1RT$XU}7(5&CQG#XmccipuE9|?w=mQQJ?r4e-v!9%srr42 zBhq{6&k;w`rRa!!(>@OtHr}2Dt(qrGR~r3qq4D{r>#T~~5v*PlwL5t`e>iBGWhq0Qs^D`4uk zl`DI7!HKwM`zeXqWj*-DbPqcCg_RtN?oPh!^!qO4eN>ze)CkS`;L3@~~{VgS!zezsJ6!n6bfwKlbcF4iw^r^nOARZkhEPt0J$qODQhZ>>6Y2kclbbFe9LW9B7i2*WZ zamb3?{c~DLe1A^(Mvt!4{o-Q<6!7m4HA2I^DTSXq z|A#bBJgb1Im|4Bph|KonQ1p5w;bb_7WA$(3yH^WAG%bu^pM$i>hM^;Tp+?BA?;!r{ z{TEX4sht9*(jJAfd#w!!W(`VW)XgE>O6x6|s8Jz<;!gJ{mR8z=93Gk?gBqbzI;s3- zpC+;>a)S(}4ju_(FFUp-KW{Bi5{3VUayffUWAUt}=d-lPKjQ~V;#lQye)#!yvgPo1L9{81Va}ny@PfMtLoKcJ-wx*w zr(P%eX&*66y%`e0v^_P*>v{tv@z!J{pTFTOX(*l4!0qz>!vpQ|MH?Ha>FuZ$*c&o>KV-Lp70Vpj#`{bpdO5%PaIhI>yM zOS~U!Brw&yGMX)ZRE59PEKw4pwZ?LzCm|&IL75=dw2EgHMh9@zr6LTqG=GGQ<%!RF zlc%ps2~3T=9L=gVk7MuME0x5kh} znMC$KNMLGQs~C1mqZHSVSf?ZmkBsFPhQGv}x>g8cWY2hZVeAULxN0ee8lm&=#`3+H zP1v^V1c9l)E-~!i_Y!<7b(4~q{%tIO@N+&sIgbhAN^CsK>0E?YK3|TZmd@gsj^p|I zi*dmY1%at4VKL0AX)gXyu|-K-X+4g2-yJ0LvOgsVho|xX`%XT3`BDruLRS`!<<07c ze3u?SO<>CLN7VmB-}qfhV%L&rBHKM{7f!nn zfuTmoH7cLq-p6plf;I%EPMamOghQLKqmiqU7$Y6y+q}Ct_kBx2)ND#*XVVVinFWCu zYJ~R2=JP+P(pi*PbplhFM#-!wa3^-TY^x+TNx!RwWPD^BqjZfjAu3a$H z(%IVZe17DG4)LE@gJG)vQxeM=egx}2)KL=lo$|TcU=vdHcaI=u_mDmxJ!`PbkJcD! zggSUj@Ag+F(zUux7^Zkt5^HB8$J0(U%S563W-`B1>Oh9(W(dOURzD_haSeC>&?JKz zp{_0RxmAV(Y4-1jVajS^5_2s+jqeOSr6k;oC-XsdK4c5}D}%x$q93#JxrfJYKP-b9 zp?_tQ`Ml@eM04$V8BFc@mdIu-s=?fNfsz=aIhjx16+$!*+gCu*Wnlt)ar_B(b{-{z z8X-61$sGIiBG10wu7oMo&_wAQOFe#m#!5-l`R4KA2JysgN*e_f#dG_zg5+0t?~7Bu zP$Og$oX3p@#u99AqkyR;DgD@=6*sYIVrwNa-87f4dpeM;oLwx4-aheckJ@{z>Od=@ zmj32ex%{!u0J5(CIt5Hc*e9@aL+;^rzp9l)*X7wXik9Vt2o2HaYAYHf$l6 zLoJQ%l9(DYp3GTg$zW>chFC`XKEbEE)+h(U!SUqrU28#HtB+>84V&<`t}o!${IBH3u3!;47a_@aP5Ll7;0&Rlf?cP z+hn(62FPH_sZ$EO)@eTe-1(186zAVh;dxi5$Tr-ZCWwD;lG(;Ht8k-5I}9~K7Sby( z9&=CTq?70iQ%f~c*yr`j@QEW2Wuh4LbqbH2J6*Qpew`r9pCz;1-`C+M54ADW2py50 zRVSBYvacg=`@mG#tz?!>w%`S&NJ;FvIfZ9DQ^DD9r^{jLY+W*2v1|=iJAYUv9^;Ah zyV7ENWM{tn38Dp0W-)Vi;&m6E%b=FlSEW<9Y(W?Nm#HY=BTyJDPi96VH{xsOm&y>j zd1(rdF?uQc@b$hNrbdiTW|N;Ez`8y5$VB0^rjW0geFe{+St^49j^|J#^tIy@uCa0( z)^BxE81>Fx2fF2xF%Dpe%0;Y&;LU)8U^qG-5M$ZxH2!&(#e31WMBBI_P_3U|)Z^@SRt@%sz; z`0HJ8#u0#J-Uw|O?K8|DjXDyDYxG9HP`i^rTk6)42f)DI^Gnm@@I*!>bK8`cny;2g3CKvLd z+Sg^r>1_oRv(Ch^uYIa;WA!UJ)CfJPdB&!s?Zn!bQ)vqw6IR+`F8;JllZ4+eW;=VX z!go7rl6pHUmPQxifCm}`p|`e8tTFdCj-EZ3!j$bbOV)4RMttytx{}!E+{lWpwaM@q zLj+NjXUxtF*p3IdwjxkV*K6(Gu(*}}WVQ1E3R8oAcVtB=hq3ni7E0po)u+tpQ4f+< zH;BU2r$9?Kd*4A^HA+oMw5@x}c3sRSv*js*s7UU}=DD51TcR`w)ChIo*2vb~%_YAE zrcjvrRbasiOHSiC!756kUEKqgm$#DiGfNW0{?$e-`#~Lc=%+@YM#yRU6E?a1MpD#2 zfx=Yr40CqQ?FNo8_=82^=XQr39(jN?59uq28OJ-Y_7V5-mli4nYH24&-9zSUc!8*P zj-)WPBjD1Rfj{lARsw8|?-e7vGo|Ap; zdJDqGq#eV>zwl?%&lqZi9JXI!BNja+hrWeTnEH6M6RYq06Px~RQW7oqTx5ffsL{(g z0fLC>ZNLhqv>@)@uQAlp^^Xagne`1}f zSn|ErWM0k<47GGlCaH?Oi?XAYYiuY?742%xTGkp8eeIh{V&at(Ecw1U{S)OPh>0O> z*^p~`q{-|dh8iK+zj3ViYAUU1I!`*jM(kFV7b(z~hIKyvR%FkR5tW)@IOCTlTdnRz z68dCFuY7aobhbcyC{0*)j==Sa zl*ExXI&Aox9Qx+IzaTyzf2tT~9!g&3?2|z)jiQtFSzne%i*wo%m>P4eL7_IeH`!Q_ zt|XrJ|E;jo&Z9B%9t5Uj$3H1LFAXIF8+t2=w6Bj8>z?J)O`9HJDBvzus1f>B+@MIl znNMR}UtpMmdtgP8+)|yl55I}W?oXs}E`oCg+}$djVTo1a#hdDJvx~H&3d~Dzf2t_l z!qxcBLoQ^2Pl6!e3;;Dko2*s2N!M=VT-SaSrr`cmQMekZ@@qdQk%6VLf`H>W)Y6%| z>4-1;Jf3{iji)dL_os>?FCB5Op!MXodZZxWcn&o}9xs2hncG(r>sL_}rr`cmQFPe% zn>qbf5a)rRf`H>W)CisY`;FahEGMOB!YE9^{i&jOwDcQ$74wK_{Phlyb zrr`cmQ7qZ?l5H*2r!&uX7X%#Vp_XQY&yU!K@HRBNbq`@|hx=1S(dq0%w)>+cjo;f@ z5OBVNTH50!zs2s}Gp9RJx(ag?+@C56b=gf8U+hH9#~BF%&Z1Bw6jNWvG>W^?GB;CU zu7&$kMdALgmL*Bo&+W8z1@Y}sTUNib3#m}sjiE+Jr=XgJZuh2})b%M$!QG~!SYdUV zRm2C=qAn_e2pZIyJ^$@UYWuClP$QIkzLJ@p=t}9JFlnvWXU<&R}6~&pU3s`>XIO^VisvzKu47K#WVzXJk z%{ZF*Z7zW+xIa}CEoMz+Cr(VHX~%mB0?x=#Bji_-#S$_n(sgM`1g79_Q&BwZGlI2x zF^Tp|(GdikEuoga2|rF@Mb{_M`)$n#Ou^lzqUfR5hv}*2(S5a>FcffhhFV&~l?JjI zo$_ew52u7W7P#9~6pdFr*y4keDSvJ%2)|aJ70u1P$@O8Ta;T;8s*?pDTvdg81O`i= z!T+l(c~c-Zr0D+G7e+cdgvmv>P?}ZN^h9iv1f+`JzR8 zNKju7LBP5as1cg@#DsTt-$i2Acu|;IHJ}IU6@3?<-|+y8;@W-_epI()dU1)b%gM`22Bqa!iX|6UO z#2xABM}G+vu&xAZsV1(f6@RhUfet#QMq%pqcY79KXiAnCug0QC+}n~Li1DON3tti_ zU|k8+2$}v>=aJbSRHgR^0#mP@?O0h*XJQ#X4~wE#nHuk+d_qnQ-gzSS+Is38P_fgi(*vcUsm%pln$yoAqZGk0yRRGH-9jdj8JNsdWyhQ z2R9q064srpydH~1aYOqnoAV%=Hs)*;1gtB8T3RQ1eqf~=qUq!}I|)o({AtDFTlXMU z$OVgH`^6@f_@y5u17`^W)|EhwP>t71*5+A18ozuYfvJR57A!2xlVqOL!J>%m{FJ@# zI*|S`j28r~D}h=%BYdlYEeae+XFMB9VCqIoGdA_R53xQ_ClkfMXSdme6+`LEZk+@H zt3;rd=8xj*Ec4}1+HsKsfvGAJ6BbDc$rzt26Gh_TODxuT6n$TN5<>y2M4(1!@bL>Q zZRaSu<>dnmQ$fEvFxf3X@@mUgUr|JBRUnKm~r&br=A$5 zHtmpVekuaUa+QOXqHs((!St@B(N%LxE1}TYr^nFmo@8&k5pt-dV~ld*KToQYvOG_r z#ssbgU?qvP2Qt`=pJ{l6^_KS#Rse8D7KN6#6_3002G6_^CMTLPZoGZJqf0`Ljq`Vs}Bn*%E4mjy>$ka~-mX z%^(j7Q?QOj6m|8Eyz7gFWO^$nLBRdgP)nb|GJD?5U@K`o!%+}$euWyLLnZe7+=DG- z(Pl>qQ*fWQD4bL6`E<9FWVfY_AmIE8HA3S?b>)-&6r|v{Erlt#-&_>Mc3ruL`$IA_ z-&7EAeuY}P!u!L9UmI|rWK>&Fn1cJ}Me%u^4R74^o1D67CIF1$E|M^?njr zwh@IXxc^@iJEawJYIhylGeBDqaDIgvA@^7d9??#l?y_o4VG7nUh+@t@bAEBX5mg(h zA_zFYLM{ExQ_T5=TqD}zn+k;~SdSr!8PkmU)>YPY<@gT-3OK()jgaGqw*2c4O1*FH zCa@+3)~<*%j;g0V-~Nx%MRjEarr_Ks3a9x7eB@*=Ix(tR5O79@8leN8Dt!EmB)Y&@ zoxm|1jx23SDS5tejvQ)fNBj<7UNUU~*%B|-f57TIaV#0(;=^Mn&mpf(tSC&u zQB4$)jv;)2>1#acQ6~zk7xO@k;&{_wcCv91erQ@NeIMK~rx!oJp%H((VoG63_f8O- zb$bhb*6jio#njwh+`5lH2~+7P2>1-4mMRV>1oL+Jm;`Sz7G6i(s33ND*D*ZZ=L}X7 z3BkO>l38SRnt>o-r47{5`K#YOxlPUtQhlVIP+fDfz9++eHQ3cvfkm<6aZg@1W;^-X zT~`pWVhC!4mTd^+zdCOvD~nqTRYJP5o-A+v9c<9y7#2nJh(K&l=;=xiwAAMHMn2G>tQy;}V% zfA(yLD$yNRf<0anHPV5QlGXoJ1bNJx`b0Ub-X@FwNJ;Q&{*QhuVtE1 z6XR`yfEA8VOILW$xbr538J&N(OsHy%+=bbwypF`|YzP*`hZb)9yOtfbeKT7Suu>Ch z>DolNE6*nOHzBv{}OCx9AXN)V=S{*3}SaAw9LTx8@=MznO z&}6j~p~|#ro;RC6%7*NJ)F=~$?+FKfc9su~xTh-!SO*KWv;(`VJzqJ%ms)P`C{)Wn z{q4b2yV#Q#t7gkY(cjaS&%WqK`i1plqL`rG znZFMUqVEPU8T`4hE*WZRAHZiz{@Eay&dF#gR4>D-Hc>=OHsh@ygwW&;nhN-HVSP2! z(kdg*l#f<~QY*7+p}HH^^NHf8jS27bwl~dlpCeRytCZQX^TXZAoVcxWs1d4f1CKtJEUwK-6 zV?UEczUKvTcU&))5%de|v|OY#?#5p2&36=kCd>O*5txEA06d=b`Ir>O=lI?y>Yn!m z@!T|o{Zx5}57(9`%^x<)!nuFk15*C_27xI!lfmOj=a7GdbJ@sha{0__LD(J-Vbc;G z;T}DmY>kXGifB z>sOMyzy1-Jf-59Z;EhpSb96fKsA@@}(6H*wW~v;*4fBpGt*`udM)ThtGssn@L17B6 z^x*Lj(&f?o#%M>fnu7(Vcp6Un%vMPUlASmE&y%2^S^ z@4UH;|M;{PM8xji>`%l(tow>7t#|bdV|oAA*KyepJqlBBE15s5N+fUhz7qs|$3TrxQ^#b!e_3CW+wr6DPTZ;2KD{q|&fTN>u%v? zOIkm^8y_UOzV*U*rPdJ6Tp}Cszdj4GC`j9We9?)sByhSy5O55J8ll^f3H(+=HR)b+ zN*H$|`h~MMYn!o4+Zk9ChVs6A-nDxqc-U@1z_|o!gi5Z)bMJ%q$m%u+g!$vy$}l$a z(O*2QVH6g{w7+ruSMCQgaM21uz&R0W=}eJH91me1$c+wbgn4l8uHNjrLkohghhk9_ z{EFejkEzlN-}3|k=XR*2-ME%9yih}p_PRYyn9rSNg)*JdIwZ!k3l_!r?NL1boHqSY z94rX9MuA$oUVAN4`kU*}?B)nzUDClUgiSTnCwSXmnJ7Lt_2C5%4XBg1o*>}L32Nzc zZq%rT_B1KJDgt7{{J*|~Nd$aa<8GEuCm>diMd8Pl@DZNeH3t{I_5XzkxnuCddE z-qATCtP_Khd$QMwCS)43mWg8L)n2^k1#|k4YY76bWTBS!WlWaNu$Y@uANRE~n7VMv zpPfeLWannJN>S+b2;wfJGu?3es1FpdO9j*j>01Tzm#H@Nm#(z}reN<3QS9Cu$Q32l z^vjfBp(h9I2O)~<+X?@gZAWcJ>=gv;8UeL*{>mbXd#V{yw~h-HuyX_KupkPv9Z_7~ z-hldbU9EsA_)J9M-Y$;E4{S}hk6%;?1?;c@HA1ge#PP(ndUUD2jU1-n-#`@2i3xoD zeoZ=kT`GnGc36NKA+Ndw{04m4bjB7NABb$Zs%zy6F_rja*J(3eFj#I9N59 zXZr3VD-CxF0(Mw{TKewnIfRGY-$%mUY$Y%S=RQ$fojZi{Uu((Ufky-ZJ1jsg9RsCu z?Z$QFgx5g=Q*aI!#V?;!?)Sckc>LyqfE^Z~MrhK3RQ{{uJd*H9PGAbIMMN?7b}G;8 zKbm}eazPNV!vfS&{b0yY-q3Lzxny*Xz!Y3liK1Kop*(V_j2w@;CJ5MJ0cvRtcXue4 zc~i2lxSqfiTpNmF*4v>xsfD7Kv!MO<)SHaYfNKX&8T+ zwG}Tq`A`tB!vfR@bzVJ;PY>UT*Dh`#Fa_7@qFB3Y7>{YIk1ewv3j+3MfEuBYF&TVs zo3Ysb^je_@1ng2V_DTX99Wfi9+&feHHWAV@5U~3R z)CfgBn#hOt??U41=LsE8zLzAh^)83-D6KJA6a&vpL=kbmq7uurZ4+ z;i&c$i(==s3H;xJxn$)FKS99mKu}A2CTb?|>vN@@xLf^&jzD!!`m%7N+gPi&Ef$5R z{{$XUw2B-kHWvi!as;)sixp4c{pYVDf$z+P&PIdB_hr#mPw?6nI#?8^3dZx*Gq#Zh zS)VcdxkB$HpruOI$>aItIortVYoCRlPV4I8*@x+G@Ys)cW$<`Xho+o#o-y8iU$ z5U}eM)KYh`taQG4+yT;S-4>zK)T|G2Y-rohSgmfAOcbe>X*{lVCAs*%jUZqzEU2ZG zzHu7&wXY<({SAbUStl;Vva36O;Vs+DWTG%1K9;8pJ43!bm&xJJg+0BXmUd<)j^#Dm z&k#1)UJg^qi81V4YZcNiyVzS4d7Ve|y)$ab@$FNE?qaZ;8Po`+=#J*idY8!2mAOI( zvsYuH*u`sVD$Vz3`PT6A2u{;aCfM z@<=uA896-noCnTbFpyKx{^{T(Y_bmj)4-f<1CX zA+yZkW*@te8NnWcfMYGx2qik?@YkcIJ)2+L2u#7QI-;2NFPr=J2_Sbjbru91YoV6* zGw9~0A^TX=>h@+8?AmCUFH9{NjXLCclek5_UCV?r~RYw%Z z(zE#soJLj}JrKrlIMzZfog$vxaF&Pq_MN5AmCUFwNyXYa}wXTcpe%2vmJ&h*ds?2 z)GmuJ8L^z0Z@2J-0*_!4RtiaABQpetVg*>ci2R@hC6T=kjk|heO7gDDX z)pgkHVqZbPzAsQqeTt-GwDBv(-Z42CreL=(QM`Rp$XA-p!x1}Y2m_c+rMm4p>9_kV1*fjqieUAYlZx} zmOt*bzDy9XpAgj2-8`xb`H?Fw`1p~-7^YwsIZ>=VU&x(_4z}7;AqdzP32KB6vO;dV zy zDcD;^6n94C@-{v7$+Uy6f`EOsphl>7VlF4eZHQ^KJA*0MDMl32Z1cElo*r?WU@eFX zrLnB+%xye;fYeV0^shl^>&qrKGx(wGe)tZ?=m z*^IQof`BP_w=3zabI=qn?=n&mWE6%kNj<^-yAM|A25qswBS8}3ThUza;f{p z4vlgjn1Xd0;dMFEdf{m5DcoZOJ`-4XiO_RvJH93JW2LdJpCI6Cf?B%o(y*tj zzwa=5|L0F(kFe)RLzXZ#fJ9H6EQkAr5$b#RJTp%nL+{ysk;4?+lPtdS)Q>+|)`0=^ zPGYJ8?l*=%SG=3YJ{rP3eLV1CLvsr6q5}5|!+i(ReKV}v@ii8aG|hN}uqzDSJp}F$ zL#WIMx_)h0jF%CS25c62IJ-EpM8& zKoGFAF4WRKvU8((UGY)!d7O{1hJ()?uIHqVr0d3WtMmorOIVc9KM|&2FGYmfJ;~%& zGyO?{U#c)t!xS8~rB1icvUt_3Gx*ouSxo2;2F7zyc;rfb2S*v>#{O{%*Z~jrqZ2#I z{XKn=&0%VE*O&mI!v^fo1p8=6HCQ7~u^$cwH1x7Jh24x`3TlL|4m-mlR~ypiN1j55 z4X9za4QcmI|GRtfKZDc;wzW?FZStj&pPD^Cimv2S3lxW01rS_n7;spXz zu>MCBM|to#>cDu$%Ta}imOv<6#w7Mm>jAF!%@* zTf1CTtZUzsSl;a^iH5f(<%dxQ^=i9W5HPjY+Zj(?6HJV&yGUZr-?iSQ@e^sf_I3sz zfnvbLi;4-IgURA*M@gLDu)Ey!_$0b|Ymp#eYPq8`R+|w*wz_FcVuu|0Y(JGnhYnfH z;3H5Jj;mD!z3D}ok_{!1vstG?QJ+g~%LfVqrY71rCW+~T!zz-)@})|PZi0X*6Dw!DG&GEKvzJ~2I`*T$$IyB* ztyvt*;3H7zm0nU@EA36HCss?M{ev;(i#rt1qc1uN0;YD+Iz{jGVPu%ga!DNBu+Tfm zrjUNo`>KG)fT@=j&UlwiI2m7-B#F}}hB3OyCNL=Z4lCLKeuBb5jVyw&EH589hej}}Z51WfgHcg9QXdXXPK=92KT*z03fm_t9>O(O6SD17ei zkazywicQk%WOqrdZu7PLx%)&qxq7=GVCvBPGWmCdo<#dwPf564cJQf?r_;vehXnys z_eMD5cgX={>W#jVSgV~`@v(9o^?9ct@DV6v9tY(6n*GR+K|}u&M|^x9Ul~n5zrH94 zn0mg#8E;Ob#HV(GB$C>;sdzSFB;7XqCV`JY;qc(7+|G@VP@{ZF6j?j@919&r8;(8| z1Wb9|a>mK_G7_&hTN3y4KbEKWO{Kac-Vpc*6dzLL^0QvPq;$z#NnB;EeR@k>Bk~%5 z3Ie7IoL%tHrC#La-DQ%vqPea-zqUVJQ1*|&N1!O1e_Gx`#f!YCD3-*z14q4&P3T8$ zkF=stz*NHy7wo^ojf@H0D2X`J+ZEnJ;%QBqu5|MG{~m$jPW=`6%gruC<>O9C+-=tO zv2lo|vr7yF0aHJzE3O*jOlHvClIY@;Q=ui@hd0&OjKW8tc%{+V!(ySAv6g~ol>4Hb{tQYpAhfTR8vO0(P#Ca2H9^)VgnEGDkhTq)kOcXn%bB?Gi z&$L{{6w^!d9VvVSieA^>%S)vzTz!l#NTSo5%U;`qU1{|RPeH)c>96kCbekC&c=D;3#N75zi zz9gQ$?p!hAtv$WJoKW}(6vtYsDGv2CA`RCcNW!?X)I0L78NF~aL=Z4_F4-GDC^8^= z0na4id#kKVP#7f$m^wYn7k}HO zONuxCC;r;MDnFf+PZchXq~ocB@>PLhWN`XUVWfs5I6@aAPWs3v6i``g8$rO7jiobQ zuMtk(?@W_Pbw#%GD%ZM9p|`qi!SEO`bxN9X4y_C)&Kf^_rTry8ntT>!7gC+m4+Q~J zFJn*3i$;f&-ON@x#=^DpD`sDtLdVp%$L4uAw`>*j;mwlD=XLgh92fID-{I*gK1x$(a;D%3$2Y*U)?eN5{f`F;&+7iWo&$gya-Bs$z zk-pGpg5yrRUJhs`*zR8{K!{c3D~ z-;U{5$>>3%fT?)9PKvSHoAKPE|B3VU?R_KYRWf{xC}3)nc_&5S%x3&g{-3yZ#K~79 z?kXu8E((}h^2Jf8ZRD3*!>rsADj%d?+- z$2rwV5?$}aRWv3vk(V7r0aL?9?x^VA{|7cL{ZDwU>{b!7tBI7WiUOtvObWoy8-GhT zHvT7lqPj#Z^O>voPGnUBh1UU7CE5gkUel5s9q>gG?>iV*7T?ySCyplw0;a@I?S;Wh z%4-j_pbrmA{U*V07pCB6Ug|tN`ncDA)kd=2V;F_c1ilV*_M-1|%OAMx*nh9w>1Up| z*SaTU;$l(2RLQ$w*@BGkxYy(V#JVI+pRb1>k%*SVg=4@}-{d{Ad8@u+`?&x9f)@(+ z`nWxKK$4D&0;Wn=f0p^kKj9VVzxP$?&lKOj)9;ccGe!uB{EP0x4itUFG|pB5H9}Fl#_==7sibgr34^Hv zA>r)g>G#-su$Pi>oi>a+KUz;rA8!#vZE`5fZdN6e^1CabmhNhGU>Gkry`D^O-ppXC zrC$g;6{bRNWcw=#@6cpEZS8ro;Pq}nq|fZhzWD2qr$gNoP)ohrjwkbn@#o2G^)d!i zvr_`upn+PX!Y5Qo+_8-0ZaIiAJCqCJ??5j$X__h794J#jjnFUa0N(PwHhq2ZD1#|m zS5Ic@W20Oc%a&h#4Igtq{b7?k=ovhz)7il_;Q=*3{Lm{F=TQP|z#D;Z1;aPP`K z*4U9jw-S}a)9Jdr*FZw87M>J@dxHfFsdXjitFZ!VY1}Pp&3OkxD_2)Cm@2O~XE)k8 zlU;5}N}_}9CwBK)811%&3t~oN2exOl7kMznR{^!Ovi$UobvqnJWBn=^O#OY`o-N$s zP6ApcDhWf&3oL700cc8sRy)*( zT#fFlBuZk|vl$}?(>>B%3!vC^Se+fW@F$Utt_rB7vj%&%vKs0BBEcIEF_;Q&Qe)~d zg!DI#Q4;DtgV?Peqv+p%qWBW|MX}ntCvn^2sDN6!u9lz1J}(|cFAUwoV5;foCq>R+ ze?mrwD+#k&HI~+tMtyed7DU>;M~Y|O!6et(Mgg_7T3Thma#y6&R_nGgm@+;6P?5YK zkmyAODT$fw!WH^46DhLUDhPOv3~Gc_yk&|xPbN?ml^qPG;F&v7tnNBNQQWGK23%`U zz%w`SOp$oqdEOT%MaRNII!bX-0aNq8K2<~}h7pU`)8(SLEPX2Nx98JK_MI3M@QfGK z2ql{YD6)U&(+gh=8BA^X`b06-sy7+uc~&lp_!1IYvOZU9Ll*4he3{M+3mce`N z1Zc;xvCnI<&6qE8IBO&1^Du{>O!CFW31b*cc?HEvW64FlTh>Y;isH&FuGgUrc^;J` z2t&sh_DbgoZeIOQ4z<)hX=fI13Ti`cO~_?1wKpW1{hIR#Yb>kY^xe}LOudPVU|vr@PQ$hnJZBDrsY~N~v+)V)MD2^Ql4w6@0Dm(6DrvQ0 zp&()u!A#S&HJSFll>%z%ZUrv}@NJi_kjL)x8B8T_4`PcNbV*3FnUY8w8pBrw{vpZ7 zmIxxj#Gf4-Yed{`X)2(Wb~M_@a*dI{N&K#b45rHdQ1-mJJ$Zb>Qb~B`_T=f0^l9#d zWrA3+&4&dVS(08mH5E`xyO3rE@z@l7+Vl1z22*vjy;(-CIf)DDtRxzk8`nEyL!Z_! z6NK}~9?ZwWj&vK;N&&Uh*{Gcd|Kw~#KUFMZFm*E0m1PgLB`w!>RubKkJM%I zQbF|3c3^uaIFm2xEfi2oJ4{t=_>9>e)GKNsgDLM(_H5(E?!^Cqm69mVYQqQA1k>TO z7Ym}c(TYX>@*vi0RTWSp)I33->w5he2&Oih1g$!v|?iOD<*B{5{ucQ$8Z95r}7 zUl7O7bYw@Q`{OK*|1F1F+P!1`heepg(cvYt8B9goHe#)-eaOOYrV3H)JbsCNDi}mN z=*$sBsbd?KKG~nh^FPR;mUe%(yT;nKA4Dw@rZJc*>D!w5E~jMZ79)iy{0%m+VzBbsnx z5`!r?c8TJGUNHAdYexkOB5AR z9(>obuJpTot|0Dbxv_WI_N3h6jvQ*~y4p@puKB>0`hOnJUj1rY<^niNpo1U-JFRK-|_qB)ab5-Bs-YURp~kN-Gp&(`)6Wwt?uE5hzm^ox4P$ z=548*tQvzqn-3F+13&fTkT;%Cz3z~T(h9{%s|vYOmofP4k-tn`bnX&~swdg<#u?Gr z!lAc7w0m7&UZ?T_?=9IXN-Gp6F6@!F=|y9rvr?umI(Lagz_tmpgJLQ+T;wbeVMafs zwB>#HO5=-ed|?|mA|CeBG{;MGAOXpBo~exC3#Be@up z@aUXYGIi0pOC;707^!}DzZ~?9Rtev8Iup@8Ii8K`KSDia@C`VfkuA(Vv{y|eCiBzf zE93HE{VfB5pz|Z8c~4PEPjz@{N9_Ai{0`FZe1*QVe7m9pG+v_OmFm3iZt8~q*4V4% zP~m%iB19>h<(b2sKSe5$Xjkj2HV$fuqZSPp2s(FBnxAQ5(p&A(za^#y1q$<3n;V{T z)w)*Ts8^~IiNt@yoW2I+343bGEmO z@afXehtj+rb@GP%=u0>b%Ize~S9C_D-Nt+u+T-PNw>D#O>H03hXGOb;MdHN#DtXx9 z5ZuzxOd#mzLurM=q0wGBO%a2stC|Wk9G!z{FE?M?m$OOs)0vFc?pDJ4pdHa7VK7p~ zGeS|gQ`JNu=xe7m@ABT-Qg(bW1GgP4ljsabXH?oL&#PqSf20KCWc+*Xr$k+}BVHr| zekkP~J(6(Wl5&Bd9qN?kb9;0=->I+>3|YHCwowj{@5kO?+FzWdRf_{;*QF(FiJSdD zS?AnSaq5Fd8bO}tQklAF#$3#7d%cKP8!gLVhO^QI;_1?Xa{bjZdu7$>pX~XN%h77j z&~T_bYK=_)7R_dF&h95WdOl>g`nvNfz`F?()%EnoL&W{fGIcdp_mMMdUbE}WR}u-! z7vt1@_b!B8r8xp|ah0DOk^Gr8Eb1pwns;`ZWkqqgpor} z_1#?t=x$Rc5GS-9<pDH9cOUH1Atlt*h4k4JJki74Z0*#*R8JYWmEqy&?I51BoZGUYO6hd1BNuYEf7z=+saEf*+TjAsS>66 zo=#(H;jG* zVkMCn6tGfGjt;@3+){yPENjUlR=7dz-580|3dQ|3qvY7=aK7H)qCn8<0;Ty5X8Wef zD?f$f_Q2CJb-DO{m(~U|u+WK?MBUYg-FA5doc+E`AZTuy(!ARDb&|R?H3F>9E|aN?R;@+i*ZXnmNlmihh3jg8pt)&E zD-`3pj#n36-v*m&GG*$bRcn#xbSGHt{^$xQ>TePVnwzFH-_vR6NcGp4E3oCkdYQUt z)mkJ9F9fKERepmyL$d{f=B6plp9kj;RF^n?gE?_qWa^?-YmsRscS;l=E1nYw7zS|on9b5u79Hpl&udjx{!rYX&5hPdu(-M8&=PS_5a zx@gr}B%Cj`S3ATz;!T^q0zq@rl;%18cnfu0tpkSc*&$OGty+u3c||kz{CA%CK4OnR z&`dL>dHzaUUmcg~i4Ie@%hW}y)*@kX^NW0BYXF|J-X#z;(@bgJPo4Qwe$Xob^NY92 z)J3b-BEe!W$(tqzqiZD3OpuH@%`{V*Kiz#OlMgutW9*KNGIh}!v`92`+9LmTABRV9 zlR(f+Go=-Zd9gd?33lU9HdrH57p+>0M4|o|+3#002IQ|62%2f8G+!;EGetJEnuKrL zrpwettJWg%ZCgEg=(0HUySH2*Xl9$z{G6YrE#%tTIGkU$K&CEQwHAqcK|`e-c?no# zF<&5PWt7qi#T0aw_C1+|CpH}u=5|`Crt>_%OUBtr0i&j(^T2eO{#{z<7RMOlkffeB z-<`b~Jy@naQ1r=*K2s?a16w4j6?VX~Y!Zdv5BdurR$s?XnxxLsKLi=qK1(#OPHUcG zPJedoOga1KRGhN-vqYaWX*N=PcK-b^P977JfI2_4h39ih)8}2@`*Cr-RBw1H+OElw zXf2*TM~hFwxjAZ8o2Z%CZp>_nuCAax0rW2^6rt^6)cO@&Vc>(U!jmw4{uG}eE9z)V z*E&wZB?c#Dx?YK1XL|kl@AUse9{iRxed zh8*pGqDUa9i>^!OtF}1tW@!7PKAfNmCA$6ykjL^d`VZa9$GCrglsdBY@}oURh-=)b zi>`O)Pb{4Hm9x>YJ}0O`iKqOGfZcqI&-{!49#ebreVr?R=3Rd%uGOb5x^AEE7tV>) z)18mr;RIDEVeI84Yju9ScjU<%e2lu)Ouebi^rHi^y9fkz74R+s%|04eufF6&b56WY zH+Do$P=yjFIT6dpxcEP!rFAEDh>S<#I*R)OWY~MgcHrdxcgg9P=yk^CtJ&Fx;);yMWxNVaeL3H zksEFL?HG{|CJ@v`_ch^t$g^wY9wn>t*KmR={}R47kM{=holtn(erB|4@6nm~{-+zG z{rI#`Kk57~>9lrV7+(~_*Bi7f%Te9qYpNTE|Hr6832{yJ$WnW0UO_5`Ts|%k)HQrl zrKG)}4{T1<;$w`@8YMj$n}R0O>jNEwy8f&^DwXZ?1FN_XoJdy%OOvBhaO|UcKov?v z9eW^Y&+vyWDVq0TUN>91w{->%Yu{NQsO$6br&6@3AG}J;<%G`9A}Qi*A`Ytx76|HE zWO7DYdBGc=JKFQRq(@P%w0+`qyf|(sP=yjdw!V_$;(g(G=`%it{@~ZrgIx*O&>~SF zsB8D+_mY2-H(VavgpXnDt1JJ#Fa<}vT`LgOIp*O)83pId)Yzm8aV+sb|?}E z>KeA|uJn413v>)#!HLuU?dAS9Uc{Ak?+4ifQF2 zl(w!Nye`+QKFf7mFOPlQ74P=#f>cp{Y9d#swFa%=%S^RQOHK(hgtkAQa$@Set#Yfa zopGW;SELFh7Vd2(>s&SjgT^;GVSDX>{IpLSH1~2A2Ke4ak$kP& zQx>se=A?W|^%9!&3_z+-BKufNc|gi*)>4t>vE#e?NYgMP9nTr5{6WvL?}Pebz$%k*0_qF=%UCwTp8#s~y; zElg@HpAFf`LL3@!qGJR8K3=wkwDsczg1YW~X)51Xz;{=XnsVY@WQDwSMq`*`Fb=6g ziM|!B<=ws3usf|ZpDq?x%Hx~{u{8nX1%kS2u-X6Os}8}eq`k0b4gH?e8AJ2rq4_rpHUHh@ z(e!`o1X~VUE38+f@d{r#SIvX13ev0A1(Ds~JB&yZOE- zfhdeZs!-x}nThmg%SV=eT(hETeupP+ix*snb^k>O1a;AsfeOX)zz1#v%&)_=$q`5u zO7u%Lk=Atk$c~n2#;^%I>$d*Jb=cZlB&bVVarnEiE_yp?<3P7=7~Cva`a0n`o6<%X zY*zP^E?;=TTHk2^cg)60u}|Nz;QEdE7)N9syn`(jw3)Qz zW)W5@q&-8xST<5D4m`SCjY9>z@E~wGQ@J z*$aEr9Uxg`yOIMvfAk)W&ioeN_S~y(Xlm=5OVDc3{Ve8s!-z99~-H)+dEci zsaXy9(jMT)-@6d(JX#>AOLt`#=}xa|*7mmM)6HU^nLa*&%#CA^DwLqtiT5FA>|zJB z%E0CC1c9I~dY$;%@WBnx-RJ=9zwd)}ibhGG^@Cl`uMhMtiC;TZ@-+L#Dn@BO-PuMB z(Wc{GsQl)GRH1}U@1fGPTQ$tsP4nr#j(h@7HywuCs=)$5UDXx-(#)7IY`nkbv-10M zAAWQzfPBBfNEJ%>4)v3I&-}zT&D9W*2M$5sjXBUuH&h^~OJ0N0m`|VButd!jyg#A= zuF5Hes*Zs4wbO4D9gnZaiTw#5H$8xPD?E@Yl%RJg&*=}i2{}W{`5xE<1cJKgE94#V zZ;N5Wgu9TwIsmCc33^ZS%BcNzI1pY6d82{^g1YD(s!(hzKBshYsemPWCm@}j>75~d z2j2`i#>Q@Y0QJU?#YUFq(mA(k7Ph$#(7Te-e2m<-%;f7eNbrpi29X;0D(SXqn_%jpEZCguCJ@v`zs>wND*6K~Pte9Ivz(FM zuXIkN_ZVO8blDDLJ?DbM2OC`Ye2Nr~f7lemM#8J2ua@_Cot-U>k?UfsJ|nOSjipI( zZ`u1gb)o4}L#b`S3$}1>Jz@U=g(A#-n(F?zAFyumD5S1oQ!cBrkH2R@XSM$!?l+k! zE!o@}qbBqbh-2sVq~Z=w*rUNZKxu`-CvmFO=xHnLQl~FcR}*$lwd?Z>wsds;e~7!= z_DWx#*`iwIA`pJtb)|)|_u2Bj4S~`;uiLRiTK&oq4Z`?tA;i^Xh^+cj=P`3j{FfN@ z<)L)Tq!(VaG#7|pmvyB3<8QNNZ*_sveBDGH9r<0PKSt=bLh4Gob6gdqb&th-`Ines z+e~)w4Me>g^#r2N0&Qtw!VNYvR1YZ4>o~d{Y3lZ?hH`{v}qV zbe2=R$Km<%s{--Ow^rpAbB!sj4S~`MMW28e`TEO5+^2KZZL;oxUJzW=Ht>9D6LR@yEH&5X)qIy*rqe;8r9CIaND+9?A{lne~1uA zE7r|!CZ^0-DiHnsS}A?H-DKZW+5)9{)?lACyW%ht_gC`$)rsrxfwszL>YL21r}00; zod4=Vs9g&FEm|cIDZU$(^%BZi@1Z6@X}-pNOAT{uoq|smsTg$~i(aBkyLN*qPaFS3 z%$(-|p4CaXT|Y)3%5D}bzg)e>QZicsrTK5|L~rG&;QOF|Z5+~F73gjYW^KIK^T*Fv z^;k_@V*8*qJL3BR28E4A>WWJ>VSWWK+0-WWKqR0tL3z38BP2f$69~Eo1f}_oKq=+Q zxQ5@LwtXm4SCi5j<-qE<>|2MrAQCCLJ(UAuzJX(Fk)S(MP?}dpPp?+CvHA_>r$dms zK8Ea7PSC4ji}(&GBH?lRi(CA<-%z$sB!H<3R<)oT<| z7yTs@iEpu^R6p1Lgn2zhg6=IsX@%m(`X*At&TX)CVjrZxUPEH~s$R5x!&c|j`{#FX z$$QI6S9=hfy5L?Xb3#~ohGXE*{fYQ7JTL)B2jN9Rx z!G1_x^csjnuC}#OHf@J%28hJY?M}+;L*KBkJL~;(1$)J`R4&do!MHp>q%L~*(eZdB zlk!ce+tCD1J-7gRBEBAM7i+L)4q%Qg`qT}&h3Tiyrz<@Rw zVbMn*-a5TeuIc=o9V@E;&v)>hSy$$MzZD)1=!?`vX9GGOk4x6gW40;ASnrcaEO=nV z)NdX!^X)qS%q21NqnP%gmbgB;KT;Q+)#!M<`kHr`O$s)|E0YHZ#I*9{)Az*qJE znG+{3tzt9BcS7qdh9&1+nDzR*%;!J@pyS=|+k*{DyTzPyG?|Iu?@hob-WGd(brQyC zoMOQCeY(ST7c>Hqc=h-K8*Q8ETA_elH`vrG4jACwL-=$D|9-4&?evfx zuWSe+u{|b(#pQR$sxjRKf?j`0^PLcuZD7|n_Q0%Bj>0v+l)p*o63SQi+cX4`uuW64 zNw<4qOo@X)(EFIu{JFNN53`!?gzZ~92zPsDv{(Kd|BO8@YycuL|9+}6u%|O76xa&{ z{XSBfpQz(CPiZvY8CQ?B7rwQZzjrR2I`ldFGOq!ML{aq?m3@*k#!VCnITj2!wX5id9zR+lb~x>!V7OzybKP zu}FMiU6ftNK4b?RbpQEu<2oHyI&>X?Uwv94bp+6>-h{VDXYn5$6 z?z2C;b^p0bio2w-_K*7E_g+RwUG#pX<0%xM;;%Ea-hFYVjv^}NIK|7-Hk z-R{@-3Tsl{2O~}yBX!a59UYHHmK&SF;7NY?{BA3OSU#-@yY#t&8Mrt7=UY4HL1S=z z+#4@kY>m`K=MOp_Un?Uk!Cv1R+fHdK5OeF;vwOG8S)&)a|I9v1qK3oxnju&^S{vmW z8)mwrj5QwE4Cr{DI&@;g-d|x2Ug`5$wAG^s*baf%wa+iXwdHjKmfr9>t8ZZdA^}6~ z;IBFehfeq=5cG4SG~YMsp*_5M6@;%>dE3=cc3oEm z)K&c0v@m}l-yO858Hhx`osA_Q-Oj?xN6f2l}{a}C9o)-^&tfj;+(#1eynknth{Cwx32 z+zs@qdA_U5X8M*gn|>|%y<0pk0CMj|;HsfVg=^c&;EJ;U8Hw2L=Nk7Xz_KZP;bq584UNuVd zlTTh1F&*0&45&CLT-$qh%#=@N-e#|~4M8Ms9Z4fwW3R>={WZT0{*xdLF?9CJtpx?V& z+utZBKe@_64r}t%a=>~>51E3l^YnodbT*(guX)W0l`mu^;>meu7`@K)m590UVbW%( zvW&wEeqC8gTpKoJ)&=$;$xIked{vfR)8KNQY1q*zn$hnwb&0Ra`uPah`XCXzmY!wQ zMQNJ%<((zd53|?LTcY-ce!|l>eY&Uj8{eh5%nhzP_r}C{V0UIJ91#K-9y+1oRBS)}q6CpWX`zj0`Kc|FuN-X;*#)xLig zYjj!*(#BVC!qg)YHzchG<3@{sDwMeNYb~49rwaly@ulmk8$B9oyF*tK+I;;x|6$t9; zc76?0xHN#6CK4yc9GZd`L$|`QY1gH1&okI!HyfC7+DVGgOJ^4b*uyYicj;`COtxl8 zH`qN#SK=LQR&jVBXEiKcQ7I^tSQ(Vgp1$f1p&grZVph92R4X=uU3#WKP}e%UOt$-* zJ#3zRO2zltHjT#_?Xn=+VxvSAN(@_<&K#CF!8Eyq6DLjL@y-0TU?10AAgJq1?@Sh( ze@XhlO53O z4i??jg*>vXiN^^GGNB?UOGOn*B$ubN^W`q!nR0;>NuT1;_E;vg^)*#eg1YYa&1Cfp z9Qn*)qU6uc*Wz(^dKP5abW>7=5+_R1+0b|wn9$RT6ECmxSCyOzhU(^w64YhqoXIfW z0iJ)_!wH?i@tBvm20qWWWK^NV)LrSU*uWVAS{&v?r(yAUdUh7{JT*fgs4J>XCaYO! z2L_M6bE3tHIKDUBI(Tikj8TOWCh_TP(C;4bHb`^&Q0^*zGMDcf=)UlfKv372?-{Ja zv#xOQfCVS)rpDsLbsOPrt71kKN*wN<&dS<4!uJ2I9vCn;#$J*x$)`w(eHY`K1L^p#=M|f>lrN23g9%oM_u%3O>=>1oLy63IugMI+nqt z+17B$D25Z&?PGW}wjJ!v%z-MD=(T4ByVAM~?6^Fg6ZN{q;IUg<;d+XVKu}l5of)jW ztUW|WFXF`W>l5+6+qV2F@*gg(NK062@rxyTKC^6M(1@o_J1=-sUb0WTA93I@715Nc83j}rTX`ada zE%hL$ZXqWwY~fY#lp_#0dm~VV5*-6quw{zou-xV}C*as&u_%|nk0p)a^@>tHM(b}QF{D*K%-(rKAgGJ}cJbI}@Ng_%eF9cH zUKD<#C~>P#IvcV{8#WbaPShFLe>i4Wo`Cv|MS{BMZ!qs~pF9}<8k_)^zz4!_EhX-0 ztz;=KKiOuB7krFZem3V^heAkG-WLe!qOk<;t-a9?2iHFVxoI^*%s`2OpI5RG=iae} z(g!|9$*O)>al8Y_0be;*5c(f`*mxO-9?sX~dmHW{qVhX>4kjwXhC(8(9A zeG9?4y+}|OjqP}cP`o?(T{#MS)0-kyC~+_^lg&O`#vVm$Vo~3Bh&?}@fT5q72n2P} z7?pRo)i|SHpTqF7dn=?0C5|SoW{EmQ%x;q=rtaqGjJd(bVCZIJfuJrLYbz9A7uliW z^Z~GGWGO`9lnB|fmNhZUXNIPl4%41XyYc*39{gTxArRC>pBeaBLVs-W)WyRvXoRKk zG(ibn-Hj~eW)6GaOEbo+Ww!Y3+##rGX(bTUMW1B&Z`A0KILY}F7$3BjX}pu|w3vB+ z?E!V$^_FOiqEM9ijl%Dn--5KKlS~y#m}D+yuPa>Oo=+=Dp%{sy(B9`095eeU{4MID zF$(W!Tpfy8Pu@es$gdJrC=vf~G23-O2}SPLRXl5u5sELq*1%7bOo5;-8lxx_s_-zJ zP*??R+pm+TLJ3KK2|E!Bu)r^rkI`&w7`g}Y?_cOM6(y*P#wdLD$q&Op7S-Tb@m@t0 zN_@3i!rUwn>g!(P(Ng%aFdP_D4X%ggDk(u-G)Cd4U@Qp3`K@Z;g2@skRVZQEdI>`n zz+!hB9+%`S3d2?2AHk$zDx(B-(HMot)OSPCeN7EG<<4eQp+tDqVs;N0oL_ZAxZg1^s71%kS0jKVv%Dn{YOel@VE%RNRFfyi6T4*qq8Bc(cgW|)6>6b?M{9#)#` z0VPa`i^eFtUoaA^588JNP}>Sse#!m2Yte2m-a!8pYK4K(=^DiG8~V-$r#*K!2Tm{0}b z$0q|-DDmv*BDUDS8yqT|&BvJTH3Apdy@Dm5<_ZLL(HMoFsv8i9mXqGY=#1q+6-ulf zyNEeec7ozZnS6}RDS>$H)N^>Wcbz~`7mZOAiin?sv03FCSZ25rs6vSiofk3hqZV-V z(=I;7-JV0R(W@traX42XsEfuZ{29k60GF(K3GBs5pb8~o^%k-8*KJ|I+v9wU!m$B3 zVaY?dY5xRG~zu;bQjIwjRU>Yu1c9HuAt_CD-}6WZD8jT{K4F&p3PBaHsY)=YtvcbFhXqik z6bb60F$#aiDQ}OV(qUL1XpdB(MBSWp)^FVzwlhQ%WpugL9v!Y8hMhx2g1Tso!ei>a zW|%eX5PX*%kSdhOGtFeD`W7%l6HPbnWFr%Nu`?UiHE|IL>Y`B%e?D*Jfr`ED@bT@D zGL1!+tenGI)^!E@Km8>dKkyweJ9^=fCv9+4e5gznN_74(ht*gBwA|57;(M63@j|V$ zW;n;by+BYGjUV_qqkPrb&8zM3Qi+936-s!!rm-=dJ;3o;C66-pFYATxTAAZl>kASk zsEfuA3dM?8Z;bn3hGV;5mZ(CBfao-~u&Ea$4Vb{kSjCBhyUlU)*VY0-T{M2+>pw1f z;~i&noOq(0L={TBn4QKhUG##$rMGz`^YD^4eu*;2n#iL{N>CS#ANY!qwchw)k2%In zD^OB}5)Y=Pu}{HXU_Q}-M;SBLd*h)A?a{KyZbk{}qVWTtcklMXYBzJt2{^#0LWxQK zY0UGy2Q0Br^D(A8?S<P$EJ%jhTlcc&yRo zGegFCFU;Ozg4UBf1%kS0{J_^Dck;yhO--@GbU&a9CA{Q0%-2u}iY#Y7hNGJ&Rz7Ww zlH)Xipe`Ce@HN%u?$~odTMQ1G1yrF##P~TZ;*AqTyN%&vl)Jm*h7CrzbU~ItP#29K z6bh?d3|&XG!t-l3097cVt3QXCy>oyfQ_b1S_bV87z0w?ee#;dI>Z0+3LUHS`D`qZj zfyJYb0aYmR{oHJJ+_Ed=<*egl=ze#_6DiGb$J1hgpe`Ce@XC*;6ZSLLN2|Otpb90% zt(wiWw^>6-hXZ_!b=#fLBCion^?M``)J5Y59$yV|#0Bkiadz?>pb8}_(q^+2lTG2w zL`^PSUG9jBCf37}PTvKBx@i2svpDx`Q7^4NK7XKvRH4MHJ+oQvHX}$Juc-o<&hCa^ zM%2Q9vpNDnT{M2+&x1ER;k^C|WUft-DwIg(*ZgCzW>A-}OyX-AvO8mg*EOKS_sgIJ zbcbf8*L(~M9V=Aqd8}XzsxGUhL4fa%MAA<-h(yK)&fCYG=AWjJO288@@|7|m##<^ zN{qfbm&MGlVxx0^@-dnkw81aC%fPAHRv@U0#t(drVx}SPU3v);KK4MWP{Q43KD+Gy zh)q;zqKuE>EpS}7v*7CQBoNd^;|GP}?SD-%e~kpS$$(U$L_d>-O#ea|n`EPjGDxsb@9~8qws8<2U3L+r++VDAGOc2x3VV6SXZoz_k(sr@tIx% zL0vTB;MZgQb7&hbL!LnZ9-1+SbucewJ6hKVI!1VA3Y+ioh@I~Kznbu@DzFYN0&C;G zNEJ%ZPeGyharPa|J5dU`<$eM|T}taDcCGnGcFsq0)~{*ZA28jp0(5hGAyp_ruO@$v zTKE-Kw|D|sr5*x7T`MO}V+qS@**BAKe2h*n6?n<}1z1)pkt&p+ccnscb#*Pcsy{(! zpo>6ISF?dr*}=X#VEjpQ3b@v{y1453SAH5ycccm>=(mfXEqh)Y>#MYJEzhn|g1U~6 zjbpV7^dPHDQ+*v?(GU}d)WyN0IwMsmL1zgbWt?b$8{ap<9pfwng1YuO#M5*xa(lS*OOtOO`B)$K zv^By`K?X<_fe?NT5*+j~-`NanbQ=l;o!dV~PhtK)I>Pz*Lwt;KpB8Af#uSf_sE1Uc z1pW0>pA~3!z+6{ani+Z0zqASwBuRb6mNLE;4F`+Yh(B`=VuRW z(BB5ALJ1lz^E)xNJ-*r63#GuPj1tt9?Geu$@A|+3(}{eHjuk85uFp99+<(8kvvCOf zavov#li`x?USIaW#{+gQ3zDu33t^F7Uf^l%DDia@^H)Ocy|Gwkd_blOCA?I=EcA9S z=o{RF6XVCMgxGme*u4+m$&>so>Uyyygf(m712I!Hy$0S#R>4H)C`|agSf&ak0&n}W z+l9VhYTJ|(1F~1a!JRR9?oWU~P*?ba5Z1t{H*BcZbPklP$$&*uV$h@hAekzZc=p+s zMZNZe2YjVGKmBxN2AFJ)#g*N41%kRt8;@c;cKSikr8rK^bjXDFsj>L^t*%TJN~AaL z%_fERfoEk2oM>U636YAxLip}D?A)fv^S;=ekj+u}c6^|X}En!rlL^c1c z#_|Pzj-TQ<@vA$3AL+4ZQqu@1L0#bwLs(Pn4N*%jaAH+f2JGI(PX|8T7^p&tF<*Sy zmTEt6*15!qp&1zv+&u=fM-LMS>iRDugpJ?o4aRZJ8Sge6y9(3;VsLhTAW(%8P0D@Q zbT3~h_in+7$mCUE_?7SA5uG6r)aC9P!n}1n!7|B%6a6oz!&HMve8>A(s6vU9Bfji% zrWcgm^WwyC#Y!+RAA>`u6bb}&Wj-CrW+gMYuQiDilTR-PPnR)RUU(9yLWws!eOb&0 zfSC7_IdQ;z1zfl?0%Jcv6bS0d%pS>%8#{w}&{9rx^H~ZRw?|-)wU2=+ln9V~SzM3{ zY|~rL3GG))A<$qT{;t$QN>EqzvXQLmDSKG5V=E^vj#vc!8VtnTdv%a1lyK1N&3?Xe zfSnoHoTwhO7>+jf!SyE%1cJKes7EsUeVxIn;0PyT74zZN6K^!HX^vE(gx`tYti`S_ z5O^n_6Yk>{Ks_F3xcAf+C=ec0-8VjTfB}}jTu@*Zm zV82?EJ#TC|7ZTUo;7<#CfuOFC$Wd%~cx$LQrRi>)rj-oAO>J<+1)hN<3MFDw`mm1Q zT7!0{+ngA;WERYfX@}B6eqIV8sH?YC81ope57o1uaiZzrSlGVa1P#WzBULEz;a)%H zd`KT`e{1>xHusng)zh2d*4_RBL0y%5$FPh`IuN&`niB&OCIItminfJ)kt&o}-EtsX z^jrt}T4;7EY+gDwyu9P@55yRY}9!J@tuPOg1Q!DM6lt_KC8=Use^j>RfAUM~f| z{`@Rag1TOr*|EJ=ePQyx5u6wibB7r|O2MiI83I9FG=5Mh4o<0H9eN?Gdyw!cduHFwG`}EuQhz%}F!8sGt86~KTMjSlPaO4v6 z_>h7zBeyZCP{OLc9otl|FI4TG#N(1Z_C-v>WX!#(2b7>L8gcNfK~gbW%962+ud}5J zCE8i?`)Zy)bdof&&+rDttj+2~%t#$25Y$B@4t^rrzWUH|b|UV-)eopbiEo|k*zo#( z5PwqB%Xx0qaTb0k0S#Zy5(w%V*29jack+cFuBMzY%6-gcX2oLV!gT^cT{K4F8J6Nl z%sV3%8}Keus!-xZZ#&lgV=pN6bK_$ecFkuIHzwimBY6TrU3bUZu@6C>Fsou1CvIiG zXLsvI;dX;F0zq9gs^RMgo1bRJ6%n{ix(HOE#EUFDwrvuE>*XnY49DH4Sjw!?*yiwS zfuJrL)$r)Ghc>jGKL&#bKL)B$!uggR3+k+dp-nY)1MT~{Oe--2%jW+O2fczYb{5n_q+?-Ie(0gp_6=qMTG%2S=~t>sEbBUe4o@aIqX~mz~$DRkt&qf(-I}!k#i>VFZc#V9bkDDkSdfY`r3n;?BKhBozmpt z0-mjBJM=oCfd>i%bq$;A#2Pua0_#4SN`rCMC8nz|!`VH31cJI~ti|&_jnwSia8tbV z!3U{AiQ*s^c7I`WXzKZ#k1<(q4g2Wd0vom-AQ045G|!EF+uH;(w`lUBy{oS?ziG`d zG<1+aP#2BP_?{u(0P#2BP zc(3!H+3c*%FYrwcL8?$9B*Bxtc=nsYQca%v{Hz1)M5AXAX%{XK)J3B+zRv4N7#lv} z4%D_8k5r)q-QSB>;{NbTMP4~Hm@z>hs4Mfvw`}|7q5LRG;8`!x<~!U^iEZDs;VxxW>e`ZYn;X`;E+>gq8si+Nq>3|nu0;88~U;}m?+NedoComEkV5)Igl7psq%I4DV}QVdH!qK8Er7R5aRH!7RJRoumpS>T%+ifi0AL z-^P0lbkC;ZkgyBPVE6r#RG|c2d%~loGpX3Zyo5D4hHjLgE`2^m_tRa$w6djAp-4WK zic3CSX6`9zZd9QJU3;QX{Ktt`e=e~_hisLUpsojejBD#`AR%QdALGTGRLpg~!^S;I zRZ@i#bhQfaj!sL(U!j$(+HaLWP}lCXEcQL23%vMpgO4!~Q*l`OD;A&dNJ$k+(A6sZ zJLr&#hn?QDY`aSWL0x0{F6qDPbcV}ub@}%^vUMtUzWR}M{QXl&6-xA6k;O{1JHiFC z_MC9unu5nC)`gQrof%aqLD#qN9CCIFj@eKb^xQ24g1R9);$jLfeIIO_CBI1|?j zs6q+4B8GSTS|;G~TQTs)wYfl0*P5HFS+i?;P-eTAk1>D1WE|FcJ`@ieE37f0s|@Li z7@pbw9*d8I(;&IEo3QeQ68k;Zu-I%}$Qz=`s#Uj$!-8h1P#)1sAgGJJLjFEpPDQKu zNzih08({?xCB*m9zN+XLE1*K-Tj~eBQ;c z?fFuDZ~VEFNmQW(?f2rDZEbUGWzh>mDxL`hb@|qbXT7I-!}k~G_!tA4yn*{GhT^oR zo8^2-9x_!ZL8~?V>@%qfT0R?vMt>9nL0$AZ@q0J#BNVI|h5Ib($W);O zt-bJb`wo8u-;rV1?)hxt3Q`xndw52;OEp|}3BwttX~KO)30iyM{q3CSaGjr;rPsWW z{w?ZS%J0zDi+w?^*ue7){=KWj5jQ#3MFXmh4+4Rt%h+PVQAKNCZhy(iS@z4 z{Esj(BnXcXpKX$f^sN`wn_ zoLY4iG&~!Oo!fZ}1a;A>EYCoGe-CR+M&gM$U!nR+30ke;@l~@Au(8*0{IGg~Ku{O0 zF7rEa$y+EmI2@1lStL}EDM70>{H#XRTZo@L2zR9K7YOR2RdRmDVf-to|6~w;x}76b z!zn?lHT>7$@++tq(TDFVepMi-i`MRWPUi44a4PPDb1kn4Reeg(+6zAc%{bXT&;EveuKq$d6(wl3hUdu4CD?G|4cvX+ zUm&Q9c8l>22%96&VEGFu@f##`g;9c5Yxr~2e7;`v`we)|d6+;@7wvlExxPL7!R2r% ztj_&U=x(C~t=90}FN$-ZoSlbX@j(JXU1C+{gxfpl`z{yyY#4~N&yIHN(H=kEL6t(6q>fW1Q&h9JOj-w(7F+iGQOB#BT0#WpDvZ@8Uq>!(Flk4 zo(GxZx|OatquX48pf0+SfS=EK-2^ub^uTbhaG5HUpb-v#=A3Mazw7`%6uAoob(qy%-*E`OdW>S%`c-F@+8zi=UDpwWOxe0^<+GkNE|L&8Ny zJCCS~()_n}%8G*58=};qa6ty0qpW$LwtVR6SjoKl8Y|wbEx&&{TG}EXW6g)wl{K|O z%?Vrl%%burwUqjyhG8*i?VsX~eH=C!Ubc4^7Kf5dZw|C`l1WP&>C-c5m^u5Si& z3jg02L%JHcgy#pTw})%1&3m0^6Q_KUR1sOyw{GVptAn2;w}iEltKJ#r@#Vc_`C%I$ zLuKP#(51@=wOds^HB~6_bpKhY!{oP8o##6_A$?T3JpVdWoxMy~AgF8Q5s4YEel9i6 z$>qc+)sTY9?}OFD7B^EActj?Z$ z(qsLToER`~biu{Ie(JRkjn!14gy+iB(hRFgDSxM$6C+}WyDYBfr}j>3ClJ*2xJ5ow zbuE`{jfy$p`ro92cm6)=r?15-IZdbxu?%6AR=DP~X|!Sxps6yqG9UYge9?9v0l%`}>?oaF|uF>Q_(owFZuAs!-zPJ(cuiT7eX9@RSqNUd6i%KIowSHpodJ zs0$bFVZSntNPY5NabjFlTETU-t$Ki=o0=+=NF8`m+F6++N$=isVsNXWE`?>C)tNaU z5Y*MIcn3>-w@0dBHJli-#-Q-wU2}ENTyHg1C~@KYRyJtPCTYj6Uz|9#rD)co*mJ)@s-8eFcKL7AZF|-~B5kzkYRO{>wSvu<-l) z=4$yvfSM|l*fH;zbZ^64DgSDHPJF0daKa)-U%hb7Ac3H+B^m3OS=2mf^kNOMx+KQA zWM>0)Nz!mNRVY!nHj6c0Iz?)^un{NDZn7$LYEe%eacG2^DwJ@ac2xT4IZFCr*Mt*y zx(sp2$@weWvN1(Niv6AyC_VFP$_bC1MFqC&-^%uWW7JfkM77Zhc1Ko9{ZHz1 zqQBkC0(Yaga`UJ$YN}A8T~?mdGRaX&tTf<6yP{~9UN3LSZe|k%g1QzKFJVRj?WI?5 z4LM;^+P|>T=?ikpSy5`LP(oXMNb*irNV|F)bHe8Gu!8v&Me?4769t00Dpo9HXR)3% zwA_dj9T#_UPMno5e;gH~rV1tMJ#57qfBLLyS*aOgduLr2yGHr)pahYiu6peq*uIvZ zRlZL(#QuBng*S`4$(k5tBoNfK{;iv`>Wh&o z%+Zt+O~+*RxV*Qt@J;PZwb5N&W$3yW^)1HibFPNyFuQj_LiS4KjxQoXUHoseS*QN*7)76& z71p^0$|b*Ms;NSWu6@Ip);b+_qEs`+My+YCr{y$$Le@<6VZ9t_pO!P5-PJ;VdUZIP zdcl{CyJ#*`n&&doClsRHAy%i!Of^*~v8*bX+2?d%`pKFxbSCe1IrYJsEh`ZT>Jnd- z+p+^LvHbjv-{(@)^zSYokt2auAgdf?E`NDFggM%BB%&FH+aodTaHx}0K;`=<$>wB(!{r>aieBQeY?9Q2;xy~7+Td4T)_8?nveZ6$#h&>n4 zS$n*XtXwFs&z&L&nmU%zLs~v-hjcus0T)r#*5zKju|nRwBmwCbDy;S$V!Qv{Bl%3N z&qZPX?cQTLZIR#foFoXEy0f*Lw5HZEX~&tmTpT)_mg|_ZOZK&$h;$1TMGFqIWhYNc zChx00=Z}*wdC%&QBb%4T3xcMeb?PD&ygV=UZ*0qjrpO{E`&PcZyG1fEO?h~FO6~92@@w>OxVZF4-*;4U6Xnc} zu1L2~v2Jf3n^|ndJ2I+{$O`Y)$;~r$QkGAZ1wm65ZB%BonNK$V{)&r6Ev&q!)^JlC zKXniUP31XzNH1l64YJ}97ylje%(dl-ciQ7wY8TgnpYj~S~hIw?VaPT zq`SHZf~IbCZZAz8+gP?Yxy6OYW^LXX4@ucRz75hXR5Y|Y#Zt7*<<3K@j`Sm^g?T4i zc2vymTMB}vE>3ZmoQJlMC+xYvMO^2DxwcjT%D|Hik#3>l$vHQvM;#~rbwK6fe#W2N z+2aC~t9}iUZlPjZ{23O#r;QwYIERa`%@%l%I2oi|)2|~4nu=`WCb=(bC#Pl}=3+>; zd!F;jKFYf&E2LYfIC}ORtBiA(%WbQ^4=#Ow)GPQ;Kfe5-rXXl)+&))n_$haJs#zu% z4x?`7oP8Rh3_fFsbPE*&{9L6)2Rq1MvzCkQ*6Ci0lOvRVaYjhDP~q9JfE`QdApb0> z5@W;v$tfJl2O}hZ1uAH&#~T-EY^bk1_u?Whn%?&Ds%#XcY#8wk=oTv6vJ07UdtW)S z`(iFy_w>wplo+e*`T0~3G?kp`BGox2%Th!V7t>Z8=m4Ry%CvdUfNr6ptkFd_EmM{& z?^KEEPxhYN*d$J|FuN)UnxZSdt4P!HPwe~1=XIS! zuxiD4;pmkfe`ZgZCw+IjuJ#*OkMFOx|49KGJq?(uGRslvC-AMrV8>eTIKC}@fvqw@2K z?5oeHq!Czn^gf(Rz9fB!{l$i5EELZ5(Q|-&zR$u0ZP~ezXi#}e5HxkH{$c5V&ykfE znQA@nkHEerC4!)-Q|OrO7RQ~y>cK%h)ZLe5-_T!l#XsY$T zLUthdCyPE>^{HL{wSo7o_e0RF*>^$E6g~UJ`wc$E=O$D{VdG&Hf}kmSwyo+f&X4>I zM&g5^_kg|<`g4e9?w(AZm9rpgBz|0dTM#rgwDy|(|2=2lR`nz6hGIi{=c)s|K}%v zZV`u@hFlc{O+7u;gNfn=7aMg1OttN#_{?MCOx?o%PVR}xP4JH$R-SgW$*4TNvM zvtN$U{(d)8T|T$!yMcaKA8+HJ<*@l&f*@$Bj?G#vzS*m$|EfCDpP>IC_sjPT__A-3 zAZY4tx~etXbV(hZUA0fVQ1m&kD0mMnKR-bbG&TMAD{c9pr|OEsRr|!*=?VGIosU82 z)p3HLsoXhc(ySNd>NArn(Q1s1+OzZuEQ^j41WnO12>i%$;mcevj~(E(bD|(d7(StGjzj)77V0hvn))$6PJ8^n8Cty#Rl@#CMQ)^70V^#^5ndHd zy-M`gHuUz;9ys5GiyiiM`R`}`WCa$YpedUVZMBEDUiDq%R3+9Wjm%+NZnK#iL_t&Z z%nLv3JZ4_@m+AlJPvO;op1+`HLafR@YYPs()F$1k`Z-?t>E*ueF<*84CJLHzjVsnR zK66_;@$&!t)(P2)U9aJ`-f%JS5{r%A28(#r&V|(uHdHgN} z$tl7a7J6oap5x%tzx!Bp$hF)G7EY6dV+MMh5dSqnx_m8L^_*Arscm6jTl;;?dRXB- z8DEW^E$zOMuAX8IfF7fWVyJm7%zaviy)o&d%>Uy8KU+V^+J5=F)OtlbNITj=O~fD4 z?(r>Pt<#gNEo#*qmRhFPxYyH&Rg3Md(3Ja+mhf(?q6SXalSOgR!5T*;8bjs9AVGxG zX$MbQom7XM_$pD&k9YNIVc8HWH@At_Izxmju>3q5;uHW4{i;*3L>DR zGo1U=p1oQ8R-&4({n%`d`H`DpgrUDeQwKs?Kt`OF`TzQ?BZe+BNB>s<>8E8uc>1(~ zf7^wzA#EmYW_KoF~NzSpTSYBmqJs6&NqcO^=7ds{bxEN+tmcSI{ku^efWH5^0?nl zw1STDOPPgwU80(=%jjf;rA~S{v7d`VQ|59LIF`SX&1qVqBf|a|;={f*@NSW#AgrX8 zU~8Dcp7HK9s(Cly9X;H&%mVK$c2sEUR9Yh#e|#G|Y+0-$I?mCU>%yMlG zx!1DUDn3JoYQBd%{{>n(w8RT9Yb!K$wT?Z!G+->`X10#FccB7IZ@0rMP5In2^0@!Z z;@={qv+U8;9TL_2yFup>Fq32>IZ1@L1UeOParvsc`7j z5H93CU{;oMB|&RUdOZNw%x-w1;I&Lsbtl-uD&-mbxqOk1SY28IzXk;3yR2eC1Z{2r zSx#?Q!;qm8)qJAE%tT30T=KI8qJQy@)7=HPjCezdmM{}5Gpbv6o9UU>dMK;`@G!i$>j~2uj4{NB_ z!T_v`R4vsSO|y#!phaf_|80_Ghju_Ho4>VsJk5iHw2%^VW3y4fM zhBMZlTB`Z}s{2;h;x!&66I+?4wv04_m~qvi`hdYYV(+u{kgJ`9Gt06hDkjI6!HN^k1^h$D9fg^7T$}Dxf4zO8Bi3j6V&|J)(Eo{}Ao|7l!JWsiR6YG0 z64iX7T)GchCd=S>u%$v%w+nor-OaCRov4R8qUHi0{I|_aIN!dhARG!5xbnU(>-_by zL^Z!sZR3sK&F4abbu)#gJ{$VLsbfu9`^q~yVoEh{tRB1ts{gPT#Ev!!T%6W{1-(5l zQO!G~cXz-h1v_9apMXJAzXH7B@V8DZZT&SJk+iS_c7Boz{RY|z;>R=@J}v0SGi`)GQkfKVN=MXr>W&#r-$V0brh=GrO$&pA=d;1j_e)gs z^X-;yI3?#3cx0L?G!-<;6BhfYv6xt1)yVVl4xU0+Tp6W@?hXcm*!A8QLf5Wh<}N!V zs`=5Yu?v1{YKXS^`U*|$=x)cNnl|mhf9h^#*Lj%uMJbU5|r5Cc;s!Bc! zhiLxZUEqYQfgMKNd?wSB|7$nM^gqTDgV*Q?_PsThZgRjk&29?9T+N#>}wmGEKc-oe3v@_Ty)712Z&am>qUG^s>Ku6TP-3SNt=X<$M3k31Fl{+NjUG{Q?wM4Z> zvn|d6=bn;qU)y;yP1Wz<1dWb7Wofq>>4+x#8(?ZgXN=p|PY?@AUEr?f2^*PsTT3@Z_i54?QZMi70i+k(NkH|$pVL@m`C zjqO4kWNUk(hqskXQ>ojUgS%S6&VE~=BmOO}g^RO8aPP28iHd?Bt--o!IcqYwk1y34 z&B-83{JOjk#y#60(bVn0Ca`4wPnNj#w2m-xFvoimGHVQ>ZGW-N4OgpF zYc!_I#-RV&|MH(_pOxD@3kA8=ldPfttduVF3k8=5%$H48OU^$+AeR4sP-s<8T;!iI z=qzRU++BBCrYXB#ePCDplKd-=x9fm-gNd}20^qB2!$DQ74>M~Dv4^|S7baE zqbAK_$tOXkscv3<;JRbDy6VSP9TB8A7KdNC#*zl-31Y8%D0D4eu0HF(T%wv^AG|sS z8>HP~lPdCLn(AoV2TniRt{ynWSA>!0gMH5Sg%1~Z31V4EKUnzIh*c)dlBni$ zygrV`{BqBPFW& z`t~-X@ov9GaFoyOqp4#44$nQ|$J)ou)De|G;;^iAHGB(NEQl-q{b1H_UuIn+T%wwv zvpf}tp=;BjSH&WkreM?44`g>py^xDDwk2#tSVV3DKQp9hU4sx_Jt zyHU7gcP<dA6y6JjBXzeiw{9&} zs`<5|YC~{l=?^GzjAS$w@XQ|;#2jP3KPvM@(RlJe?3(=tHn+MXi1hj0VN+oyJ8H69 zrJ7F)DT%}*oiw=EwUp6Rt;jAgX52~EI(?0f_|Z864>r}qqP=E7#YL-bud0n6>oY@K5_0MI)XBX>;YLk=kdEyUkt4e-vfjN<&@Vd>197!!2 zMM8@w1M~Nl^^j8H!oijQ|GDE;^OmArlkwx{lfFJB?PQwrI2{f|aiT*u|g2`|iX1L*oM^s`-lePRV$~s7!r)(@CbONDPN+olVt~2S(_KI3*b$ zuMJ?Y`#K6Dpm8K5&Tv!*HR~c#&Cj=YO~xj*y097z9A%p7sD{Jljv?x{JJCAgq@0Wc zVF@c}-AEAA`E$H>9IA%hmL#gH&dDUBdVK-A{;i=*Q_D|=L(PRt)BzVGb;MHsyUML` zkWCM(BZ%4jclA7Pf$G(*gG4p&O6ir1_0#t-JvY0bjws>3tIL-! z^UsF4AfoLfVW`srq9UVuBvec+R=?D*CsEB;>4hcZ+l)%4bt{u-s$g+AgkJuoHd@qPN7VO8#uP6z zc$|Jq5ECYZ!!}PdwrQ55L^ba}zcv;BS!V>VC%VJs1?;JPHPyk~~9UR$5cmC*+cjIQ(fU*7#5pTN1kyn|_uT5y+?~!AS zikpQ4!1R$Di|>5gmumjqd3Q1{bE^h<{N_V6wP1HR7|k|kiLI~th~nIl8R&NBKepIt zx*$wvg@ehumMnjIS1r~2NPo}_Tu`P5o3a)#no|2mKxu6wcIfF3Us3$$nSz&RzhI`7 zHiF18kAM~a_RQh%YAw|o&D-ZQ@L}mU*7`(iMpMee2dDj){0G;dPYk%pSRRC1*1m2WqBSORGM1i7YVo0pQ#H^rt66Pr75`o9x_J< zFD(^U??u3@PCwM#ts05ys?L`beD>i!J3GuwOH;Tb5-zqrqn?YtrWHl@j}%<9YA2g* z*Fd6zejcgj-&l^PV9tJI*tX z_+thd&ThztMpQ5===+swjmCBR4AiUW%4!wq0Zk=kghSqet7`6b>wHn1+{phPEo!r8 zKMNTZ^c_w$-|u!y!QS?r*rnKejHdj1M8K6*XVk5mLVZOs-8L0nVoX@4gi(#-(DD;_qtE@d<*U?^mk%*{Ig3xb}u8 zYkY7KqpADaNSM4NQ`PqDuN8%LZYs_nQmj5~-bfJi{Yte)^KWu0;&V^-FuVh!DU$<{ zu;AEYwfcfBT2TbPO2y)i`_vy7R;pCc_bb)BcPTFw4XU?b+M?qsO&OF$@+*x|>VcUT zwW9d*H5GSnU7!|U8{^w^Z9Ke5Vz~H{R>> zqf?N2wox}N6^0)pVa=}A>iG1A64e?_-6yHI4iFu8rj_hRoStX@ueoiJJ$$Gl&Oe^ z6+tZe@rJplR)-qb|I<>UL+!m2@lv1pGEL3tVgTm@4B_V+E=`i$`PY zO@imGKFZ-Ass3S%j_k-pxaX5R$ z5kY)){>64{|FXStDFGXR}aKM11bA43>Y@QQUju}-3z-%F_TN+|c}jj^LO z3Qa{gRs+vfkJ$H)J9Wfc`_*7OAq4l_*C;eqt*0eKY`@P=*>BSkUmeroOK>-QZBkPZ zBVtV<`fM@tG02gq<`rkd2H04~pRX3FsnFECg|*=2jbav4?~smIYO@QL<@w_2uXciP z+fy4lIGB|*`rfxblfWY4K z*w5QJQ-F&n@uv(Evdlwx|p4-|DdO zOAKYI`OM6$XJFvC0%jcuS7@s2dLy`#V8DXf>FbE-8;`-I%R(6cAyN=K4%UU6UH+&~ zS{Tbz^SM!*U%&?2D7blVkU~>mTQZ5stI(= z@mGIrG|~}mPQ8MAhHKgT8N&oI)}lU4ZgC}l&4KDN)qHB*ZhtuTU@B^xUXtk11g-kw znj)4K#@B@=;o--3C7PmZl|(VgHU_dw5^&l9Cz%Rb^{M6^Zgr-BCcy*)$4E|5+~xTJ@>c zXgZ{~Rm&olVeTMsq>X;{>YteJ%Sw2E8E-aa#Wt3Qf_~ z%A#oY_c64Nw!z=c+X;dmCs571;yb;9{Q9-9&a!q2P0>}?qBwr_6@;xZ##IBo1VO7l z)qJA$iVsk8ya5JG^HOMvt{xYK#g7kAcDfAS9`q9gt>IK_Gz;r}fe|lWfyWX*g{J5# zcu`!5{Q~a~7QuSM071}-Of~P#D6WKwqYA-fe>a7u=xTmZe6RKsv^V#|n&Z6$L2EeG zeA?SZeXKukEBL+Xsn8VdN)W}`nBS0gGY!i2_YnlG;Z$oh$8DqVSqwYv?7aQ;v9WE9ybJ7a{#-(d{ zw@EgTW?%#}kBsJb2Kv6f00t$D#>Wj3gcZLJZ0bV58ot)KehsZC7Fb+?hoeT~jI!T? zpsSdv<|_fsZ$ZZP;kf#|p|Enf-mV6a6#a+2o4Q*oiZSUW5Iiv&&zE!&1YM0ywMKLO z&cE;}JPK!|^$=EIpZw4e{LXw~H}wr9QIzy~0q(sbF{$<(LC{s@RP!U`fcJ3g?*JTO zFke_n-XgyV>~Vk3wzhGWL^0*zN7yU%#f}-<1VLBFQ_a8Kef|oyvqJD(zf568{D+|C zFv#->o0%FaiQ>kaAMn1iJASW;f}pGXspj8t7HIHsvu@~-bXr*1Klp$nynlR)ojN{U z5`_cP!#nd8R0B!{L3OIpFJZiTG+`Q?%*E;t+G#F`#B z?bT;N(5?%r`P3o(>KI<%4LkMxBGXiKyc7H_%xB}vGbB;eTVEYVx;WvHxduXS2JHo* zntwNls)5B#TH^S*hC;_kpI2=ldh;PR&@W38#j?^G*kfZOykli92-*chwMMgMxdrB> z*yHIEbD{Gkvuj(hDcR1NW*wJAvFEb|uIXcgtt@N>LA!aV=68=+Rtw*_*FuvFTcLyJ z`l5EQd;S{sq7h1>z=yT4;-(2MeJb|+(5@t^`C7F!8?1562xZfTLMKw*6&H9kc0M~c z{-Pub(`z=k`TG}`?<@8$(OxO4t0tw};fmiM;b${Pp`+^6Cs)YH9Lu(>xFLz6=`6lJ z`1(DVaBieJ>chpgX$=FFNvbp=|*@>F#y*&T?9e9D5>V3!R*G^|IZ&b@kwW)bJD2T1D1Vj zt7dKfD2d`TG)9L;3cG3LF9_P(Ni{#;p8F0`?1$lzX@7)zN9&Tf?zPFBPf&aDP@EcC zTcRnto>mlg-@d_!)WKLk`idZEU80&-ga3ZRrkw+E)3dum^`a|@Me#0Q4{s+8z>8O% zWcs+YE>W$~m|Qi)PGS8q@TH4PQ*=eND0-V#L+srf!yU&6g4QLfHJaPstK(+lU|iO3 zf=p9%Ww$88(G2bSbjSAks|7*p64iWuVs=f8x!{j^(djZx(G}{VSmA7m^WFS#uzFY! zv@TK2Cz!ReMxSvK{Hs1c`fkBOm1VQT()%Z4PKCcNk1s~~7y zqMF|=EzTZ41U1Ag{qHhO(GCt#TzX=UrG|FcqPw9&g;1A-{tvw-jqqem8+`EDP@yTI z6GadUW;Md$F6P+%ehop;x+G}Lk^N2ZnwKeV3^G?}igwh9V*igOcu3JhD_X>U z$tF5s{N=q+QqoGHDcW%+iqe@*cqn5T9FKAl1g%R{^COwA&KNg)5!_5@r_dDboD;>a zP-koq-4puu^AH5BOH}hYcbRRm$q0W~liXgRDcS)jijw_papLo@tWmm`AZR6{ns?+* zZ-*7?M`rxJgF;iZlTj3obK0T(ICr+w*hdhwzmjTxKbAHQcunq(!I^VZ+A%^qR4VVb zgZ)olG5@3vd<{!8_eR)dPdD6d=cm%t6f<|otoMus=>PN<#k4+6@oaV%Y}y1BR`Bz|Icsq!mRsgO(WgM#gJ<-U@>D7*WmFq?)$I z<)5{<=g4P?ru-&&!O0P~Sej?PRup$!+Td~rFFfGyCR0IsrKsljH>lGVA6k2&VP{XF zKPrE=59~;|%x29nl0;E{u^o=z>Vli*#0i4-d{M2@)Ia2k9pc*JO^0})&r2^<3!A#1 zW=Y{rk|@U4a>v8YEwQ)Z3PI4`HLCfn;xFw{uedo@u3jnhtJ!^!pyrInWJi`eg|^^z!74wtcIVg;O<_fZhEN0n-g=G%D%mrwc#7u%Q1G}ZbL6_JOUxwa?@Tq@fntC*ICbP%*sW(Q^a&@Lc7YcY{aLjG$0SjVaqf(+tq+4) z&l-ZDz0XwhBmLoBuxa`}n5$ny=yzVXwhM%|bYi<_KP8D`{;saLbjc)m_1IPrv=^OfK7+2vABXiF z1J!M8h5qwdXe049Wmi6O(;GZS8*q1uB^Fk`!(&98Bu*l40V zvaTJ?`pLBHawPgCZv@TK2C(zWEu|=>W;s9HjraHNGgh^$LJsnr3 z6-8){f&u1DusH+>g4QLfHJXD>I%1kbBiwN#P^KxHOP#<#KF$Ki)t5vuG^rD&HL8bQ zFH9E%txHt%JNG{7j9ylDxNUNZOj8$Ib^&!x7Q0v?Nun71u?rsOlUpyoS|bQrm#F6J zOM3g`PB#neuURY8)XdPXU{<<`8L5LLQS7nqhSF&h9H?dqg4QLf`S%a!0K9+F7(dq9 zC)3oJrv5P4el-hyHdzvd!=V6tbxDJlyXFak)+MSnn$)x1anHctkP@3O)0F3Ze{d~Z z#MEZ>eQhIs(Idpwd|ySi2q#k%V~(K+Wb40!ZH z5VS5)%_sal?S*%J3Sr0J7cxzC-Vgx2<3m`xaa$!(bhQn_h4Ztaap7k{(7Hr5KO(aY z#`bNFLj3yAGEM!k=?>2)cVLSvc1xnj&<11X_^pud`bQA7E>X?zm)a@>EBj|aQQmKv zrp#t{hdQ+!m{rU{Nfd`Whv40Xiy+6uP@#g>C93(=j5@t>^0j$TanL}asi%*+!QUqw72Sm zJ5M%*^=J4rD^g!+U7}i}sgv6W_dc%&i|uPDG*xYG4=8#*SABF}l|*qG`=G(;Q!KN$ zg&=4pqgtc+?ARAWzvi*CcWNp$wd!CGkTgbWP;Hb%v8H8TY&5A-y)n;H5YN;eu$!+# zuDFI0)qHlsIzM!N>WFq@XEIvvXkBU(A_Mz$ft{;2hgZ&ecROOif)+S>{6t1mODsFW zowes!-}XE5MPbjnpjS~-%r-8~qk`5Ys`>p=-*&~tLz>{qbr*eT>TzOcXnqiw(OT74 z6c?fcaM2D2tgXgLRM5IaHJ?L2t23oRIg<`EJ>}v<%{N}are0X!2J}#|G zRP+8?%V2D<(h|Qtag=Fl)zSbs(Q+3{xMV7cq9il~|0y-a#s7o~g4QLf`JMiH_C^Dj z>e#U`Os1*s+1+8PT?UIUbCN{SEw~T9y{nItV`mA1)+MU>5kSYj*rB!_o(-NY(^Sht zJwU(RO7?nL4@nevZX9a z5=A}FP<)&C3VNmN5CpADRP&zdicl;!ehwSQXUa5H_976vy3AlDt_hMT+V<~{AKdOi z$0tVwLF*FLeD7lwhGTZzf|fgv$~09ptS8KvH;TD`oFj>1%AhceaJ~RrTcaRoU7}i} zDYYJepBA2j4S6Wj)Z6Pl;aor{vmLxt62;fx0XRJ;8#aErEC^bcsOHnfYKCLRe@9`u zeUVI4H+*_QjRP{PSh!je#ZNgL_ifz)ukPFx1g%R{^LzbPgrh~-7T9?Du1r&Z*7O4Z zOh@*2+eS$ghIJzF>)GXC(D$hzXkDV3UxUO5%+M|c`@c_QntJ`b7kutv$@C9xlSJ|S zZUjz?odUxLy%PkjOH}hCnQ@Vr{dOEoy!lq9ss1g4AbjE{wL#7X?* ziJ1e@^n@vxxL3+F^>s@Sq*P2$)7u@AL{YYPAYNaxpE-Z}D+pT2sOH}}zYRp!!MoY* zMt^0RDuy7~V)8jZUO6I(qS23m=)C2ndfi-4p@LRUs`*`xU4n7Nx!Rbq;~=B;j@Bh{ zg23xKA?UHm8W)e*!)S`mG7yFP-9Bh;Y=xg1JyWTmb%|=e3Tang?Dfb3qo!U_X^Ku* z5JldfP@K=Fo?f}~OsIFXE>W$~EXwbX?^>B*-ny?s^`es^L}9&U00z7>#`o*CN%V1P zU80)zZFdgGJw--%|Km=fdeIpfqG*090w0;^;o2Pr#E0 zrs%8>QLI}&5UsygKxDqNAZT5pnolurHV6kT{|wGC?PQvwGfPDA%x*9)-ux2E9)$^l z)+MU>#FM>)G2Qw(T=ox_X^PHX5ygeDA(*(~9=uAQCJ0)WsOHx{t_;EPo_D~nOR`K; zbcT#54){gkvFyv>xqgWtXkDV3AMYNI!oDsSp-cazGELE0IHHg(hhkVO0E0*C1VQT( z)%*sabB1D{+4)d&#(J5i=u96`jJq@xcmFs9wQKJb1g%R{^Y@iD8f`rffd7h}GELFh zM54GeDH>la-3paw4hw?TC93(1`1jE$Z`%X`-ww+(MQ1FDBG+yhZpdB^(x!Yt(7Hr5 zzia5SVff<0Qs}fbU#2NK`AHOa_YcF?lat|}=H~@L>k`!(&6RpF*!av8*#7mLOjC5` zl_;*c#NeNR0WdS{iXdoRqMENZToZ#K6?~FdWsyu%bat00j&6;?8E$Riu5w!tv@TJt z(F`l?Q#ag4+ve|DQ3xZZMs`-)r&RA^mWfgPo{8*+bIulM5&PQU=x`7#cIpT>R=%hNT z`8t^nBk=CGt5DIRCX{~c4wL3=W}Cj>SLqy{f@wV=`TiOdga2;63-jYz z2-A9g&Fuxv$FF3;bxx_G*qb{XKbGEvJ~IsjK_?JVtYpC$)%dF*)|%D-or2P$NQqvS3)O3QO##SeBfeG z0sK72RGJ#;+7}A0&0+QtCwxT_;Wri=YEQx1{++Z`&{MP9gI@BQ)9_}8? z(su0AilS-GIGpq30Nge@AqYB~jB0)#6LlQ^C^!I%UHIfLGUu$}yHIE~buf!7c&-(N z>B{jKJ8}msPW~wfI%AD${*7hzc+Bd(1KMr;DbZBmr2a6NPq|sRvxX#!g4PpoYoGP- z^X%@X*U6nyR3&@FX{>N;VjShhiY^D*z~0hB~eUXJpuEpt$?5yH$l*u zcU1Ff>>DRwt1HW4^)feM&fN*aFqk#QjX|l4B#IGlC*bCw`QXqvKoE3xAJu%nTQLDU zex3(k!UBYOec%xW4L&qwnTz}+QT%e5h+`v?V02}qAm|K2s`+GYc_QWpC&DS8fx_Iu z@W?Qb8{4q;tAZp^SdN{DVZ)-q2jT@mXDL$6*ZZVS#L&-CaQ}0>Fh6nWv@qz&44IYj zKuHu`c1%R=;vQgEW2PYJOh~Hv9G0AkxGygN&O6K$=0N(d3WLBAuhoiGBP3C{-{8-2 z#})c-Tp$QK+mdR&cJR$a?1t^&z?KEVJj=tGVPNf9s6GyyAco??9R^OqK4u5ltQYHq zIjILOhrxVF5~pFz@x%^)UGM zA~WBuXs#p*pQK5cGQL=Sc4U(v=tNqo`Rs%dlW@n_4NzpVlKK1&g}L3L*>QhE-&T$K z!Tm?^>?yNT#rknnnTS`Mwt`R0ZbnnIl8NHa-tliWrFz{Lu$jp5fXhkt=<`jHhdm*%+p-A*`X$7EKqgmO1 z3QifwyIIS8ggUWt_yD-$C$s2Bs#X;5>nGy-)KvJ8u~`tb0#MDb34fk~el2D}`)L_M zomgBl08W>+V=wD{(2C+lN+M3*Jq~`)x*-T!0jSn!;)f*Srj`>Sq~kTAPFOVvhaT3= z*bZhQiQ+z=rk(RW3MxW>34&Gts`&((9f@ckH4OB|R|<7vRj+V(ex(kZ^vX^W#Xn_< zXr9#@t_-k}>EqH0KsBFqdnXa)JAJ`vqoqt!bk3b9`dK7l$*GR;v7m_{Xa%5}e~L+3Iudd)z;wIA+odYO}Hrga~ zd0`Kx?K=sARsgE`eX!amAzpHTTDF~JnxgXzMbRoS33GRtLQr>kd5xNsgroBpvS`n- zGELEWpQ5lxOv2$?TChy3NrIp?gKFMcJUt2PZ)?UZpG=f#iq0(+1GeT7BqzNInhGdooBjiT_lI~8Xe4S*sXDhOILsOERt zNS}({KO&*{?r26+bi$)3l21&-yP3UUb>s6Y6|`nh&7Wi3G(5bt54?{mRcVS&cofCr z0n@R5P$w8>v)z{pS~IBTJ&LuaX2Ipqj6M@JPlPkDJ5W*~5j(LgzJ# zVri{pRJ@zO^lNJbL2CxpyelOp8B6Y4Lh$EoVMZfOiPd0;e=>HkwSiyTj|r0_>2ru8 z@kt849~r}RsoPu+gcVjiC?-K-_ z_e(WD`%#>NsWa_an{US@nxa#PMR5;PFeA;KEpBx}qA5C$P88eEr(oUd&(u=eQ-Yw= zl&R+LT{Q)FS8CYRC#NKuqVwoPQJ=pmv)_x<`3Z%BXhCL2Q_WWh<)+|BuZ^l+=mlZI zG@ULdinyaG=oj@|{ocDk5Of9|)%^P4pwHl0Xv!vs4po92>O;3SPqM;pRu}HiD9)2v z_~biSu?yQ*;^)KkNMSwCWbZ?_*lBOxi#6DpO?(usU!ue_*SttdjqG>+9@% zI{%Izi=JJ|0!>rV-8D=QG*$ff87tad6MUG4pHFm5oQ6%xw5;xgAlUo1A51#=S)Fh5 zMwkRF&iM6sJ`EQ|yRwWu{(_(>aaw46`=-!(V={KXRH>!UPN(X09{HX9ur`Ny&*uD9 zy;^saIj=~;%BTck_72tbXX5iqR;7S(MIw6sG1bz?qVsm>-M}=O!usA|oIV{7+c%VG zifZ}_HJT$O`(Rtc3HT-^N~MoQ?>P4LvjxH8K}gZHdRDhezhq6xH+<@-N$U zTcOG30=2TPpU{s(J6UOOjz%-3#SidoGX!ss7|H0f(_U11Hy4dYIrsw7b7IhUZ@zGE z7pm#2nV%5ewd46^XucbgFSFv>1;+*RMY3vXqw0&{Mucpn(?5vu#Swbz@}Hm`O(sH zcdS;cJ;vs|WAxeSnz98gyx`)-TkQTpmA|UB*PYRm`C#eaEMest)%4YBG|Rj@qVdya zSeo;P(Z`}!-^ccsV3FYk_G!;~{v1mt%Q%4Fb?W%eYr-{ps_84_*9RXC!RHsJ=C2I@ zE?mu^KP|noq0wB3sp{E96~5yNBS=u5aP!H{ zp&vgQ#}^!dfv0_eUgx0KBVwgsu+5so{u%v@|Kx@CQ*gP@F73+MONAq3dKQNsE%Wmw zf5&67IX{M>?;OPHy7+M6aVzd%O!u2b%~Jny8?2n0WWuVne*$dL-0$>8sHB zH*^9Gon^!CG4j{|cO`scMWNveon}M#qI6!4MpGQo3&-+#OK$7+fWG7CJ5l_6m?-hs z<-aUQJ!lW~FGbI)iND?FXU5}y^S8mR33@)IX!w#j($VZ zXrhMR1Lu%jk0OJS%4fv_R-8$Y90yv+`{5^h;};_RGo_B4zWozh$^ZY)^}75X(xbWf zGqQ%qMIB*XLmy06x0E`}wGp&NvxSQqF!_Y4BX-s|fY-4Nq}4_?GS&R*D;NCxu%=K) z)Vym1X{+98$D_4OHSciaqUPq-9=CObY+4O^tm8LIaIu!D=2x(y@4=56hfZwJ5!EZI z!N+>bwQbJUlBwp?zoYI!dZ~eDT|@DAwJ6;LYNYsSM064Na8Rk&Tr$>AhIdg_lyj`zG>0i-GLx$QROt`ZeSZ*SoNc zS^rAIr4H=sl+?QFrthl(_L{_zlH@)JEl(A4OSu59VdJ5urXnp|uglqPp7@2M2NtftT{ zRP389u_L=~OPy|6axu7RZ+VvI5GCN=GnopSs=2Tw8_@2iS0w(3DraJxg-ACT-5C5^Mk7mZIB^Ru-F{ zmFX5L%w9HQa<{9}=YBR^9O&CbJ8p4;(&XF}3l)K0{LXB57l)BnX;P&Ka_HORh+<1^gvOUL?LM0e~7-ci$(J++f0Dro9eXocF^vsijm-+_yQ4Q*jp zn`EW^%K|OkLPgf73bn|sSh^KdCH_ud1{;1QC~XF$3xcM8rU9UxF;=pSM`aSlXaA>ZX2LP zXdD!}g$lW?HEX!;jx=;{)u*=kdt>;0EllZ~Y9t7n3S3~o7EZY(rAAe~+dUiqVday; z74IMeg>IqZ-GCbG_oEw9Tq`Rs`bKqtA7f*c{Hs@GDro9kx4)|Ixa*R(MQtt`*f)V^ zt41nM3=3qsg$j1Wh|OtzO)};+kx#l^lK^9#$0-I@3j{$^GqS&`XU(okJtL~B^QrdT zVb$PCis9`9nQoz?(Z^rv)#PGn_>C&@ecE!!4xX%ZD7`6BK~rw`%hhK5UE*L~^)4y< zvj=+a9;Y;Q`YzEeRA^d!R%;C@mSR8IbMa=NB0v0EL$U1|qP+gyhSl?ZFO@Vily9Dr zm}~7fQfM1v`BzK}7Pshybfuax7dH1g$wo$&iut!*3f)4*ymub#%&Mo7>91;BxR(5o z-siSdvMMD(&=h@FYBc`o`m*~?CndGqN1McIqZ_hWnJy7rco)4HnS*uU<}uD%!C{I+s`uHLPhkW+U$DY>(ZLoTKqX;OZWtjjL}M(ISPWN=)014TAVCldQoGQf?FqL zx`m2OH_Vu2gR7FmhpNxVhSq*?NPn_o!LMdeK~uuJQgb?_9X#KWphSL(k?9sHu5Qp{ z%YR*wZU7u8x{kEd6()N{sBe1T?*;D1-Kl)Y2_fG>k7-t0fgn zKTlQ(x1nk9>t%ux@o1S36*P6ZS-IM4MzQp*ph^_ISOz8E6O`Jq<=%7)6%Aa<)nvXe zi7c!V`9^7=tw>O6M(F2JK~pOll&dfKbHrb&65A}&;OgfDWzL4DxpWH^Gn$sG!?~FL zKVp0BG%)8PbJ&_ZDrjoBUAfvmrC72rs(Oy`4$EQD>_8@>aNUf zZKu#JRM6u`jb^U;P?}gVK>2H8BnXfD6f`Zr`sFbbP-Ae3Uu^YSl zXD4>+d-mc!p1JRT^W6LW?CkD2Q)go3vPELRf7vEZ|Dgo!apLZQlU9nm!x)(KyNy6l z6|E)koTB>nO5bUtL5c0m=|7a9{YUIy{fJbiZW#mKMbb0At^lUW>JhMiG(0?c)_C;a#Tt#<3 z7Lug2AWBdbttD`VH+HU4=20wUZ%YcI|4?E`a6#^-vFDhgudnVT&sDzNi-jILp4X-X zRnb}k&kL_LQyHE(3QBhymNTq)LGE6xWon%(%V|wS>lhrdxXx2fW9@UMVfi3RP?cEw zxLM9qx}J-L=|9W_f~s;$7Ub5&yqla=Yq*$?3zU@Fu~2Wq=U|!#Rb_Y;W1&Yz z`&x9AfsyUG&w@i^-C$dTCIUfKHnSaN*Q_UO`s8Bx9K6fXki*OpqH;P41XaBSXE}Pr zOZM8RC=$;{oM65sKk*9@Jp_WPCLby-Ppw$ME?zJ~V)f7b+>8q*uy1M?fuO40{XFFm zmp9Bl(in-O_Gzqj*P;;9I$R*AiuQvg$!EhfCF=4hXf-q}g!ZXvZ-BPil60i>R^`Z@ zVX*qZ27#a|+6JRN(swBBf`-AsZ`%ces;D1hY{`GUQvYQP*xy|u5L88d0oUA>8LaGn zJ_edQl$L3^qn<%MMv~lp=PBb(#)8@4qe1i^>WN|*Jh2FO)?~**CEL|O^dCylvVv!^ zPMfFH$&Cf;8?%CFnV>34V;s(-G%Ut1E)03@0|Pq_kZ)9b$0{wc;0prcv&u?Q1&Tsz^D3(VVdhoAdV8K|n}&*AdY56{@iVYUWDxU&hgSf9^Z9sz-< zv|+Mbu;Mw3s^q{ajdQ8{jo@y~Yo6Gp4p7y>!%1@g&ktGXD?_5umP`E5jT_wFDNG>3 zKh2hn7CvOI-X%GuC23#YX@3617ruFNW1y4tQgKx8Uw$28`grGF5^nf~Dd z@$h1bd}G5+Hff6sr!+>@B4%;F6F+#T+;%`!zxyZ4W!7D0X1S#eh$e5`xcP)zy#AR! z0@1Jh3i-i~3+%+YGMv)*Wzqwd{PnS~JfcW9psKt{i{(XTXV~NWWeteuixz|!|GvPF zM-LE)n9&>LE@zIj4mtv66r(LI@Rg$ak4dv|vOqFuR{^0Z-x zdGv{a0@3}_4%y|S%-STnb4p9ne+8yWN}W6We0U^KRnVW!a=G6J*h6a%10wdzP^EH( z9o*zde}T9qACPmV?`G#?%5zF%U$or>9sJ{rZa`I*Epz1lZP&0R2Rsdk?H~SA zShpk|Xd59A2iG2xOOIQ|Rvjn@1|Kmr}Y+)x5^W!%6-Q`x%Q}stmhCrA!d!ys6nrJ+&5#` zGpe>g&~isR}^)E33<41&c!D;}d@KwHLYx1TA-z##!WAQ)IX8mXPzX15niivla5w44KWW z;K4;=%9ff+{Igg5d3bk$pyiIzxcIY8s8aG!5wLOY1XMLBV!h0I>|sa0dvcMO`ZZN) zb@?hkf3&MW&~is<9No=cu9WEfimyJ`9;j-0x9#%k>6=)u+7-A+w1RWW&fYTr(6*yM z&~is&J9KSUYlNcrtwA4}>zaJHD ztoxI=hu`hg1gL7oDOoljm%=7mR^%d)7PpiiXx$0|t4lyW`CvsvhoWA@6&0ktKI>G9b3^8o`~rG=;$biVK9ixv$)=)kRjlmouj{ zuDWm2gWC^o12dQzP?cTJu5$Ux=h&%cI=dMVD}S~K*|;$jrmrh65VOWkl2^z_S#))G zPH9Pscb$`SII1PYo^l4NI=?wVo@RZBwc6!jKpcMbM1Jsx!?NEM1tLN>TaL$eFz2!- zr!=lYN;Xm=5*oplPGy0rjH0H?cZX%OPGc(?5H@MCit?id9BWruAWGIwm0#D~%Z!g! zQ zmGI@1#>n=5Tix|^JLr7H1*qzqx=U+~l=fBwy5vmAk{>TTIAFRn0)wQg0#fXJNKm5;jG9s1mRD3nfG?&$0y z_OJTku7SuNaPq@_p{(g<){|d`=d%?vOLCED->Ee3k<(ZZ{N=s6?4ZlMc9PSQJv0qJ9 zL%-m6Gh>gkd+*%2NQ?-dAV2hM4{y5TnP;RnpyiIzxGtmnD!HCdI2iXY3RGp9F;Z^t zqGKP&RNx{J6ceNznA8Hs=GhAbEq9d0ofc~wE9=|0g_!c@KvgwEC(AL5_p{vomAOb< zzpz-jw5cAX4|fy@TJ9)~anY<5%4YAzuw}U=P?gh|x$*<+?d*N39~TMpqL&qUYYjMB z!9gHsxudisl~{2VzqL~bqz9HjRX;!_AJ4$0z z?VGV~%2qss{){oh+vLaooa*_C%S4!8{qXbMWV<`}{+)*08QrXl+cdV`p zRCrSisLCy3qx}5z0(Q7|H7*iid;E0oD;0wt$BPOCEwz-Eq*iABy7_0!pl7NCRF&Fr zr#z<7bT(;pH7*j9+P!1vI}V2N&2xm(NlOu(;m5TG+ut*t^I+J}FIOmQ1Iq@=Ry)qH zSD#C9k+77;GykxDaHaSSfuN;`(vr0OvOinQDMOY*GY2*p^VwM{h36nAw za_7a75P0^nK+sY|Y22}1yN&$YcL2s3E(m3fhjx}*`5$H#2<$wMZVJ!`|V!@f|epm(p|&+-vS)mc6?M z7m4`w9=chMZjkx%sX)+DL}~ms;4u%~`=9Pmr29RgtXWoBFE{BmpWRBX$wlHsnLu5t zsSR9sa9bc~siicop)Vb%Yca+SE|0y+sp@|3?eeHnp`9r4_h2EtYs_=_FN#8 zPFjlSDjQrgIAvo<(MuztXWbN`tTkR*S?=@g6sx+xm5apPjW2U2EF1>C2W%4vT8b!* z^Ujg=W!K#!VC~bzLRnj$6D)VReT;qTUY?7@%6)I;)PljVsoMd8prwe?k`x?ard<6q z6xuIcBb2pgx5H$oqj~Iienl=4OJ0R5d#^>o@SX<+f|epm;}=6N^i#~P4}g4+twLD~ zTir*Vzc7cz?e^s&aev1urNrxQ@L0GNc5R& ztgFAYA)MWQSRiOAqBO3Pd2g&67tk2mUfnO0wbDZu$S;ysvsr5bxk#|L&br`RHKD^a zMIdM?qBQp5zB%hkc-Drz{(FV8R;<}lIqXO}A$DyHW76XAMS)rQhx3>LX7v(}aqg(pa~@ zTA@t6F&x&_4HJke+bYWammgy}{k=J*aV3ZODy7q<;V?741f!}3&Tew|lgC-cULOPE zyvIJ}_u6O}VKrSK_Qx}M&5Atc(a4`uT9WFnm6dYJ5E!~8BZR8X)$*4|E;+(@UKImk zaf`!>b-lsh8qtMO;%sd$zqoyn9iLO3QyQOqcsBK5lId-Or5{2xapmIXQU~+n*84DUFM~XFBK{m$!yeb;dHP3iX>J54pO5H8rVg zKx~;*PB*edV{o+#5{P|P^JKp=tJok3t9(M^n(af)bYqm#aDQGawjzA1Y&|ZKZTQiE zmuS9TUhX=LEh^oRyP9m3pEXKiPT_UYf*)d==sp*5gWR9SjH>oM%amP?&SFD4)HNU; zJp$dKL~l^$%@c^pHV|YbW?TBU7IrQU|$hege?sKs-kmjB9VE|0muK-_>bkG0 zx*WQtfNei%FU;fNw>cKuL9;%4c(e%sRna*%nx7;Yn|dYM3_tr~h zH_(YwT9OvVf97``ck&W`VL(-Mj!h&+^*zkD?%m6mjSClu%(DySLmQs3kylG{O5=)@ zaeMjPi|Jf^A%j^?;Z*EthDmp7C=HXekJHIh(1Fzh4 zkU)Igm?^*AbB#T@;>szF-{v^nl-E9Vg6}hn0;;03av~8wcMaPSyqagcjS+~{23uv{ zfoECquVp!<@k>q4L)gwmd3@&d!9Z1XR!$`Pm{gNH$1LVOFOCohrw_a3@T8;cLUEio zATxis<1oFYe9e0^fBSkEP!*k(6N!s^%PAQaDLgJcMj-Zg%$Aqdk=dg2$$SgWE`8slg!AwGag`Q8Rdgms zBzC<^QW_L>fUN@>3qN`3WE&Ys}_CXHJGRneI-njfz6-uo^%zIz22JFmV# z1o%#uKe?V_sm0t3=G9(I&kwm-7kBRrZw^#NXZUD-XphCV-2Fyncn}gS5baxzm))H& zFo$BL4dw?uJg zXT;O_+@*Rs7;YZ~R7Gc8X?|G41?Ta~Q*hmRmX|TBk+^fZJ|A%nASpte=cF^Sl*ZMD4jp+3$3Wck<0H(z(h@8Z z&KEQIGYR0gtFu7R8D&aK(%_AmJk_fvn6z^jW|3(L776F+r+D6+U|4m^S|I3-LrP=3 zq(^<-oZ~K_B#q*=>TQ)yr8$&o9t7A<)rM_+`dSdsOctJ%+ z@gmXhc{SbRWFL5RalAkbJGWT2n~=to8^H!K03*-py3L7|!8&X*rz#qap!wlb2(Mf=n&0MlD6!4ugqN22_`n5BoHkp zjgXxacC#`=YZ%0q>b@#aW?k<9Q>Q0$s-jUYnjg-wlsc;Hjp_pj>n90B<6pQ}+&YJG zy8we2ng5tPW%-I;;8-V_Qx%QY(fly(W0S57m@ych9~&hQ4*!M9lOT@;{H|;e>syq# zK*>2j5H>%U!>Ni!9cg}&H10{b66-z!PSqMH5M>jq%H|D^vHG373}Tj7-Zob{#Kb^; zgXx^AX!MlkCrP8nSt%uO)qU|s5dz^_(@pm0r&ymhZU(VeU9(Se-Al1hr^EzKRWu4r z^OL0MdsF0*7vtdZ?zRF!W7Cwzm1osDD&@b8f_>>80zsdN#2{AT z1Mm8k5F#nGrWT2W2DNoY{cw-_=F$R@dpAS&Kat8xCWBBP<5?CXYU>`o^M%entK;^nqE?OGO-!-9amN$ zXuOQlxW0XNNnNjTO`-0hDx9il9V`;38<^|HbZielx|9v_+;ZHSSC8ukgB70R7ro1O12g8R!}|N$PUa zTPd1{yUER73(<306N%-#+l3qQiqUZ}W?(Z;=u4}j^6wH>+ zVl@6qee6k8vfL?pIosZ>KE_MRI91Ulj}3yuzdRZBcB-N@j*5m?)y-Q|3#`x1V^l?H z8u7$+uR}s~+17qA^`JeYWt*xfjps9Dl~cOaPvQIL#RzM*X}pBSXK+>V+^>As>@qOn zGp>gtXJpXv8TB_wx>x^)68$zDo@}Tr)K}EoY2Ae(8*1t*WyVHFnNVvV+#@voDbG4q~Rnfpa^ej$>xi}v?fr)TO;@7-%0dEZhF zz^jD;RY~q`SnC_N*`7dC17cdGLA*mBa|pQAN+51L4`(jx&$D6bUTs37@9vw!d6XqA z+0hKBYH!J2Y`t=oJ$->Y$OXdZ%m)6mW>GlYMkE?$4Pk!kL5r7 z^MAoWRpnkJvL-!GvX1S{3!stW_-?`;NQqMWRzPXIR+iKi+bVk3j4zKA-ug?O>5P=A6>_4e0^pVd2`R ze8cc^Kviq*B(rm8_OJ~tO$~@?I4;Pxzrp*ul@SP!gNs?a^_gsUKQm5goGThy1A-6T zsbd669ZyeR&|(F?E&}dDH6YzXR?_UQ`oB+W}MQJRJK|$41Du| zU&qx>RCUyLJ#$~bl&vfl)tVPyvYNf|na8f3 zR?m8QFtPz8wJQ!y)-K~zb?Zkub3DJ8rQ(c0L&%>Om`Xo(UKlMAOsy4fVnCy0fDG`na#KRkN`Q@qYp<>xD0`Z|@CD!rvS!VXE zIHxp52OaCeyN(qgVAwZCeY7KFu)7n}*{r?xyhZUf?5xo&)-+N*(P95j4*vgDfGlfE zPE~ntGuZd!RJJ&`h)Gpz` zsVZpFTy}lhDi(t4^hM&-d>_~gbztI0Z-JOQXA&FRY75K#Q-V_(YwF!TPy>nDCo6EO zn&dp0O=X+dop=`m!sD1LIO4fDI|kJeh_TOxvRcpguznq#Ii)4(ZLTX^LL&TD9Zprt zTMlC*KJH?BE4UgEKUZ19YHXR;m2M;ub)361IX9d2zURy-ji-^+v<90Qt)Po>Q%+UY zm2NEO=>g{O)YX6(-u*XUXxbSnPiiF)FG@9MEt(u;H@-M?O5=HboqzH{jXJ}8+$}^^ zM-Mk;Z_^akyGj`YVj%7|{1es_y58?75Y`^G*yZS>?D%wNPH9|i*ybj`v8N~W-qC|o zRnLVr*!G8qS>_{G17iH*ojmH&0N7tWTp(5-a${3}oM7@W7fxwBTm57WXn+xCqg?|T z^&jdPqb--PB1S2!T|;N|_GOQ2K zBRnfu#i(ka+=)4xX0r)F?p!4L1^(s-ws(W|onr-pdIqH>NxtxnKUca#hc$BbOkBVhfRdZhu`@BDoxr}k= zB2i)I1@5x5Ka@;fArQBl`>+T&%BFg{b4ueL_snWgxAFo0Hn}X6yR(ArE3$!o%s1v% zR!dpJ)vfGt!=eWLlJx8f@GABYPxA8ys-k@=vF|e=-4j~9*v@B$R1t_>Zj0E#7Fo=( zOfiH0)v>ar!MI@_&udT}s4DO0ELLEAguPS@iS>cj;JG1(hvfrM741#ZJH*wWSBpaZ zlBf7_*ZKmnW9&p$v3x#T<6>gav)ml;f*)FNh@U#&5~zyyacO>dqC>~a{KS+CJl?jo zK*Y9>WgTi>V|VRL40^~vI_7Yz-e>uL-#Y?T(cV4H56^FpPT@T^-{nq@;Q~R&9F)d2 zEDx)3ivf4|$`QSRj%6sZ=vq7WZOvn5`bIqoA?>g~?{xe&pK`7@P?goF9_+lu1D2Rj zjEls+mZ`i*|C`*UNLPWN&qQgAY|p3-t8f3}oj!iyv=>f${a$hgd)a>_n|(oD@8kZY zDuh^m@p+A6X3cth5veI(nhBBn`B82j>^Y@Zz(h zFk%U4Foi{z-^Xrru;wCRIm!`!U$cf%kDLX9j>0I7YrI-m!9_bOaQNyjjJ)1&h-F)w z>DcQ>)?6f9C;j4Kkxnr4n5RI{(IllMX~4qQJPFT@o^0;S#Alu;4RMjxgt2q+X&snPgVQW0)0&IK>ose5;ua6^ zJu4D)bWdqX`qm(sUmsN-Zkf~;M)X}18nQ*(&olnoii%A{?TXUXSwy_m@vXhOfvfI}$F^ebaNo=3CjNu+F z>chniI0H-i(e%0^@n*wDzRRmNoM_=H5VQ|ZX*}^H{s1@GUK=JymISJzPb(5%?_T2t zodQ7qR6-!=ScK9zo3ZB+KeRFccAYN{R7I^O62m*u%2J5-3#`l@8JEXm1m_LPch5!C54{s zoy}fsWX@^U9V2iUvn;=czjf;cyKC>q9k zn;(XP=cIK4LB~{-mLwKn4c_ZRAz<4oVH`yx1tKv6>)dz7!SJ%r5`my&LrP21kMm{V zwlfmHQ-tv#jd+NJ-+5nX(X0wcYi0`s9ph43k`AQ%L2}P3aG>#YVO&ciHzKhpH3%NB z_JCP<79G7V9jjAXlCF6KgZXn0NK20q#^*EwB@)HF8^MlPXJ}y&ArLfzKxs*Ol=g^q zEB~E;nBGn3`;;r)fIWWjh`sAu%pivR{!28g{`M( z({e|9HDVcDIK2;d>Rt`@XZQoH!)Y5OwjcTSEBUT-oglpIeIb%UBP?PWyf(Tn9GvS7 zPX^mE8cCt!PjLjf@R-c+bsGY9J`uubA~UiKn>-TtD8`iGbYy|^gT)SVSL1<@d8!Pj zDmr?hqhgFL4N~}vdPBf>Zbz0dqBM(1I>GM7mlLi_uY@N}ZLAIhKked+pOyt0J*A@; zar`lT>m)WT=ORCr-5*xnY0RvCJZB%gi*jl;YE3+2E43cKUEmH+LhA~B20BkcZG&f$ zUr**yJzK(^FcYCYr~LR4M#1PsNkW}S>tOL+E!xueXfMF*@4`jNDm zZOod$=ACpFqFg<*SFxK}bC|JDW2~vq;0d=Q(tO}Y{fKP(54FE&a~Fp|j9pcS+U>^& zQ-Z48m(F9^HY@+;vHW9IsAE%`Ekg?5?wh5F;2c$p4fHt3=s%R0<8zhWS>zI; z(s-(4p9J8m&G|{YdNL)bs!{SKcKl<;U*hfF0Wdq`JpUPTC?q=cB)c=Hr2d^auRp=Y zZ+2nobq60&*p9?Tf8W*UhXWwVEuU{OugK^>l(2O_$h!N~)6+P*yVD13!=K|=X=fHC zsOro%nf+PPj2T6!X95N{?F06UUt$VK{O9aU!Ag( zP1-;F?{gHBdcf%ZKlsjdP9gLkO02Az#nNYlGqVi!>}cQZUBLZ-2|Nif52gfFy`H;= zZB8A)zISv*q5w;5xAV?m_3UjhEm73-AB@|^c6J-fZaJxE{IV9!!07?D&?dEl=|7a9 zc}tSZh<0Gz$_~EmZ<0+3suJ&NzN-mTunos^SWSYd?^1ug_`VrSOOyY;s|_Q}ple2F zD1LHdF#U%TVl?V~^jBW`dJl;HT|0{sR3*li!pdId1vC0XvuU!y?xUVh}*0*aLLjR$J7>(Na^D;kux<7PzJS~_KR3)}Jzuqq8{kD#P=L_c7p#*J9 ze9K%785(;2?_Eu(xtcG?9}X?Mjt!>&P~uwVi;!Ut&#~@1Rp0Fe1Gsf)92B`>pF;_% zN@%<^q}ZrStVsve6MrlWm6LamhewqxgTHyK3L0Z_O`m(-XDNG?`8C$4jw{d3uajH# z#Ff8yb-=u>oV9U0x-C3AsTwk8|LZ`p3 zxT`U*@@ZxK_knPB-i~1U4<+aw;#bDX?o}oZ9}2Vk^v|LMRf)SZqt<>=TL0_;&4%WL z(4B=Av!dnrH@ozAMc10(7ZE;7x#k>0f~v%Qkazc2)orn_4M!UlWAwUo1x#$W<#PA9glR&^5M_%fA4C+ zjb^$%Uas)FtZNAUhZ1yuq$FiD=%Bkj-x^|O49cYhRW)CJKpr(Mf(^ac0Lx&mYd_t< zs9SvN*AmPnGFQIbqm@4QI1in?*fx|sO>DqN#T=JI&XxOnS4$i9)BU({lUMUMXY?OR zY=3q{E_TD0*}PWQEd`tyqT4o8=E2Qkaw$Po-jh$s(keTaHc%x>qzu>POMzW*7a3%s|OpYi+>O#h+8=~DS}@8qW;ML*QTJo>F1qwDl`1Wz>H zl0ylqsx#oC>@aC(NZ<^WC~G%PckFRBOi9wxE0<;b8c@gvuXFC$>wwN!rY#(YKz zstS5|p0(|K=I^^&iEYP(3X#0l$a*p*s7mbhh2jc5>j8nhccj>}q$*0|y1to*_`5TM zVgKpu1GFWhZKBw6#z_shRqL@Z#C(z14w9B^?YUkdAN{m8s+p-Jf4(vSj`ymOL)*Ks zrlmp}Rk_N(Cb)8u=(ceI^Y1hsj%}GHw1ZSdX`C_Pek}Cpc$l4yU!x<}rR^YXQL&90 z;G-PvJr3e~PYkB*AZ=x6>x1WbZCax^L=A_L_vh51EdXs3#n#}!pzBJTBK={?soWr1 zJJa?`tf?n2H_`1Ght@c>j=@=gjXiV?zklWF#fIim6|GA|qJL_8(0$v*OS;|V?)O%(S*H&% z|0bWA?%8Tq#(f_P+wz@Vaazs}l*?yJ4!>oRq%>&(~RHzS0^f5uCY&H5#yk%{`0fF%cS1*!W8QECGwYg$Tsi z(4)+A*hZFK<2j==e$VUu2A+t-DkP{%O()Hk*>~R?2ExC(^&Mwjis&d#mKH+YWOe~E@jP!+WS%@3P^*EOJ-+jpKU84HB! z8PDWje38&0 zK~-ux!}$U0Xun5aKK>Doe{h`&p7w6^t)f7v<-B0RHMX;itS_}1jVl_D4uM8tDg1hs zf&6IubXKldQEoHws9=LC$I_To$BYlPmeEV<`3-}0{`2^}tF84m*DR&lx%l^Dyy3>3 zOeECuv8^8NQdqfCAgI+SjpxH5u>pyhNKloU?(9~Ccd4^ke}`Irg*I=|!5++pUJ(dt zHA>^`D|$&75{^hvm6|T$@tt|!SgZFEEk8V!3vGU(N)=c?`Hw&t+FYaY457coP9&&G zO-Gu4WP8u9(tF82;tbl{qFw_y8CmF8nr#hjuF;b8j z+<%q<@%S&nkx+BjRP;{h9TvW;KKJXuyU=?Aq1wamvoU}0Xs*F?sBbqCi2@|3idvB7 zCrR(o=9L?ihPUIh1w!=4E##<_S#5vLxQSknV|Wh%@^Z28Ksl?)|UPPk!YF5irYKz8ueBfl#ds^ zVxZmKWZryx0H>=6Cg#=ZpY3f&+hf0##vrPF|9`FbyflzJG zFVu#|g~jTUMWeBk(h==QzWR0+Mni! zUqo;o2OZj%;~CSJ=)FX{Zosb;W*_Rxw;E3qya)H6KaU5?xElQXlx#*-7UNUdojgZA zd)0CS;=jv@5OioSYrWf6AX?W+W!A%;`MX^U8Kv>8$;@$Zu1zWa^v!7Y=X?rtIq1f- zuZ|GzFl%QDv$$WL?|j-BTeXVL2{7ZPEsygI7gXw#yWT6yhf8gkNT_f3aHHjXsBwWn zP}@*ilAa-P3W>Q$P?ehY+T+X{{MST(B`rVPQ;jws^z=9H8d^`VAoVdyOOo0nYlnmz z5>%z8vwR%*lO^@^d29IJNg!xhp)~G%!SYcGi8LgrN=@IHZNtw@3)cIt zmS171jZvC`RaS;T&@xYHNlL*|I}!;OB&bSF-?O*m-#-TG%b=EDVLN!}OD}lVezQQR z^#`qqG#bw%!`degiTg-Um74DP!i;;Bt)Z_={t?kB&)CjOLm;p19)VC>&g@yn-1}1> zeGRA4_*LD03Gn&01@D~Y%a$xnVI^04@y%gOuyf$N6n4_so1ZA>j-JR4B>+@4;#2My z7gVY*ML#Z&Z?_~93DvKb|6YwHXP-b&&!9A}-$h~x5>t_&Dm6VC&o4c*wlHrkKm0N& z`c=KU#^7UDSeI!2Lp_7ig`NmVcpyPlYP!;s68vI!D}CNteuaKDD#{;94`?6|)H5hu zSnm!*;$i;=dcV@VK_xm=vggY`o9aDL%MVYvLBHB~vNfzO7$6Xaex=ccJ^gh^EJA{+ z)b#0e8-8$YQN1VrBi^B3`S0lu9lB2x2t&WpXxwS>m*|89RjKKgy{-6(R3p77{v#ew zIM03r#ln-`GXz5Q#Ab>azg68=?}-{MNmD;00K4#$9jtUCr0=v8_S2{`KQp4J-eWX7 zub-5{zK-(YPd;4^k)-xMiICpCfL%McD}?%wn!dQgiyz*T6(SOOE2OA49*=Xgo;=iEc>z7+F;BSDH7d#P=nR{MgEM zAvC|j(L}gU2e4jPRv--hN~0xdKKgDCBq||6RchM%ryY--zdD5GR~RYknK}f5B8R9QzSwk{SmxDCDzO?$4}0Y^jFgI!xg{i zS7UaXLVKGqy(en^O6^Q(JYfTgNl2VSf~wT?@EjMOd+JNDNT`05)UpP2ellGksGTW| zZx@M)NJJq)Rcbo_o)fQNTo5c0s$XT_>;!p_G6jO#nbNrS1BnAjWFkRTYPw`?d%ns0 zMX*R@p%fAgoi-V-$%cj|plfQI28*$+=Q`Qf4z*7sQj?s&^zRy`x4xd*>D(N2DwnZgc_ z^W=+Dn#vfzib#O(xFWr41!qB}5?cnlapQ{342T!#iSOewxzm#E0-@S@*hg2s>WPK^ zca6pqv;Gn#kf16x9T-xIKWSOtfKa1qb2E+Mb3bc^5~`h38kXejZZZ9pG#Y1qkVr-1 zH4;>%rf+X^;ENjs8xU%|q}vOB*!?J2AXGb_nrzRTZz>{Fy0A{{j>H}$s7g&gu(ajl zd)G7|CZJ#K=+_3^-t`m+)y^jGZFpjlU%8Yn>?f{7q8<`drKV5Kwd7Wx17wk~!FYR} z$N>ys7g)uh&1QscrLO?*s@pbWoj&3d^$-W zR8JgU!it|-^C6eg7=i4S02N!C@`Vu*a=im7Z0Ip}?r@=xVCR7sQ&>&>u57oY1oXsn zN5?@6A7}oySr0*_dZK$%7rwmY1X(21)_M2y<-A_NbAd4QD~-kxJrb9YsE!0xscBtv zN6spZ(O>Bwq4pEAUjN~xj|J;JQS&(J8I&%pMOPu=i3C-t>6))>cpsmk`nsp$Y)Q+~*(x84)A{0jXl>V9wN8M{s(sAo_bXWY?uyC5+d393@lnV*aD zM@ilFo~Y#~Nr6_En33&JSkZU8K&YNLz|V}EhE$g+jVBMU9S5iU9eHHq1+w%Zg_%t# z&3iPTCD?g^ODZe!xg`HMDGfdGjMq3AW>b#WGEWm!swdWb>A<%;E|o<>ZJqO+GI*I- zJB9iy^$bcE)`_c-D2oJDsp(RFHhg5URDIrBeuaLuZsuoxXKjChpq@eL!V!y%#7!iq zN=>&jG3PH*=IcFC%MZULgno7FvS zIsVc+S5T?G^q_|o-+O7VED~y+xY>LG&+zfld!pt))H5hu7{%F-#1bT^N=+YpWx_L# zY}4nh>_(ys5>%z8oj<%| zmv$}Hd*VMr8l1xh6m*4hk0l)?R8KTE`^s#u&eMCMM&k(r&xb*5!bBc;ppP=9Ya078 z-H2Z?%GcZAZM9!)rQ0!i=KeIsynnEa8`sejPtF+zZ+=bY4Zil#+gwwrb{;zY1$+18 zmI0xTCO-T)$A3oc6bRL7;U*v1(|3wKKaDQz!xjH|jvMvcskgbNQi(ri4_V;bO9sSS ztbKk@GKa=lF9kxinnkx)tk#DEdYfx>;k?>ABtns(Dm5KiaFbnZeAa+aM{jeD#xE}tf~wSXM8*~7-{^z^p{{@^notXNHYlT`glbJ*>_4_O zbEn?s8eJG+F-Bqs5>%z8&osHn=2kvxK=8cd?D6n=;C0qZAXG2eVSR=5zOU1JiALjB zz%O-ynql$0rSlu*ip^3MoVAj@+ianK)3z^Gv7nMgm7w=aS@_LlHuQ+Kg0ZE!9bui{ zG`=V5qo7hP*fDDcyL8;bfOw4-Y~E%&PZ(ELr>eB;s&9Jt<)zHyzdw3=Xf($9kZ6a* zcqFJwP4|nM!lDM7==1(ZsBZ+do-3^sG^H@!VHx^O)B0EvM}P?egV z={1pgc^T`y=O6JMEx7dcb6#&uJAqK`v1e5(J9_k!-X0n)NoLqaE%-}Nm71PdE{S=$ z7SY!j|A@U|N7$)NpLwsJ-SrmKuB%#bUXl6i$eS;E3u?3^&EDGy-dt(NPt5iB$J&~~2Ep^-os+C!ry zX$BIxNMs;ERcd-`QhU~Hu$kV1{|HO8hiA*fe1>&5fiSd(M&k-Pv^hg!HWE~&rpMH1 z!`g+J=q>n<*l<0E%`JM4FY+HC5UK?`I}Bnw4;ks}e2vDh(OQ{-X_+@T7uZq%S~;QxQ;kib)c5zyq(>+Hb7-pnjP|husM=N5 z-heRca*BUWbKthnUm)7l)UjPi+$m$HP+F3%b|cXfi5~se>7yK)N+q-ii%6)oD8JYlT*6WWLiG}O@5Jx*&DH0p z(S@<_5F~tBrs$(Jno1?KND<8sTW9pd2Cg;1YjB)EsNO#IoD27xa43h;g+xOn8X!Sc zYFdkUi9|1K2W?uKL4$q40-?5?eOH#_-WN{hP`WUx=8D8?IanV((^M*f3#F(G;d{57hS!w0A{qLuouY5{UvNdLuzqYT994DIRcsxjt_#zrykPx40V6 zL>Vp+s+~0-qcon&iGK9~i77}>m74atda9_F)(JNJe4lapNRdVt&X`n@*YSY51N7qz z&9>BPs`qH|%fi_{CnSa;K~-v+Mj-zYs?E(Cnn38K9D$%VpmgCJizN~bkf16xO(T$6 zeuXxF)~_1uUGPmHsMRQ4=vQx%ScwExsc9O4)bcB|d5@G1;1}tnZ@o0zs$QbmfYOqb zgkCZViMM^6^lgTwQVAM?)bhg_UbK0-RWz(msvr=CHrHrLvc;Bj1`=zEN#7LFvM|R5v7!AwgAYS{nn3L;=!s7g(1V_A_@>E}%H5&K0BT);9nn+NUn$||9 zG{3@FU)wGUFYr99x1e@i^^ICcSDD|NxB5CpqYKB*gOT`x1XZbNZG=tp!(RCEXz+=j zz$?g;1>#njbawZ80UH(c&|tK!t}oH8bB52Ig7p^s^ma2F(fz6ZjUHdSjX4*6skfkJ z*+QG=Bk=(V^(|^DYE9LG|A=(7VBBXjxLLwmAk_CW*myUydsHBJj3lWxPekGt5>%z8 zHQUhq3L{00^B?hyepUjZzMq@t53qN;zUnQg(SU4jUd(cqm6`BduW!$6)8yU`Ablhn%1l-63fsY;rHJ2 zl`E_3EvQ{reLvcWp3;(}+B_18RY*{knx;0_^21FKSfb4Co#M|dN(hAderNr)^E=Kd(N}TS~hwwGE|lcP758Gi8_X!S^HeZ+CSbtPYZ7;5bC{8aIVP0 z-0k%FX>{R8cn%Uvkf16xt&M(Zet5DG&H}_w?9Z*H`v`>kw3d^6S(CGl24iP+h3N_; z9FU+YHLZ=}X?}Pb`@(jx&7=fSGeYz#WJ-a7N+UG71?U0z@@5f^X#OG2Pd*M|RAt1Vd`8iG%h`|$6SfGzD z4{EwEm(r5tT_X{OynoFS2JaDwnp09(gA>03-rP+LDYMSnF z({|KJ(k$Q8tnV8OC_A}>K&T$Bsa($;V-52cvTe>^m?U}T2SVoZJ#5{Hs=Dz}YuSE` z_0-ICR+cTzWb3`rIKlQ|+WV1>zE0FiGk*Ugx)`3-?aAlI#tVe{9GXhKQuhHLL!66S zVZ0$hvgWJ zdJv$`L)%3~udAlDollZvXLpdf{jLIu;k5X%FC^U&6B((9^eZEYNW`MpabbnwJA?%~~nX`GU-tyJ^SBA${|V~Y*n%Mu_m zyf#zcj~2nE*HzQ~y4v#Fk%O}(sa@AZ=r`>t8*z404sDBQerg_C92Qq*+F0^_)e@lo z`oaGfBh#*{=Ap&Qu*E5mS^A?ysG780h_@Twp+-y6v~NcI>->0#{_3HqDlOhdudAlD zXbXNrAwL09CP@7LC3|7*AZ?e_=lB;@`&1l|C4<2JP49 zp{*mL*HzQn8VyN0(q}9fFRjGm%4Q4eGUyr~H4kkq1+IV?V9h6F_Ja0JpX&3_)_BnC zs%dTZ9an$ej)$s%-}3T(D$hKa%3hqa2B#p|q;Z9NQVPH=SooaI}7Dn$xO}9JslwCf&0rT)UG7JXTPvbw^ zbrseD&^u9UYAtFcNpn{ZhbbGT@)qlB>&KkhKa>#fD&UYMANQvr%-rjyzbh?rNAE;U zYje=p4wjTzw|T9g`ZouGFnp$e&oORkG_*{cit(%Q3XNaTH4N%=Xps=yy&O`MZ=PQr zd}FHX^Uz{Q^iI^YuGm3V^wnj2S3kN90#ly}{AuE1g^sXiK1^rDSKejQJ{1^@wwpx^ zf#OXj^N#ms3K14c(7VNNdVd=TxAsQyCC%0=wc{4ETJvSLwTrPZy1y5^ge?!-&gND# z#lFw;sr_M1#CZPj{bqrncc?zO7IVO!e&sK0yKgzz(mYiEp{nSc{`Ypvmg@}3b7%0W z!(R()4d~OVJu+<+E=hamc7?@v)A&S(Yr^=P65^BZ8gIh;Y_))GGu!L$N{fEbr&ZJ1 zTspSS*;kl%x(%#<)m9+r(^6WJ94oblyH$tr{NhGBI^#~)NvO}E&8y@1&^TT-FQkT|XKe`cr9b~1W<7GN8ujcV@?0o0G4L6&Qrw+Fmtj|M> zC(!Gv>EtEV*(@(J^s5>*!r;&^C$5tmbbCBjvAo6J>_W2=`Zuk`0J?Tw&El$>GmjA^ zkx2Wm87#G}#`~;x5(s*S>Ro9xMsaW_Q0ui*`2OW1^>?L>-07XD>3==_|9a=LEh{tm zl_4<#q1uB!)4%74J5n9Yru|_Rv7FO!4ZU|ddcp4kxCX%i%NpGJWhG&JP6_cj9=trt zx*i+KQSXXA)4%7Co$+jSzp{Kn!&n`iWmgG}rXwWWEqe`5TSzU!H;f-D zrz-h-|tKu59;o0;C((BL5;E^pg6Dw6H(`v?+5BuNq!%n=n4QQ%a!kzfE( z!~}u}N-!ZJ2r3vcC(Id4AO-{#kyBL$j3h+?a}F3V6O4S-M`mUh@65OE-?i?Yv)IqC zcXx$d)w`>!IRdJZ#R9zFN{4LhmcWPxvCABHxy+@zPZ<*E1FEu|=He5Zw8^TF$BbB8 z)YtK}>0G+(ToVEg z8Zx5zfWev6vk|m$@EVSQD&O2(oR_XiwqLYj#P9bChy2geX-xHDj)1DCX9wcOBkGf@ ztGpSZ^5~S~xG^(m^y_^DS|G8nZ7#0fuTI+C?av7IFRtsfsnl-58IFLe!q{uTN57+) zj-{Eg^!62jYge!~FXU~(9lUkP$nT9Z*e=cUhKPEprlRD`YRM91E@PQROY+z6hNZ2@ z*_wICC~u$K(V!KJiE85pi@ma&h~EqxF|`ocrp>i-R0dme~R zI2Ov~ms)W&PsBw|7ry)`60&^9Q%FG7mw6-5gS^MJK04av2S6!i;#e-%qE_w zwdzy(o+9Zwa@JS~?NeS0E8P9)eAPbac=mgFOi3#ORgjj+PVF(2#}z%7XFrRj(6TNA zp~-zdD$fKSNhUjVbc5rP)-ohMiWOhB?u0t z8pWNhP#zc3JTY%=q=1t)o(%~$S*tkwEFZtM{wsfZ^gj3ZgTZE>Ywjg*cs4{xrMV_{&&~aHO z$w%y`Sejaxpcvh~o1#G0UOstrY_@bJzdhQ?pTz}d-Vp6BdgNBXG04l3ODqZ zqX26~n-U9lR^Nw)QS-7xr0R8^10XVAffiC32OM|tHSt> zDf98Wr!F}YGnek|@ZEtUfGTTYLp1-zN5wPECX6ty87LNhGp8W>D81Ll62^g?L-f1j{Mu7j+AOE94=FbNH0RnCY;P=!(`x`--L)0n zZt20b#EW`69aLW#FTgKd%_U_jwPxE>*X!S|21bY8gY*dO7aq3s*I=50ttoHT)D6FD!J2G zX{>GfwK?rwVkCy?tBR0-sy7iy@);ja%3mZ)#N!JIXRgd^EO+}AO9wq@j+&+Y83$)i z)kG`TeUM90+vJ`$YB~9n{1zLv*?aU?8!K)tX@SOGixr^-68hzz<(H1Wlt1vgmtBv>ywPV_&NdXP zU`g}Dh1SNRV*L%g`q&WKF=a0b_%c`Vd8H|t6PYT_G8LOMjL3@K$?Qu8$%;Kaj9FR5 zFEA5dYdpeRyAPz$0tsuABPix$w&I$Gv@ZO?ZhcY3z7@f%+&BWNLJu55LgaVF*-?!d zakxrHGaj_uk=46BE71XNiWo+J^S9TKn|MjKJD_-+ebaXnR^w5F*V0dY*VD3{qGS&s*au zv_RtL)4eEteVStSBq_sE9P(DEjvYgS4|{V2RG~&m$n9HwoZsAt5s%i~5@wDYOAe3n zr_ch4{c{eWAsy=Bu^v(@`T737kad0q`PI~$BcRHw(SEdwTH)6{r8;*Sc~K~}Uqu2! z$5Uv5L=*cIbWgJbKDD2(}v!kw<;Ua0FD&l>nwCcb zW{#!M0ttJAV`ylX2&_FqA}*acCT!_gMiLW-aRgM^KRSw98mz_^^;8(K-C>h((BK_W z_1gbxmH10>Jw~K8-6J4dRhpeOm?NMn&OaT+G~JEwoT_4X!UtL{5jsp! zqt@@;DYQUhiT6qLD1Rr;*(?#EL)HohEA^@V$^je!RYf%?kudleZaeJ_BQgp@1r0w# z+OU}mg%(JB-+vnQ?Q#?c$4JD9mvO@7vgUNj1UW}Qm5<#S6tm$h9^iPF5x<-U2v6U& zqGh853N4TbiB_PXV-)uZk%-48K0@ITYns`u8%IEu*Ajx>C0@toZ>})neX*s`ad3A! zZio$q7Dyxqo<%pl7UJ_(R~bQ6dI=v-2y|ssYmR`b{%_BtmVuA(q;;nl@izD?s<*li z^~J3zv_K+#LJk`K?jc@!M(^65RiI)8@p~+ztSP?7{HNT1-n>Qaz zoyOFskbtV^-E+{E4dwXh%p^u!`;6s#E{>r=*XvVgfrNwJdDN$(9JhX-$cPo)DjbI- z4yO$?^*92mauyI2vhy((HlAd}GnMBkLT4zo3pSw80*Q4Q7@2N*fg2u?-ijBC51)B` z&YhwJBaVQoWxiQRCHX#nqMyx(F@x5jou`~=Pv7Po0aez|Pore-BHZW6Wk#GxFhS19 znO=%)PN4-7PmE3?MdzEii-|;}#-zx7Z3UX%w-ZM|m77lnD!F?ee;sg#5w}n-Iz2{C zGvhi@Xo1A=+iA$A<5e7zS;UC0zDMPu5%$!_- zB@K^q<_M^|QoRQaTd))FJ0ST`JJwCOX{Sq%&2^{u7Nw%aGuGgXMk-{v&oQ)Y*dF{n zy^5`T--k4Bt-}Vtq_K9@$LGB>3wvKkO+E_aMrcAA_}vGzh$=$Sa9x zy6Y1Bwn~lpI8m>iuvS}>uFdnL&;ki~eKOhoo0E{!1|8b6IZr^5M3nbw6u|9ZoK3aZEjef}-&7Bpb6Q1ot>kDV%5n0lldPl zD)MNSFNGFJG>co0e#VW&&->{x!YgtYx}N!jWV{RD2&jtxxS92AJDku=dZ+q^Z8GZY z`jq@S96+H35}!=gpu0ql-Lj=Qb?>0rC}GTH(#9o}BcKY7B`lWwdWPa{a>*4GOrZr5 z{D_k}Fv{`O-9S2K(i39*>;~Fjq(T<04Z)kw-9T=|DkLB#1UEZffXp`jz&^#&=-hYL z4isS=KnHesL7)W^lWYo*d&UoJm?jZg_X5%DQ9ktb&Kiz@sunx*P?FA9>}4kHz4LWP z3A%G@EFByoqtF70cE!2KvHw@>T_(*k-YhzSy629dcE7ba0;;+%x`sZyc#He}mgYY0 zU9|;Ubx&H>tRaOKNbHTiica->hvRc3qRO)ZUGp45ZLb({1XO8{yuzMYJjJJF#~Gnn z|EavmX?NOZmJx*(NNl=!5gANkbd$UEu+UZYja24hR4n6b=Ce9S|Fi^F|s|MiUXXb`w!9h zun;}Tgm&BKNTCH1Ywfa8PQ4?zhUK!^J}kwF!sd*IwD_W;?G;+Kr!I{=x_Y zl>-7A+mH^@aiY)yi73a@Xxr2sc*02O&dWOHqL3L_O%}a$;RvYGyO@RcZds4lANt9N zhfiJ!t9PZ7-CD!A%mmCvWG+ZY)6RwAXYZv*{k-U@ut6(>wDcTKp#>7}Kb%C#^QPgv z-V!mT>V;6z^^ zBBXI}c>BA8W$FWBI(868Kox)GDe*dv&kZNiT``Xdj5sEHZlL$2Dx~|w5DcRPdvC&Z zIT{!iK<~#qC(r^3{{ADdZGUv@qYth3`xi$*6^s(>U9$QLRBxj<9k{xNKno<`{SMn< z+-f^A&hetZsv1y8KoyJ<>|KC%6-e7|1Z^-aK2&jU6 zp6w^ot&BcKZQc{WdMGg8>|-I2}`+fZnM z1iUL|JqigzjJ-8Ai|x)4Pz8IiOt#Q%zR-HF744DOjY10~;N3mj=dN{#;QQ8+hPDj&62o-q7UaSaPzC!u%MM;h7JAIrrel-) zQ)qz%%(k$0HGY?X18azXKX;CRD%dw!p1~wrc=z=i$#_1H>w}PhStFUuM)SB}*x?a* zb=s37pbEwqnJmO8U+C(6mn_}x&czZ)!0Z>>@g(qqux~LTO}CBW2&jTtT=rH<=0hQF z5$(xkogo3Uk!+o% z#Vf%pFPf;NjO7TZf?0L;jNVTs&TJJ)^UT0R+Z%wCsqrKTRD;^Wn(x3s^HTB z_Rh~rO>s$m2eN4HaPBDpBw%(}Cd=%lE*>;AB15luaRgMsoHe_<8`4Yeab!F-+4qSY z8(N6$=gCOD6Z7!M9|h?AVi~y!Uz&8Ug3A;^!f@tQ)Zq44Jlt8D z^;x92p%EKL(dQ2}xNH}bkcYmR^_m|!l4Rg?%4_muSG&j?FMwq-633t9un}*o9)9gFhUqNpqk_j zAIT9=1)o63WOqE)2|4X5NT(y7+>-`Kz}x`a@AY-OAa8n?Obzkj2&jTjQrH^`ZFULX zt4hgW&oSH+6G+%~--m8(@WMSbqFaj?eDN2NPqKZ7Kp`=}k{a#K5N3yA>|)=woG}z#&hewU zN52qgfdtI^%4GZGzvYVL(e&yPbqWcng0YM3#acBTO;8z4w^pfBXn_RG6th|QgO*5$ z@t{lc3^)R+VC-UJ)TR{l%VsD&9M+gZ3nXBsn7yHJaVF~6(uuD0Z^02z1!EVRixw53 z*cbij>!=nKS|9=QzATFqycadku%~y_yK)3n!Pv#JQMZ2}tBt+rx^-PBv_JypeObOe zCJ$xyv!Ysi9XSH3VC<5~K6)Am$zGjk$7BZzEs%g&Tz2o=u^OFDwxBk#P8s-anjnYcMSI!>=m!`ex>w)iy z^bW>fYqMK^x`8gIsFLz${uss;))Hm8@{MnTXspRCj({o{$5{4Uu8A@a1<`{~cmk^6 z{E@ZYytcIaD@ST!+n@6RRq*bf&D-a!m)8`A(1tXZBcKXq6WH#1^Y+Q(azd!vOP+u# zm@j23ww@*lz0BRogQo0@;~?t866It2i14;TisM`ovvekfPbwh+>qaI!-ftt(d>BZ7 zmL?Ne2k>bhENPjnQ~fj{>e)Bq=Qo7AAB6XSe1=7%;+K%>is%XB*94XiEM1t_VDt8| z3bH|K40UTrxtTtk-Sb4XzMU}J<`;R8H=2tK@HqwS^D@~mjTq&M`-&nL^3H?pI`c}6 z((mvfedX`nB}MfaX;p$V`+!edyv(#O~f!Hn2?tGn2z@eRl6 z-Rw95sxr*eP|92t@@2~uM)b>*i7Og!RNS}rq0j<}v$luP%j$Y0w(AT=q}l6;9oKtj z-@EHcp#>5_N7$}Stla$fNyM~e+XcN1pBxk~!#M(~M&CS$ULL4Netw(Di1YS3w5gqX zw#hwDnlpCe-&dHqaU(K+s6wK8gy5sH9l*!=DTZ{itc9Y(+MyI$AaQZ=HWb!ag-mk_ zV?Me*T1)hQ{B%4YAHfk&MGF#92FpHPTOGlOGlntBmC;QvIg<|FYn0xlRwDiWtHtzr zyH@%4KXqQN8AJW{9<V2Q9A{NPJRmli3m zoU0(TVJs>I>?1a=(*b^FsLVet-jJ6dz43stb(*u4Fmv+zB7Fk5U8Lt(8o zEZwWT+O_8+Fkgca?VQj9{{qLVG*ZMIOS|9;ymfaN9_S(~| z*Rr*t^1tdp`u$h0Jt#Mk|23}2WSI5ZQFD{+DeJY+0tt_CCQABG4Nhgf_HqA!EaS^E z3JIv%G{2twpI+OF_1a|YtZ2u2Ewn%)^u#Mi=?wqrwF8X*^jb(jRm{K~$A5b5VAgBz z8f;XQuwDx-knp&-*zuoUdw})Y%5~n^Pgt*o7Dy!JMk~+iPp|c3z1D~ITFQDYB%msw zagD=2z4kI|v-?@EHDqm=9XI>0D?~=mv;XR~j8^{rkB>{N*Un?TwhimG&;p6^h8wg0 z>9tm@*EXx|wUB_SDuV@Q{^_+WQY(AyIacSao)v$!4C(h@Er!*N^6!7@{3GkN*G?U@ zU%+}Tv_OKj1;sz@sw=zVz1t3C-D4#H38;c4!g8;y*KRH;QdF{D3oVd%yHrE*Pp=)x zdhLMe@eXZSuZ09u!E$5cIqS98YI`lLwRKZpwUJ6e>a~0gE@8d)ac!@K7D(`=8^U^R zVr{R57D&K)Vtc)8u*2+2ceMP_0}S7NTweJMA1Z4^M!s2~fbT1^HS`6;uyOeuI@-#J zK-I3wr}*-5ZE~pRr8>l}QQG9^k!U*Js0l~-nta0#n`x8eQ3(o2vy~i)hGfXK*)-}# zI|5bhA6Ma4`C8=OkditCUKmR5Opc)5{+&3&;gMRdYVoAvSiqL8wUp-A4y=jN0q}hm5d6R@*^QYDW zy$Dog<}@MAqJQJdBYxH))^z(xDy>G*0V_sw#JIbyNOolfwr+n#0cp09Bl^IpzR$8vL(4Z(J97?+`L|fKQ6eTfHZqUVR&O|@x+BT zejiGp$|tfD(N%eg_0-fcPt5dfL%&aOpm&QxIO2YUElJS1i(fUrqkuGfCfukk9cO4y zUu+B~P}Mc4JL%|KikB=2cw!;h_T3Y>!5J*y%LRe)3cSX;$awoal?i zhICu2IRvUkn)e|st50Ir(gv6(-VXAlCmPkG?>^1qi22u?$+dO+anthW3P`i3ebYSY z?Itoh=#$j)7YazTyia>S zTEAW~2^n-YF;5)H45e6mH?c_!F2^eIZA@^>iZ-RcB(a>qZ#TGMU_FI!#fVMxLBlK%fei z4^NcN45G^__YpJwWjrx`Ala0^3hP&xVMw$2?z|xS^}~MBd3QX?2P#-=JTW3=9Bn%6 z2H6$8iX+DEA3%!k?ZKlzTGXj?#lCS=x2T8&jb1^Z3bsDzkG;cte;BpS|3QpbtmTM9 zzeF-$mVrN?Zc(T0S}TT8pR>QnvEo$(s$egI{#cf?-2j?c&w%RoU(XQ*OYF%`{Tw{W zrB$6iIQvO|`l?f7YO1-0KoyJz&>!0?EVT!{a;-JJv2Q&`oOQP$`(E9|O}4kH6H5lz z^`NKC+tSr?sub_>njPo{?l(?Wfo z7(Yvmyw+4FeZClANV9xmToQTnAcPtvM-Zrj^BtbJ6Fr^G?h{65Jr3sx-JO+q)Nf7F zw6ivbv`ki59z;S`&7d-IB7rJ6Z{vxNR*gx}<5_fD^aPG*R{jL5{nR3vzV$Jr*~)>_ zTI6=UDC(W)NuUbOKY6134#FW`(R9eYp&SACv|uLPdSfkt`&YpIGAu4U z!kOmk#K3I;%K=!$-c?LUp26N6NFq=*_1G~;bD<692|cfQ_=tKGy&V(55pWj| zNV6=bPE&m0^(?ym>S6*_uoQS=Xv}ClAvv0Ud*s3q@X8@Alf^_w(r)$au(s-a65Mwf z`EmED;&xVZyzU@-e>mG5yR2-9;rPf_K=?$`Mj6();@5lvRiC1Ukvv^Xth3ap4zcQN zIDM6_MXvW-$q~z@xRW0y{jh$+E*R2m)yvLsx;9Fa6kJ$Eph|7rP_k}?GmiafQHQWk zn?lbjCXn#KTR7sl%V6>`Cm1`9?}Z`FR_Ps{LbHP=kPC5J2vpU03?cb$)3CE=yE=r% z=0IA1_D=HpY7$3i_I4o-r{eML$UYd-tPk!8q^g#?NPCSW0#*5AUCI8M zMPq5r*~=v3Oe#mjd-o%=9&E+f!4*TAJyD!LmX0#NO6+V85vZEJs6Rpxep5}-SHa*!c8`(H=p(lnk`;N)-KJ-9}Hl5Mz6oIN5-(DoC#aVo`pS%v? zJ;sJEpWTe6eN%A6Aa!dJPOf3ck0UXp*_)GZyU~nt3p)Np7J;f6UAmF+#|m+a_Cg&Z z)3*if*r5wG45J(|u19;a0S2fn~ZY{y_ovl+6v4&7)d(p~Sf2~_oX*qk_LzQH9IQ5~Y) z*-EnH(Lg%KpK?Ua8)H&5;Ujj|7>yy#zDqXiD=9g~R+lb4L!fHma}%QTwF1A5b*w{N z^UWuA`@LxHV+BWi-rR_Ilzqb`9$pyIGTGBr*N7N1ie}HsBvAEWwhno_v<4r!-?I+U zsAm${u*#2qKYN-ZoZqPuzb7&>-fS3#G+Uo|e-}ye_NPW9oj}!|jQYeNO_hv$Zc~R? z?Gj23E(oG&jWRf*{QDPt>!T{^8!{L}S|%GAKY{#2A=EDDFoCKn_X_+qL!IX%^m#dxhObD#c5!RD*#2y# z2Z;&Rz^~eLz>sElkR7Mc@6?Y}?byLZQ5fg7=^(PXJqK({j z>`od&O3%6AlEJ+(PmHseMpcSC6aR;MI0BwKq}e>tY%Fz7xJ0&fJjTUD7_}28_9vmu zR^yt;(d?`$dwbI?uPpK;Ba@5N!IsYCYvn?GzjQd}iKdnTbnN)8Bs=~nN5Ihs(rgV& zZ~#4Le~5IBT^4SdwcckOM~&@#=xn^AC@{?ljV+j2Im!Tv<&B=|hHVY{4^jkHb81bH@nUKe3P) z7*URZ zF6IbWK7#$%{A6w0-P#Zp49O;yXJN;=i;EE3QaqHM;aO!Ku!4kJb(DI-U<` zN{U85#W!9=V4kRXq)O3GfevhRn9y|*Qwbe?>O-2324!WZtsJFD+1E=3O} zbMCIk<))7mFpJApQ^oqy=jFwu0>=@kf_Ye;_~jl#FPuJ3G+4$F5`oB_7^f`638Bvv zkY+1>FAk$=LuIt_u%%o^80M_6>N}Iv=PCF?&k~jwHRml}-W^3*i0FX`%) zg(og3Q1Ha^xz5zo(wMIB_vZ+hdxtceQxA5gD!q*8yb)8meESqHM3&XRf&Kwcnwimg&{T9A^RH1-0d%7f_Nh2y$$(aSq$@KoiNm$ANtoE%;ab%Jw z`B1MFwtxOw!RJLET1Qe6U`PU5`4Fgr8CsqgwknEFGjYI*v(q^O=8YjOll5=dfMB-s z*O1hBE|&qbEpP@XlQ|yLC&!G#=_{ZzDx%M`&`F;Cc@*hAvgCec1kH**BcenFb8v((r}mQ4zz)%|vIIWjoA=ZVr= zd8AKkAG+xL4vv6XJV>*h5cU=lx7lN9%E%-xa|iEIc%r0P6)ErMK_6D`;Ru+Ggfz>A zPx?ldY;mXgvIATO65eg`#I;SjG(NT;Elk_X5iqL?X%^dK^r-gZKGeQPGM7n(ca1!8 zeOOD{u&O)V@pd0a!0a%jWwICFThcMpY-sfRWG*8N?|ylr!RGEXsGudicVHh!z$`bU z+3sSRw$v%41r2DQ%w@LWT|7^;m-nMxtn_Hc^CXUd*?LGz&nEiOm6bZw=;?kgLl3hN zJkh9`2R${bnw&YjnP z0%^7?tf>#Re4a;=@9yB9n8551Pc&^ji5d(`BK8e8as>Aj2xO+%ewGa<(Z2H%NrRS~ zxFSTI}16B@}g>81#6 z(%yS9N5H3YkY;Zj(wTJn%|@itutnUHIGA?qDty(rgdYATM_3 zGmoa~Wn#F>0kX0QYVjRb024WIbQiRj6P!V z3KB3c4r#WY+J@~jxuiD^3LMVmkYNr0<{a2}WfGEc(|VI>*W2d^^bU{9&##utRB>+m zsq~aVHi3IY!!v|OlF6FC_o0vaz9EAb59H=oaE8RsORCP>(I$EA>3RP!Zq5ML9l-em zTa(()ng+G9rPT+!b88J$M|UIgl&3i0Mw)^rTrahu$(tSM*_{(O0ps#+2+ENc)W&&aM4`DoC?jU#muR$!iZ_DD&3xF#;p*7DoC@HPAR)dA_}8w2dgnu!4*lr?bJ#8crCK*gA4O< z*EgJm`p=@1Ca7~OouCTRGTGQ&0i>UP6#X*gHijy=vZ`NDHU8GP5t(Y&hWQB0F(i+U z$578bPr2v=Rgh+7^u!rs$fJnQim4Hy&xgi0HwkL_2IV9yM$)nr7GI$+o5Q$*14G z9064|$=XDrYk|WHr0dvLaDhCu8BZSLKoMFXvG-^baNY7v8-Lvi>rHKAgJ zDG_E{W6OgojHn8_ND6MG6Ys<^BD6pPo~=w~I=6t#@Y_RF%)L1Rs`#^N%tGQJlb59W zvb%Ub!iXe(nvIvJSEAjm*q2m}#^H#jGNJi0V{&o%czp8O55z{bPMEmiCuGSa4-r}* z0nbn-3-5B7EWBMn#(o~o5l{t7gnd=_)CrRQOOyJ>^cTmdHzo}tHsFgF%FqH6HG)2F z#=qNsK_^`e$;8J?@wg)&q_bkrBwjyPr(cISiO>QGc!q4=9)^iH{3q$Y!<8eT3YG}# zwO5kKrmoFsy)8Y(?jl<$x%?0|_Pm1>tLl-ACr5D8@6V9I5qmXVq0Ro?Iw$ri%>qMQDM~&cszD#|j_ehTXskMnr0(#hcwIS1K-Gu?_waJJYTS;! zOCgiJbQ?ydrT9|of+qsBKw?OQj4ZUM#)jwSFakdmNtgIQYB?jHBcQ6X^G|$GUV{&f z8_$TyqgLd?q#!zEeGW%Jl}(pI+^#;Orw@P_HhJM^&R#Z&rMMytKPO}M8xjtxMt#9I%IBr;n$WE*vdhhvoB3&zOYJwvqc0u6%@TCTgbUN;Y-gkKQ!uraz7nG)Kno;NeQ#sgARVGvobM=; z9l4~1)!kxgqj!rDB%lg@1xF_Pea>HzdLovVe0N090>51XkHmIRezuo{I(DS#)JlZC z2=+&pX^jZ+$9UwFtL(}b58h7P-*l#ZbUJYaRJk<$fr-a?Tz0dF5n1`0i9FAqdcCm_ zp#>7KudpvjhOQ*PQU&@w%bX*i3ieI*{SUTc=JKU5`gHU*t_ESPEo*ijmygsW&%1YH zXXW0rKIye~CVgzNRNz$KUgPeu4T$!QFLIt}AAS~}y%0rPp7Y`A9IBQ9nq}2~p2KhU z%%*auAp*3(I)|-?5qMHthKUcPZZMEXJ%-gsMD_WHRBZ(=FYEy$^TrVh!&WQ3A?qwjH-md|993G2ceIz&UhFe-RB!lJzu(N6~q6nww zMA7_BqXlSz1Uy5wue0kR-2PoOo!p}rM?e)U5tdI>=#l)AFdDXWvyd~u3;S=ZPdp5^ zAsC4aOb6maMjFIhbrn0SqYw1Rqbp%F@XlrdS|9<>P})1X0uLG=L3>YM#1T*hON70h z*~5`-8qe_Qg5k6IxMIu)Jo^4M1jnmax1;d0 zqm}r3Ys${*!(DH(dbc-q)_E&H3nbtfvZwmN{m8LC0rXz4B94G6SRyjnj{bi}=aw`0 zvGzmfczitS6)x>jQfCI>IU|w;>kOl42S1)e;-TwGoTL2+pXw;hWadp;L>#9Nq+K<1 zxETOc@eyu&<3*(5mw`0Vw-Gllfka97b=bCP37&D{E%UKYgY9#FM4;}^%{T(8U_54f zM>knRhI{m*ZS0M>xC@C7WgD^k;XHgPuY&n7IF>+CJ3G>&{rK1pRih_v!za$4#~D*< zq$}UQi>!XznZ9@K$oYUOI1;g49n~4J$c7Hy)`lB#AQ6+>?gq?LUkgUsGd*(S*a~H2B;7|XNY5hiFV$)1 zocCuY*BD6qavf2ZjqqZ0;PG~V7#vc@9Vrdl#YBq=?peiTg zISvkt!u3-dGD2*TL+s8zA#SAu$OO%A#4S3=0vVH^QfT7{pm_MG8ZKe`bk4qv!RvTmi5%ZZ~o0;=GB8+#JxT}rOs z%O!DXL%DlSNbF3j!p)s~V+}Vc2Vg%xpEx)iBffJ-a|Beymj1@W2DHINBXk)tvR^5g zymA52cr#8MZBUmyIyllmj}evoOGx&T`NYW1SA-Tw@YiAf zJfC!P-bAj~AIA|;#h;Zp_bGYU&Wf~IJYLL~YmjC`*DIE#>T?;7PPf(AbFp&@O;Mkn zRhL_LN#C-jWSU8U2rV!Z0?&}mWI7iSwHL$5rco0(0;*t%u)Pgs_sC(pVR(x=pOb+; zmJ6E1F@Atz=6C6=o_8xJv+i!g?hXC9EDlsz+}9+J6LYiQbTnW@vyKl*=8tCh%G8M* z0aYv1w8#qAHrc8dB_D<3Zj*C`Efu$9K^y^9VMvQqHS|lfNtcMofQe-7zEN~u-zsiY zgQEc)uUMAzOfdQL!8%O9G72?%DT+uV3qX20ZuQm>&vwaf; zN8=v?RBZ?^!OgpML{HDOuR}EG*Oxv&879O8n2V6e$tlK18hfH_qc#Gh+1r3u`_NJT zGlX+*%|)oXa`pk<`r8Kid9|uTtXU`kkE!Rrc{Oae1&D_1$Vwhj3nCMEgcOMtZM?a0KiVkY=O7BqMq!;W7IDZHNd} zu!Zx)6-7AxetL`W;L$P!+bC>HxlIbO|GHQ5`d|96w!2UkPOIDO5aJAXA*eFhUWjSX z2YEuZgTND6rqigqdxG##eKgnNU|WJTn=QFcrBC*46z*pFaqTCsQ4zj9;G5i}m94-N z2d)Rwh0T`=DvvTa0=6Ycv+n{l4y51KEfesfQ(XJ`6i|XYMysH+n>q_TvC@1Lz3ehg z*rHa&5wI;mn!O9KcqARhHo+cssG4g(tCrozUCkRH`K)#VPiV=V=y!twLb$t`2#*Wf z5~SIERPg|M_0a&q`@ES5RYqf<;|KnF=+~1L0#CRtvZlRk8w&%ndT<168IYFA1XpXC zw!E=m{l13?Rc+JCadJmfw5F=5z!M)vna~bw7n`!~LpTDqL`buIqG&=tR-8gDorZ`| z1>-JH9Po&u6BG_06!Q5{Tf-2QJMR;Se zLXM&w1fG~bKAdXK3KE>$M{z9AL&do=Dgr90}aL4(f@7NP2X z+%G)U^tZh2E)#(#a^F^xF>}w#!@Br!#C~&CQWn@0ZBR23AkE&qkNiY*(n}m?E5?h< zHfa*=dA;S6A`OJat5u0{?m)S2J0qdNR}J#PY>nLNf;3M&#P;yMU2|SxN_|AA8e3V9 zSo;RcPgok)AsQdhp;n)}p>8go9HE#gBWHgF$mh2;5g^Up!mihtHep}(deF#SgsPhh zzvC6TGvsqtH>pE>jW(giR;uVs4>u92{Eo^c8rlFq*j|J<1C&D%~p=td+(Q5y}90AV?(k!!ms0qF0I~>Ii8!SQY3y1#L(~O#dwDoVXdDL&4 zI`Qhr{>k(Ro2Ru_OBbLDMo#FDWt}x=(O$=FguwA*IpVEbF;>Z0CYNhE)QP+Of@aYy z>#l+#e53$Xa0Gz<*n354G4y4wT(CK^3_${pOOR%(^x|Tuy{wDyOl22>DoF1rzJ=Ky zJo4l=%5m^WEZeXDy?plUcASsWPQ`c$Q^jc_fhX=iil)EpTMG1NB}Yu^T!N=DqT%OW z0;E~oeI7*(a!Qc8qZfDOu%sc)?u0MRrioT*sOv;Gu5|5gm*U0Dhx%(K&Q&Lt7UuHn zW2Cs-�Pg|8iVD=#j4o$37Tq`ItDnK^56hdQ)E3g1TFQ4yro? zMVksulCU+$vF{)Q0iFpwLz(R6JU_ZOU^7y*{=(HDj9sucSzdI~F#2)D2Q>Gz4i^() z>GH%#_O{5ojxi{FBp*d#9YC6Wb=s+#1Z;GYXFc%cMjSZ8!FrO(Mp!o|t?$ecyEJ^% zeJyKOQUp-#0x-U$BVWl}C!(>A5qI zfGRjMV5=s>%E)cg0I}iWCXSGRs+DD`~DR_=_HQ*Em26B;X8(?Md#^ znay71VuaJWGmwBPSpRHI(d{`@+q$`MO77wKYfb~=^=z}FR907BHy{tvT^)Pe(HEo~ znQ4V{Yw7Q7y-(6STHtsSq5cojprtPHPgbq%ojJ5Gs}r@ncHJNWb8of2v;X+mXB{xigeQ; zeP-$@{+v~@oexbYmC=u32YW&bBs7LCB>5P6?$})>u@@|mu)sApsGHtN6wavRkR2; zV#Hup7bdJu7H`?_P}>rf-g`~|jo;Ex#X^~hP}^^6&+2!g52<-Ko2E>7DDd?uJv#((OV!=Syc`yn^itwovwk zJXVAK!^(t3(_9=O0adl7F8@=5MytorfFWw4_08v;52)h%#{*V-#r1oLNoO1URUgV@ zK^3Ig3T)Pjtp)5sM2e8yx?$s@unDv=T)7w~`fht(KJmEUmQ9SjY<@pM> z3wze=M;77=~Hn(XYcpL3Q>wc|72RlhmGiEbl1|w`30aXw651{p{ z*P`D&>Jr^tt;BHDNL=RdlOvp397X=S)}qs?ssg0hn_(_i;(bQ+WCT=A{gi?xui1!Z zUZ_jRi;cwA_MZgT5A8)rjJbUR#l>$#J)itSke12JBXq@3s|I4fBP~Rz>NzU zo~A2&Ty+%vSiS^(aL^LgsvSg^7cWD$L#5KyWW*Up>}3R0?JY`0o;l0Vs<{p75L;_> z#HfONf@ zik1s3MM%_dLJ^&^47Dnk36N&bgc(uwx~A6lS@{i>d)U1q}htbp*A8t-&WkIwv8(jc(t%iv-=N5oMpr=MnDy8$2?Iw zwVCK~(L%Hz`HdssxkFkeQ=QgK{FP%NCNTo4V5{Vb2_Nf;BTV$fSuBSK33#=TW^1+? zF_{sQ7y(tV9rJ|x_q#&U5>;_}fWQ&3?LwOM^A_&nprwZ5_zn~e*58NnRaPL^03$9M z=xntQrMc3R(UUoS#VpO%V*Q*Vj({b~#}eN|qKMMliA%>^=Lpy*AkCho9*~Pu z`g9WI^)7P+>|Ky%U)1ps#k`=~g0`S4UerB^S{&Sg_Iy+ke(&0gmbcr8-YwG<_{eb5 zqP5r{v`FYz-i9Nfitp#6#0^5m4L$K>@&K`E!6nqcFaaGkt>W4%Y{%?NG!+|#aSL_D zt*%ZS0qX!baE!D7#*^~EPMcMDJjqcbcwHe1rS6_X~_7aQ#V#+4#eL0TqL)YJ%XGkiolo%JVu z;?JSPRU%sbyNRIN;w&21sSkUaX(23YlY_3r%aP|xW7e+NKe3b%Y5KV*plYDDiqO~Z zgOw`!`jV#en}N{`Mgq_b(a}(r@X=fBlOS zt(uj{rwzD{q}jy&g7NaNor{&fuUR%lmE*1`fB&VH{u?Jk)jf+)$9coZ|AF|{D$yZI zy;Mm+n)d-!iz2iYT@K>^197I%UeWE!pX-1$?*pnftMD^1LD~@`jRt zH17kdcBdQQlGfM$n~0N2x3=7|R3Am32cpfJvGR9qJt=?lKA?)7yPTEPe-la{kchfB z3so4WDG5mPKA?*3PnNgFS^oz@)ucX(-=D4|AkF)z%~L67mR^a4c){IA%HNVNMk#+Q z33d(Azc>-9l*c!zuk`W%5PyI=#H_H(SYFUvNkIC~!T%s}B2-O`O~&iCbo+PWZy%5_ z3sB%&zV1o_(!39-vWwh~?ex6=o%q`aBwi&R#TP20l?0@DA5f)zX$7tvKmXr}zkNU= z!eH6}(sfKM_hFkmh~Bdq9|T z_YLS^l7KXS9Z*%%}Xjy33v&K@lF4>%_NO|TzvB2=+*L(;hMzZ0x(kTeQN1f>7=p*$<-!|zNYx|_91 zNkIBMghskzYho{%k zuu*x+(FfAJ52#`>7_k`q--OZ!B#P!0quin)N&?cn52$LZ$VQ6!asN#yeLzCcDn-Wi z+?6?YNb^3RO1hI^W34hT{=X5m{^U~WLYnshRnnb=G|&CtiP~~g5|HM7K$R4ESfuzr z5ViG>q_cuF?*poo5tPlV|97Ic9V-b)^FE+TitADgk$n7bL~Vam5|HM7K$SE;Nijt7 z@xKw$s3}DRiGcKf`>2gXN&?b60aeoIFGU2&$NxsuMpPvMY2F7^NwXL!B1k^|H==ed zQ4)~meL$5o8T?N90ofmIz2IeZ>9o6emiN zK$=%es@j}`^7nt=r9z@MgYf^*{B=O0HXooQApPG&?cKeSfb@S8wK)JK0qOrHYG)Qo z0@8mIanhWjcE+MqNu!N4W0uMd-YqE!rk4Kkgfwp; zj{mBxBBdf*B_pdvsOLFXBtk|usYFCZAxV+FcPe}DnURW~=Q@eV$Vk(OB&5vj`8(G$ zPafy_>Gl47Uw^!A*Uj~~cdm8L^Kq@m#S8hDfbBt*fcn1$+|p40w}5L7H80?~8oYw= z-`4=3P~WeU*Bt8qZUf%6g8IJ&yn_k#e+zil2sJO{?JxHvdD-E)Av_oTZvpS{LH*wX zo*P2_-vXXNLjB(Yo;5=KSIm=-UAX4*aVw7@@>YQQuV54NL^x)^v82MQYN|Hi7zIZ= zb|n72;;CwbMa%!G#;d<`ps46d>O9r;-BpvGqlB_K3igdS>Ce|zx#{JNEu`|lF8_Ub zsv;pr-D$B(^_QfM=Kn*$sF$;&RiZ?<$^Q^AD*wxNl_1UK@9>uY_kWiPM$H|!UnM&1 zt;>XQ>j`o4dOW<``Yc=z7`3TNEJ|Wq#Ic_V6Db2fw3o%$f(9L+fKi3o@hFjr(~XUo z2u>W>K^8N7R&fGGd32!YG!qXS88WdywEbCGm{`A#gKfa5v2W8*JQFRS)@0&FaW~a^ zyuGSC0|ktd?~BNLc14&hz_ywP1&mVvJ13|t|IAU!M~Qk`j{2jO|69PQ#%w*+xr){!be)D&3x{M3ctyw)!stqi*~@s}f6_$ou2J1dN(J^QcN}JX4#AF{>&ku>C== zMz2m#udTf1Fsjwzy~vNP$NN?CaYZjpa*##L-VGh0fKmKcj%$y0>L`mkV+MAD0!G0v z9t(o)220gar7zl+2nCFS-%I}QHHT5^X?gwFQ(<>&id8CoCJXEaP`I{mTiKW%N8xXi zl-H`t{i8*&k@)gm6{#5YqcBRTh(njhJyotdVJPvUYx*_p^S!dP_waa5z&!{xt69@3 z7mu|vl9sm~OJUU3w*(D*_E>o)q^86R_iZzArRZAHv&0#kfX5Zo>~6T{B3#|5o|Nnn zOkq@9k2Ey+Lca2CeSL`+UBeEbrdf5R?cHZ{0v_#9vq~X@SapKkJEd{80;oL4?~(_( zP+D2_cYUr7BzGLDO7g#Nb}%O+4fWX89m_;DCMGi>x2}$or%NtckezPwBlr*Qzlfo!@i^jP(BY0i;n*S4|T^+H` zi$zjD-)@|+abeF)ymKG{cUkQ#pao$GTMw(#X_8^p(cGHLYrA#eJhD1b;I;zWA554r zVem)5s7Gt(lWQNfG(-#&Ij!DGJ8Xuj+E5F*jaxK^ocQs9$lFb=*?ngwjspRshS_f- zGlzZF5U-eM|4@&%+T*TjLoMVs+I~GswnRTu3AJVwvmP$TC#LJt1;@&TI?9j`)IQ}X z@$2zYLp(h+AHS+xpWb=hMb(B{#NVRmRzU(W{rHGL&FXBkrOJp7kcNptDxp4pG>;PX zam?OVW5P5hKyqUOM#)ptfkSr*|V z_3vx_$)A-a-^=^?zx`1uK~HS{skxNQYSF{(1IJpprP&+npPN<$C=q zyP#%o7F*rMCz=*Y>qFe>)vN^c$ZIjFIYV2u9_nS6m+Ifha5nWa-tT@}N{b!H3C*pb z)`Fn@;yoH4SSnqq>Z@8R^#})-U7p^1B$9OX{=|;<>wV{;)M2-z4T~mlLS7HJ75=UH zDy5hJj0>?_9~8mPuZ z^%$+-v-Ltenp3P0b!cc9k|h zcjv}k_zMR|S5|?>>LK=zejshn?#1r^top50j~Vb+pYMaS z+bqU)4ck!dS^xLgRqsuBEU>RZo!^Q-4C+i5FKEo|LAZ7KqeMPiQJ+&-v1*5ZzDJMb z=|A72S4}TopeGd<86!FNzlAzV)~mMaOZ_gNW|i3fmrzH^!m*WsbjRrps|onOggOd{ zr2i+8B#S@m$BxARXoJAND^LGfLRJ;{e+hMzEdFeT|DQJ0QL^~6r8NXQdsC|Shdiy` zAM&(%OY=*mDb!K&zpJfS*W-4{}$>fAT;)e=2HC;N#NiAd(8>_yYjSpOaJFm zsf0R87V0hizlAzV7XS9gyIV?0H`kixd6S9=L zOArE<9+iHUwWY)Bwh&TW8BY?!qeNxH|^>eYW6#L@2u3F zG^M_a+lep=*4W~ObNe*ObyQt?HQt^Rm8M@Iq26oBxx^Y6YF2};ezH`%PhD#DwSx$w zV2v$a+_-aF+T&ZDzS`r&iJsn>#KmkrxgAgwL(SeS&b%U3N~lgZWgrno!Kz%ma9ofl zO+4{Snz6eJC-%>ONNipQkZG|77;08krNIqp@?C-c?%qv=QLri(FOI*;mA=mXD8(o7 z0#@aMT7K`YI_+@02Yo$g2VQb$DKV~fluZ3t504lZL;7{zMMfWCZ|!)jB2i0@k*SqU zFgt^csY;)pa-*Z~?B}AsEZRa+d+jEMTI{)CPQ;p;(BbT5gzY0waAIh!y`+tG6se=# z2yjjjaUq$-o+jyQ|d>Prw!|Bh-$Z*(1|N-X@W%}Cwj)7ARD?ZB@Vt# zFw}x@GO7u^ve%ZjUYUqt)U*p{h`Zi0GSIochR8E-O`APzN_C%J;Dld?b0oFabh7@m zIfj~@b85GyL9d$9W%W}qj5>QlBEf@$Nzb7THN-H|o~|2Thqj%5jT8GfB@^pYBZ+xH zQw+5r96jBhHV>*pl?$$67!^AFGFhMOMVb{h(hyJ1DQMzGUAlG89Zu}%c7^DMyOK3k znqjB~;Z>r7&fcU;tM0plVbloMbn)VFXfW`fwf7mTyqU!l;y#)j09;)hayhgUY|qC+)9-J zHdgGtqko!RZ-4ATcfW|2#x^d(FenHLpd?v=Or@ZiVYc|YmcE8gmsbrbm5U~sq6dg z2u2<6aDmjhr6Bw6bFsN_TPl5bBW}5+mU4FuMTX@m+l!r2d^-sZCWfwFe*_lTIAfhbRS<>bHhyA8Lo8W|a!>DCqsDHuTGbCY<L-rrNC#E7qiw$UAs96~b~E`rK8Ac*&_+YtjcP|n6g$#-{cJb^ z`vlbNMVUd?v~yQSdOFSm!6?|Hc%i#ci#D^nK-SFl6ybZR@XcaagOXKT{QN{3V)lik zc#RQZ6s(5G3vcI_QrMtPq)YZ_PQdq_p=LQ;pHgX4B^&AV4R5aEBCKt>dySU#yUHZx zYG3(%=e4~*OX!WcRCm@$uAZgi%HO26&v~WYZ4=Ck>?Lod?`VuPSUG|du<9k$?Cs^K z*V2R~0S;778nb@}iCSR+@}9N)xIN7Gcz&%Vng;m?p&bn-S)P+vq~6($Yj}{x1(sz&fc= zv#Qx8FQremXQjsb`in5ivCAvsKCv^|@}m~!MVDpy()>QRB*nWvoPgC^p=P{CkQp z3g*|m2#zqIt!r9KZvy*?@c4oI8NS0U2qh5>=)RRrCG5~cgi-LVcwTI?u1Ckuu#%p} zx^coY>;oA-H%_T6VjLoPg)iP_ue6IbWnhH%w?N;}+bx zbN`OXuEa?1=7My_B1E6N#mR(vR1*eZHQI3$JTH&F*cdK9puJXiH1#)#a{bTph8G6e;(Ut$p<| zFK+l>mZmB@($x)2I03J=K+W!L2eqT_rtB+98`_Dmufaayb?haXG4!Oes8?h5tLDAY znr8G}A|1cjR)kU3ZqG<@=eNq7NsTZs6hT&WYTZ~V=Ta+9z&-&rt6=uI6}@VFTnf8j zCBmrYk&j8Mv8H5Z|AtsYm|4;{%Wq4m3s@Ba(6?cqfLaiKBsZh618z!-W15LD%D?m; z=@(){HYyrmUO2=xW?yS8m0I+)-~{XwP_r-nMVe9nWiKUNXLAuo8BEP2<`3OS^{VwT zFDm8Mr4dVY=;?$;oPd1-YF7EHv_5?oqD@oRHxyx1atrpQ_XVTKy|}uV7c2G{(QZiw z^mSofPQX3^wIC!FnNWABCcVAWRD@C8>!y;n9y7_~-lmuro(9!vjcE<3IL4S0uuniO z2;KAbseN(-Y8hBdgi*?!=g8&5%ZVSWCculn0opWRq7~InufYk}C!l8cqr5BASEViK z^R0R!jH>tb70ed1=1`hk)}KS#!whsTu(l_#1d1Vniy(97}nI4o(@_ijh${R!oCLk z1b^=Az1x*0&tEAy=@^SJ3ZBLDqBuaLA5X?feSR8n0`>{0*%$KaIMdY|&q!;63`7_O zuSW3Vy`nRHX_+IPZdZd7uunkEuKRrHOp8mhq=Cn)i!cgaRpG^#GCLaC;e+&aOf^ox zJ^{5Lgx}yMW-rVcT7iw zQSd4kFXlY9q)zrGbZ8}k6R=M}&Awmztr_hYWlZ<%_{H@cc(slfR`nXvl>^MFp4lf( zz&-)BAQa7OMBiRBqqL-q>pAeMBQI7ytwn3@Z%1b>dC3XbC!iLD2|>p6yiGfL<=1nr z=fJC{yjbj4mAXba(v5HOIRSeS)U2wbp)MWL)RCH2dcgHHcomozzOBDY_KI#a&nA-- z@Jch(tj_kX09rrSRq8h23@+4vNW9sVn;N%Tb639-8r>ri@)ezf*6g?T%K3@Z<1CgA z1jcev4c2Fqp zGl*C5E9J0QYs`zwvqsS!XU|Ftbq{a?UcZEzRmXqoLmMd)qzCg4a@Q>5r=^n(7i*J= z&DvpJ6igmYFJ*EiO{|!8gqV0PB~kH~m=|;UwWedd?C3JLMVx^5Tc8$%E<;<<^>6KH=Qc~Ydn}t< z?Ig5r6!~OqfqAigYGc~MM5Hr=!#Dx&Eo z9C)pl7u((i&;^Z8Nq5tFa02!TsM%M*D+f@aXPmSmz7N-P;MHMXEOnx9go`_0owGuunkEo;;iGNu%*c>A~tQ zT+e~mka;of<{XJqKQa=EeKA?(|S&6B>E4 z9VcL)fSP^ZU}-O!Ra~1kNpH{f9C*!|7yie)(Dn8fwB^ZWoPd1-YC*`17iqK4O{qht zc3jVa*Q|M=^|n2Ib<>76xz>;quuniO2 zsD8^#t|(R9fViX`D@`PeDfuPOOA9uuF9RUz^exET!dXUIEHAi z9CvA=nWYGq7oLkO{P>c6!)=B#z(KwfXExrR#@@7-Vt?CkXDm>|t-!u~((Jpmx4R1s zJfFkmSKN|tcl84f45C|H2TI>YR}xcQo{_z*^3&#K^>a$$c;{~=E@zr@D~Rj$Aa+9a~3V??<)EJdXL~; zL>H@UlE$`M#_o<9cN86R!s&Q7d+Edp3#5Jv^VnSxLk;g{vb#$9!X=x8_8WcJX!6-Nm^5V&iVku$WW@1`( zj0h{}!n-~2E)aVXa78b=?6E@X-lH~m?82jjKia?d451B6oTWB3dvRM4Ze4gR$WK$r z|EZn^oCm+d3cu*Opw(*C7hPFh=@#Yj<^P{YVRgD;YcHelQae>OJigA|Kf{Zcqi>+S zwslkj>VNU_lEF5#7T!QdrqxynsQ+8|zGT(wE)=V(??L_FVnwq%Xvm*>eNd}K`CEME?pf$AM@UcfmOiSjlUn%dC!w>zuafI>Yj zN6A%USgnRXZ9oC%R3ysV$jt6eKOl2e8&IgHbujKWrHlR>X%TfGW@le1y6^ZgTnqs>jEK%N8P^hQnD0!@6 zBgLQffCA2`NR+oBk5z00QndkvdRmT>$0{~b{AmLUIHw{}-iAC@u@Oks1{CUPIZ7U@ z*hulG4JhE8ibQ!E@>s=2AXOVssHf#9d8}e1#h*5yfO9Gm#^&Z$V0w;_*JYy?uZ0fl;6j)L{p1OW;-ry^0_hCEiW5lGbr6zXX?3f6IBcSeDL zb1D+$ZOCI48-Y}9K%t(Nqxh;3P{27AiSjn&v5JjAavSrYP*2NIuwn&!D;@|qry^0_ zhCEiW5lGbr6zXX?im%oK1)NinC~rd^tJnynY6A-Ov>YXmRcxgAbL>I^=Ts!h+mOd9 zHUg>IfI>YjN3pEtZ|x;je)U(tITeZWHsrC2jXktlCN z9;?_0q-p~S^|Tx%k5z1>_|paya85;{ybXD*Vk3~M4Jg#pa+Ew)v613W8&JSG6^ZgT zs=2ia%{Y0q0aC%G;2~DmDVizftp`P*2NIEUQ6mr1;YY6mU*O zqPz`xtYRaOstqXA({dEcYW`M!69g#WoQgzw8}eAiMj%xiP^hQnD3;aytzf6hul@=+ zry^0_hCEiW5lDXHYaSHpX*r5zHGeDdu`2&Sz&RC(@;2nLij6?3_l2NPPs>p(tNB|| zP?cZ(6>v^PqPz`xtYRaO#MVR3um1im^|TztvYNk@5mousUjgS-B+A>6$0{}gsoH=- zJuOGcV-*`I$lv_xuYhwZ66I~kW0ib{C$9$->S;NOWi@{*RjTrS;Mj9;?_$@n=1tfO9Gm$0{~b{AmLUIHw{}-iAC@ z$!BaT!vDiY;w z$YYg!h9|cHg?d_!Vp+}Kn)Ist>aT!vDiY;w$YYg!h9|cHg?d_!Vp+}KT7m5QA3(r4 z6^ZgTh2P*2NI@>s=2ia*B{6mU*OqP&gDN9U;ie!pkB7`zp$djDAc z9_+yS>yVIHN$Q?7l$~S0sTodpyzx}dzt982IkHxZE+y+!)5~U!WFj|wBGuki?6l@a z8Yf`X&7P6S^^%Sxyzph>!lfRPPK(r}Xyb6Pdd^pPWHrW_nlU;EpxLtd#h_Yq{eoCC!P{WHkcL`OQ*X*?6D6D`Dn-Z4&bk6bwcqfU1}fdo5kNvC=c6BkUv zMRtJ9+mqS@mwF_sT2H^>j^t_e+skli1>v1%glHf2S=rv?5rT7|hf_V-qXI@A>5e!k=x{dfED`~0iDNHYUO#UlGw zBAf#Szdvxtnsm-o7v&(fU*H@l;ISYGd+U!unTuVVo^6>cPH{Sj^fzfqNw)lP1&=rO z?M!x*D~)?71w;Nw9Dn?%YCYtm5B?=V*s$j$&eCe9Slca#YXb^?54yACY3NoLr5jrh zI0p)N^suTCe|qg4)@#AL(@36H_rY^TjgHdX2JUVESQ zTIYSmP7$ovLII$Rb$4kl@{UJK_y(IKGB>0htC$a?K0pBSfj)@z}F zQPaO2aQfG4>7QPEf%RIp4^&Gf_gZ;c-D}~}miOAZtk+`JYvCLydJ{9nzh3*A^;$F5 zYa>~&g#t#wbz)C)uwHwjueWkO>$Ob$JsQ|LsrH(@efWL;i}l*>6Gg>b)@$J$DER%+ zjrCeH)@wc3et~nKfO}RDcCuc(_)o8WUpLS3Z?6SM2|V6d=FN`sswU;V7S3URSGAwz zqYwTi)&}dfF|60FX1x~9fr8(IF6?;f$a-yGwjOW}6!2JJ-##1KBWd4x1F0lr4wdgH z34Y@gfu(hEL2(A^b@`+sTByt2n__Q(ZeH3k+TTk05;~j0DD}N5`5qL!Hzf$u_AQEg zHPlMlIg1zYE*aE<(7XHlq{mju+bGS$QD}no+(~F)r2j zZ`oXroz14N4|5#d-kDrUm`gRI)axWK)j#3k^W$7U?{6f~B!Uxgo!}N>KWB~xNnctu zLBns(rArgDP)!%CjA>dA%N6G51t|B)OY%o3#xQnQo=G&-MZ*|hHD)n$^lR4@;qpB!; z>khJBt5gGAxq|eUNEcZz< z>96?iGnl51*B4>bn=m`&fx@Sx(x~GaqF$4u=fg4v)8b1tII(HWv2&T1i^&P$0D@W& z7VHd2%Gx}HZro5^gi*5`yChl7EMj*nk7nodzd41$hmoPQm&jjIwbVrg%E&DM_q%LPM05RaT_;9ZX%9@nYHjD~fadpAlv1 z5d^g$M0Rhe2x>Wq?!yKmjOq}$OEFj|BsKG5HN>@=qZI9|2hz0%4LMQUIa6V8RY10P zI*p(fgk4=+Nw=8Ube>HUeB*vQWuw#Cq}GmXl)27TIkzx}q_nz;2AS7TKG~2%CU|AA zqomcEND?tAjP_mD1H-5b0mjO426<#@%ry-$XOS&w&@Pl7>@brPE5>^%-7@k>L4GQN znq5`X3L^7$L#UhM3Jjy_zpJl2(Cj`L_aQ|?G@n(Qta&t*ZjC*_i3<%vlqY9BAgeM6 zf|{MtCv+xrn*~v=d$AZs?K@EZKCtxpvn!Wk*FogJr&85SOjwX(tC&7AQ)x7dZW{w%xtpm^J5M1!!aDS^O;Knd+2c@ zu9<~m@YrnP*y$dES`ZG^jX<}C&!xprY9bi*tZyAfLdR^<`+b3i_&Mq!>eVHJMsK&{ zL~h%uiq$xa)cANGLCxN^Y*K(Cts-a#!!8I$?X0>$v3Y$a(TjbmAzTMF#58+0y=iR7 ziSJc*DQ4}tOR`7iBdA%gU9G^OFT?1U)EES#oSd#G2CTnBY`qIK#A|O>xuqIn@QO9~_@Wu~hT&jNq|K^p@WMN)T|=u@>Mun2%#;r z4G@g_6kY`#>vDq}8um^@Tz$oS2POM*Vr`5$8hqsnv9o!Npk_~I2JFMPT&B^h z4NMS>GSzE<9!I5-&(5DTg#Ax~qnszxpUnd~adoHzI^ceh%pP2ZpcaH~?UndJ!DPC$ zMSTRLcKTYQM#C===b-NzqW`)qe9&w>4Y!}e39a~EDA-vdl@5JDPz%EL{JVH`)_7|5 z#2mq>>$6=@>IzEEj}b60I@f!JPj_d}pEp~=iT!uIQSYck;$HU`f|^|gUR#14b;nS% z2JH}x`j$Twjr@6zm)fK7?sv;BI>OdM-E=CtRb#t>x(UW52B@E(VW<@djUEhb(BcMD`BWv8wUE~q#lE5 z?JC_6jPi4fKv9#A6Tz#RhM3x{p18)|omNiW#)*~5E77X1`&i|cDi~^3JGxU{(QS4g z>gIzGjPjVY6h-SDB;qPP4N+%TQ*rA~7n+cJiW95WN1=JcwvlU&x)^HqepI4`_;au; z{W84`f>93_tVMp!c9EmoYiJ0&8*N2BR*fXP$u&-xRNs!OXKx@!r&Y&Lv+6KI+lt3? zoM@rHAL62#Y(aZIMw5Iy0}ZiavZL6our2jm&c0p_{_g&)18B;LWu)aZef$t;_WkqE zoyDMO*7VpU4+NvEEcc@Hx~s?mTuVdzy5cHkI+)R}ruR89?Ncm@9yyB)(lf+Rv-?pq zUB!Y(3wrUY6@pPAM~|W@^XC)WD#jY(hD(2OdH-6p{$MQ(h5z70^fkqYSmoBjP_yUT zXZ9C+yfvnqJ9r@&RUC5`1$&PptL~d<2)f8q>^oGTndzmRh`C3R_33WpLvLdYHG6V- zsi&yZN1Mh*Z9*_AKS)A5r5;4;R7XRc8$C|69+fNk9k|blP?I#Yptl(b+h>BI7KB*c zapJzikEN1Hm7HKy*|Uqt-OHB9=jXiGv_C*Rw3A9(^bIi-rxn*w-e4m#gbAqGd&0>f zVv^xp>2=EsXyLA#$TRSRvQJ2D96u=o%{`c?JbA4)hUbQY&@UrIT<9?MHZU9ex|bYb!`kayUy?-OiXg?CJ7f@5R4+GnJA)kwer4X zsv)Wego{s_=MpKW35McKdN%sJ`b$#nPqi`Bg3w^W9MM3bFMTxHtb|b>=d;k!6r_wf zVyYpwkC-Dqw%t!Wvfd*o>cnTGCat9;-xyO2HM^=dW3KqU^CM-C7E=+7f?B?s5NNcp zY5&!x>`eIQ)(Ek{#*p~#NaNbb9+AV&&&M`x_knFIPK@Z#MPXleAboJ1KmV}*t%Eiw z3rSDA69}G*u(yPQmMh}wd(h0C#v+Uo_v)aJV4N<8^s^Y{NH>&rY7db!tQ1P;C zqSZ-4PzyrKt3MUv`*o-LPMeD`%07G+N|};Dde9UN(fR!cg=2yXosnZH!l>0&M zE`{W}-_;PS(iLdi(oXbabz4q2n(aVt-pNF7TPA{A2z!B8-~YW)q_4 zlF0W}c^aa_0bf)t#+EAbI&wmP+);$b#*>+yA0nvP`)V&(b{Ex_W?XanwEt2gy7z*cIC*RW((Zed zOfM-yT?|u@cm17Y&yv?jXGk2H8n&0T8d1v5?vf&=qNE0O=>CkpB8+nGr$k$~3FL6v|z#MFVt3iZH6v752r5>5Itk zUcWSi=iTK<$3UPh;KV^O4anWWos6elj~d~talHtd zQbj|=4!DXo>L*COk|%TGafbrrC$uLW8&$(l3&O-JQ&Cx+!&08rR1rp@z=!CVXi45~ z)7212#h;FY9 zSAIEK6GP2vK+Muo4zU|W+nasH@Cp>X-pXH%n%>w**<`{fdSJ*W45N$=bV}-as({4K zI)iwz)4i3`j+vuqLTg^Y>#b0;_s`GtaIzadidt{^gke%L+)=;WLOAn zROeB2=mTEB>#a}=0xk_ve3g7?#*r@=MqR$pSK-8JE-iT;hj@|uBt>y$g%3T`=_@DT z^;W0_;Z%O6!Y0$3K8gE|VO0Hzn-yi9ACcQT;}I{eRjr2FZ}6r&e1C8P=2TD%LTg7O zR21b!>tFhfVbqVx*A+iUJ|v!>6A>>?*S10S$cyR^5=1CqP6ai4Drk)(%KPL=Z%)+~ zVU$tvcZL3sdt~vGB*cqT2Zy733q7fhjt(baP6ai4#%uE!)aLVWI%Gj*5k_Uatc{M< z%_W%wDB{Ifr$y+f$8fr(cNI>+oC<0|xU*;}@*6yqRvxb_!l*BT4RYV)KZG6)*W(1tsi0=xiJP|*Z8aN2(_ZR}Fv_$`PqZNG7FoGI4e{dE#RRmtbO6;6 z4LAWaB&b>ca7{#gz5CPDS4JX?a*Ogs)@j#BI({71M$yEjR%)B&gY405c;zyu^`O8MYQ-RE^f#kk|Z^q{Oxe z@xroEGc5G#NP`R8asp;#P_ue6!`Ty!S@twH$yS6>DFORY`pQFOp;ZauMccUcxORv& z&Ar#26EJUsn)Q#Ac6iB$)-+*NClN+f(>;M+=|koA>`jym&l$0xqyHpfQH-oPb#v)PhiT=}3IyP<84$te*&@=B~Po z3QgvaoGRLw7w<=eVUJq^eQG<16EF*dntk(S#Uy;#`@1wqZ>R{P)^$lo?h8hf^FJzK zUhIxvgij|vk$jUpIRSGjs0G2VT{t!x@lYCJ;Vr_bch56W$${=9@=#UG3%BO0@wP2Q z%C9|!6ELTOS`cbIU5G#aN|f9J#)>fN{+3*%6Jbs+MeAW+l%+)C-_0YX7L5Zq0W&11 z+5T9#0#DOkEBW1oKckDLsguCc>!a zHjk0ff>33Pjs}<)8SkR84n9d-)24G`eZ8k>hvSbV=e`CQYIgrTWCPwT9Vf^pScFk) zUq40>W4Q&Q(nAlRUkjf(bVL-0fw5ry}EvkGOh6hIxqMxhWQ}O z+xR=92a_f#D|ehgzgD@6Vbr_UHc8eY`NVwJd5wFiE655b+GheyOU~c~%-f)5PrSr$ zbShwNd^Ed@VU%;kCZ~BG`Q$_DdBlsm-;xw}s!yQJH}C@HZBVny!{;w4GNkdex*#EauoERnz0cxqFa#R-_VK`jXLrB>+Hdw)7%TMmX%o)M7>RQUl3 zKSdBP8tw2yeWv--F|Tqt0rNJf+4l#P6VZtLakPKe`xr*eD!rf>-SQq$R!&B|SkZF> zI%GYL?$mzB37EG*&7LEB8-w~z8%y(xA7L0p;@>J3U&$dwr74IPCv4B68teS%sYXvY z0rNJf1tI%nB079{3=LUXgke;HhXFeJG?R20dKvLz_3C@*%8b#}a`FpKz`PA=Ho|>= zfXw^*(nfKm7)IHQY>7-w?vM#5t|4ByhHBw@r+nBGhi^Fn^ERm2`Cw0NZ0qAqpSApm zVbtOS&dBlL4dNAk3-LnfSqJNk7)jTx{K^TKw?WN*apLRXJ^3T(hl9T`jC$U17&^V{ z3Tbg56Y*lqr`9-i^e{T_p_T{*%-f)5Rc@}e#t)N+&|_;Wi7+bi#1y2|P9Z6#_Yg1Q z#&^XyVIW-{Qk4@hZ-biEZ{N}d_kHU@H@oVIFv<`uKn@p@NXF$yh!^$u4#%Ur^rdfB z=yL+*ZBVl(u_sd$~X8*Tp8m=iE>gPJ|V z(m4>{tlFKvyIDtsQ9FCZpy1ud$s_j?#0%$Di*TDVXX>%9J||$_1~t2b)o~#nTZHMe zX^lh}6*h4vntOdevHATL@k0N=I()IL6CJ(EoD(o_gPJ{=`DqQlcF%#P_p}sY)VLo9 zk@tk{@h!=Wk+i>&G)--5KOHRPN4Qf^|JZTHwbiXat#;rvdrT--s^_&w$eD!}I zUNqf%1ZT4vqbFT$I05rEsM)Wx?Lqutp9LM+++KuHq4|l3mMkOF?6oj2N-ig29V=5R z-RQ&#n72XAo`852hi9=bB5s)OB*LgmS;=U6=UK$KO(o2W9lDqC&>vN4*jHyxz`PA= zwm%+Uz*N5qwf1%qVbtL4D`-V0AL3S21@oe%b_SkP{f!j9){PS|Z-ZJ8b{tE`HI9@> zmdARDFv{Y7I{WQ%AuR{%VqSz#%Ew9QiWFYfj}tI&gIW-pp2@{O`(BdLn+*_Qly?10 zRAo^UQsY~7%!`?hFK}7fCTaioA)J7D8`SI>VZB1!^K6V{dw!S*qZVJxMPkb`RX@tNc&8JvM(~gyhu^J#cS#{ zkQ@@dIRP_0sM+_E&b-21Ce@Q7Lw!UTB~^WhCJhNu_B1iXyx70%9X6^HM{*)ZaRO#~ zPz%CA;VnMi<1`Vf`HC>=x^_OY@cEo{a)Tk}g-6aiylGmI(tIf|st(OpWtLTxh8SvA zWpnCYWrH0-bou-f7-o<#Z{wc?bpE_osn``nd(Ak3VU%88i=_N(_lcHPipG!l!i*@PD`Z-bis8f2z8g`W(fg}x^+j9M{py;I!b`($y$6vT@QleLlY)F5iB6Uzyh zw?QokF^?*t$9;q7@Pt?lqqetHD2&eEBRl$DM7+>vS>Mm(Kw97a6enQb1~vN*?_+DV?>@Gmo6zWhZjuS9%gPL8xn!gL3-86-EZgm#J zs7Rf2imL3JUW0~SLA>}_^#fmn=C(woMQ#b+hHmKSCb1hR`bHW7rqT3}5qq0iO(55XnNyzUzh!^8F*y83* z{HfQhtDJy&8`SKJY}M`Xi%sKbQOb1;qsH~=gt8RZNMUL=;)S@X53ZFyhU%x?;RMXv zpk@`VGx}gBhcR?|mrM+!wtei24Bb+R`P2J|7uo#-@QWNDy36=JCt%(NHG6Z?CjcL} z^`UyFA7U8QJ=+hRmMFQ}r2z3_n$99z(9)A08&t#zn72XAu7wvb#7Cx&p!bYkU>H@~ zAPl{VI!BB%pCMkP4A_8u4h^O|=e^|w%-f)5PxjZ{fFqs_qNHCLhEd5jOHn}XX)<|M zDdNR}+k5b(A^oW7upgX&c^lM%U_N^fKDV+j-Ea9D!zj!6b*Rhnqa?7>d&CR7X{WJH z3pYA(XeAK}n72VK2(Q1L!aoQ0pf<|NB8<9tVKW;4c`sQu=QHBP^Uf)_|5uT&p?aKv zc^lO1Ti81;;5;*t{%Bl7gi&Yu?m@p2wvvunKM*exStj#~IMAj2YHfo3&=;fNFWa(!e%nOSbAMw)~ji@rrj1w?#gPL6n5Bh-D**9d*mzaw%%5Gy4GJg_6 zRwh)zyy(42N4(fepFTEi$qAUZLCww})3wEA3u@3uBdtUjwd#2aYSYb&oN2F%c`-4# zx_GSb7fGU;ZKwEuLx^7e8=%!_T2W@6IECX(qO7f!&u4Qf_T#@I|uYu`j_dD%sTQ3IXt zp_}G2lr^1dVP4F9Z7z0idXBi1cH;!h^q^*EEL+V*w?2vFn7ykAqw=TSNA6udCC%Mk z3-h8?u!Y$DWr=c0JTHtM+(#dNW;RvQS{Q0Uc)Tx5xqn{>eLsI0h8ZNx+xYibW?#6Y zblx079q%o}Fv{S3lcdpS@`&F0s~YdI#Mge{bVmxIxubXi^ERjjq1lc?r!fg3^iK3L z45Ka$Uf~oRokzOvxr%sU7-fmNjt!yH$1djt%-f(Ag!ieI$a+i&9XWkDhEb#1*(>sn z=MsZE*AOqxA6tiFj?AEAN3Y}r%-f)5N6DIX$n^LOdUn7{45N{>DCa}kC~)O%G8$zeUL1d~z+LAC(gz*4a02FSP_s93?7)U4i)k2kgp%-f)5+3VnWIBMVo`rhCmhEXXUyQ9mOE|QtE3K1{* z7p%uMtj5ylg|VD~c^lM%uF@MqtH9k zy=2RhUx*j$EMDV%%ev8_u?3ufc^lO1T882^-Voo7PA+@QWp{fUZb!quY#|FWv@kD9 z{RHuA11IYLvy>AsZ-bisI)@0NXCEiJ(y^4w?t;;NG`n9UIoPcd=0(3qJ+X9zHT`|; zD<@#y2DKn;iq{hz)?3q27r$`XUBB=XsE5H)VpX#$=EYs#+Tw=-GwQ;=)CB)7%-f)5 z+0yFTqG5e=`k{l42&0~s#iI?4Lr8~Bx|kPZ);AH|?;6q__IjLvc^lO1E$mB8#DUdo zQ5#8Dgi#ioB{crbNYdlnE@IZ=X3|Ucybp|;@G%G7c@wN0xyuM^i2L2dFFPn{_0*gbFw=ut5FV6u z6VqQ(vNzRSgi*Oe^Uw>EPf2%+jW92qFS&}3mw#3^_OakZ!}L7W+ZFbLF@{IR5zSDJ?e&G)P(z{NhNl<Ebm13S#4(T77fp`)1?HEd^6-Lhu@5u?6w?WPF_N*hQhJ6?v z-Ju7DQ6&@SD28celLVVg#0yX1E$aI-lulXJhZ8VwgPOf1sfU6)Ls}yJ!x@IRW!FsM$5-t&Ui)dI)VWe-MUIZ$^Jr)D65vwh0drFQ%**h0hO| zPKCw3oPc>7)Pi6#-Uk~ir&If2PYk0Tyfi|+o?Rz{{R$8-(CvkIi)#>FIBX&(VBQ8b z+aCiL;vyPE_b&0nFzUmpmMHV;6|&O)8RA9k-i^4$&Pmj5ZU`q}-UhWG%)=Y;Bdf{u zQRP4kqgH=MsA_|Yq@_m*;>EM%qu9!0JWZW3pBErcgqppTGUF&NEg4T^3&SwX?yRH% zX#YJz*6n_acrjCvj9+&fLz4z9;{?pxpk~zx4U+M%H)H4&y+s&CO>5wfl;0D`^E#gp zFDBQ?!u`g2(f(;`IRW!Fs0HCmNoA#uAjY?+EdmC}3U$T>gctw(3V$J>AI(n72VK z2wPtM!ofQIX(gMjTy{4xYb~<0-AjJ_(8j!2a#dHny{9|<9DIlqFmHpJoo$!uib>0R z&|gRQa@pPNd7DuCc3X+(^vakQ2iez+Jptei(O*%kIK1 z??U6ZMH1^PRWUDaI5rVO9c<~^QAwPDc^lO1nY$GBC1@Kvntbgnm)-ff96^PFOG$*E z9_B@l#;wJL$1JGPi&Rd)ybWshRI#$PXnVLRB~y~Q?5;%b40=@-LekIIz`Qut-$8WU zVnidK-r@wz+n{F8s_AqT53V<+I(x5i+1+%#Bs6A)7a5sS6Z2xidS`Kzl@>kpBbO5} zZ-bik!GT@GE=JmPu|X!6-R-hw_a2kGl7=CMm>1T&dWnxd=SU%ePdEYdHmKRt31@qY z-(&Km=5HQw*&Y6L6@9$Ym=rZL!o0ZnW}p}``+!tU>m?^(-UcxDrUxT6!CYTrY zBS(n?W?dmwLf>%$W_nPwy3VnqM90Tzq<*`%Ts}DLat=Cr|5K9LDAopOPY}>bUy)AN zBAt%B;{?nsp=M_jhkV6PeYMGCr*{}eE$*4C%0({)m|$K6X9tUi3w6nh6;T+z=?mWz zhMIjhJTX|b4XZ}(dqiUx1^+HDbk9#09oJ?M+r=9=0pFH}S`dEuPZxcA+$P;JqPcgf z;r8LhhHg{EVTbJ`&nl6efbWSz&5qr)Aklcgjg)ycntSIQ?q^=O44*8{doxFBb$2Z% z;M?m^voCHXM5S$FhiJRUXlJ39R zz`c17`yDT;4Dk}}vhPdFb}!}xtR?_8tJ2$Nq*u?+^#FOUf6@W8@q4rd^5bm9c8;sUiGTz;!BzA5WVV@LMFFbd{vyolbZEgEDDrN_Ua%)gPr5O=)UD0FpPqEG%xzp&c)Mj z`BBqR4LAX-13}HI0;lHUeZ^zwj?1kvjDqI_yfBQqfZH_=pkD?Va{^X5f|`AAdtwS6 z(su%NJ8OYq6g;otMOdGs*yiLEdZc9yPQYqSP|NSc9m5?yO{Slx*T*mlo}ckTY7vb~ zH%+5MUR34;tU3iXy8tQ1;Ef-q(y^b6FpPrdnY_s96M?TknL+dR2%Lb`v!G_V&&YW= zWzY;7)U^hNQSf}37vj-D*l|WEwQ2K>tFZ-ZdO^*u4z3%DorO@^$Gr-MQSiK<7e{m2 z;>0OobiUySu2vYVO$IfqWpTy^CmDv(P3N^RjDpuMco8+IDsJ{YoO;H*;cA}28f#Fq z_wIh^V%@Xh)a1Z-uC5xq4#SHf<5JMa#&f7+Y$+#TtvIL!L2>^w+WmGmZSL@qs}BdS zC-H(@AAv$X%%L}`zvKk0c?UJ?gPlg9Z};ZV30vQAb?)GGFJXc{5mb-9;smS%2sL|JJ*5%Jwv3?lY>N?$ zf>$^hMd1!Do+&H8=HEmzS3E`Ri^NU4FEYUJtt9p& zU{y=pV1J>~bkl6^ZKn^zpQ96jt(5VfYGSAbVLW|{--i|}OK$Veq{6=opHG#)k76Ol zEP12MG3d@codBcYa|ePjF|1owRP*W3M6c4@k zuJm3+kt(oB5TvUpO?s1FM0$r+nuww_mEN0RL6N$Xp*QKh7eSCN9TnvNUc%eG`F8a$ z$K#nZ_x|=~_e&-($t3w{m`?Cx855raiGNN16Bh?m?O_iYvDn$MwY!PcB-W+)v?jyo zXVTO0U!UrXxblMUNlfTMn(joJ(9=9OyO2(G(f@1_d};{ZuS(DO{k@a9=vYoYqkIkD zeW^&`-KU1pdQ>iJT=gp|VTnODKGy*Mf_SeSRjboZn3B2=-oORfPTdDz@2EM`sK1B=(%%f{whG8H5vAO%r#l_1jpNrqaTdG(DD@aJ&dk-%yjr$f1 z{)vAXn9+K#T!zrSQRfu5TT~cOu}p#UZu?Tp<)LH#q9~j0_yGMyCMWf zxEZ3vB^oX$Y&N*OFG2(fa5In)7t=p$1M>eNPwGx zgt(Z_z2Rf^+Q8)zf+O4vQP_pVpXEO^KRdW8LIeqLGmsD$(__2LRBslW9U(Zv%@BoM zNF4j_3o}i>MG+!MfSZAYxR@S(`#W`f`6m&ABisy8*o8#W>`TmDMC*z zu5;fz?BC8sVHXnLTsv-F>Txkbgfoy37t@>SoKvZ87K{+IP~P_tga^sAfn7mN_WScJHkroX15wZvqf|F;r_ zT}aT{W73)!A;K9*h>K}jD;2Hn5rV_q?;#4ikf5!=q%A5!gfoy37t^$LDcWiyL^wkf zb|FDqvq>XEga~IKAugtAlu$JKM2K*PDC|OlMkSL*xCjx>Ktfzh(`ct?6paw!3{lvH z1dXmHjnok$oPmV6n5I!%(cU0Jgfm287ZS9WFlmnyA;K9*h>L03`zYG0MTl^QDC|Ol z_I4)iIU__k0|{|4O?y#Ad*=ud&JcxNNYGx}qzWKHgfoy37t>Tfgs94h5aA3_*o6dD zA0|~Y5h9#{gt(ZdswPC$QiKR+h{7%;sEP_uMHV5#8AynWX{zVeQ9TzS!Wp8l3kj+Q z15^#V1ifSJ`U&Sy=MHxF^a;X$TPEah!~OCbx*zQ$L_vbv((e&nR?c(!e%8~?5CvVF zA-`cXAqo=QmVS>|KcT+!PS=5MhA8Ob4EYVC2~m*Xw)A^M@8wEWyEN3z5CvVFA-{Sw zAqo=QmVTEA?s;QFV8e}JZiXo6;tbzk&_{@Z1h=K%%LpDzZIv4~#LW-|U7R6nOf(@1 z65N)4k9cF(2UeDO{oD*u(8U?D=0_8vAi-_v_lP`Q)>`wrz2|0#f-cUGEjXGG1qp6T zzejvJ;&*Gq->uyYQP9O1G7?1-q9DO->Gz1K-=?!id{EcT5CvVFAtP!uAqo=QmVS?z znYV}?ELO?Q5CvVFA$x{sLKGypE&U$x{2P}2QlOZdAqu)UL-ugdgeXXGTlzg>>&3V1 zG>axO^AX7x24}BPCprFJD=5b@Uzgx{c?m9O^AX7x24}BcJ=6GH)u7}%@74$oFPYg z(S#^Sa9jF4;@;GbcBey!-3(FC#TjzM8cm3T1h=K%BM!`LV&^HDNaJUri~HrsJDLy$ z32sZjN1XVkrhR2u4mU#-ba959L5LSl<7F3zC(F?=S~Fpv-h32sZjmqE3tNwuh(Aqu)UgX%~3TyHcX z3KHCwevhD9G(@$in;{CiID_g(_uO(cAqo=QmVS?*TGXLh)XfkDU7SJnWB5EZoy`D3 z6ePGU{ayyuq7K!fZiXo6;tZ-E!{@2#?bbkuf&{mv-^-v{)S+6`%@74$oI&+t_&hZ| zKLH3)kl?oTdl^)VI#i3g8KR(zGpK$HpQonhGy)+C65N)4FN11PO|__-Aqu)UgX+id zd1{*P41_31a9jGl45~#n)uL{ODCpu0svpDWsp&~jK!}0_x2509pjuQ@E$U{7f-cUW z`Z0W-n%=MigeXXGTl&2Wszo)`qHcyL=;92jEW_uiXGv|I7S&XXy8BvD z(8U>4KZeg!8wL`hAi-_v_cEv!)l`eR8KR(zGpK$HpQknqBt$`i+tTl4P%Wyd7Iia3 zK^JFG{TMz^Z5T+1f&{mv-^-v{R8uYLW{83=&Y;RNe4d(~F9L)pNN`*Fy$q^FHPxbS zohS;rID;z7@Of&(KtdEGxGnu&2GydPYEie|6$M?KA!nnb2~m*Xw)A@h)uNheQ42o{ zUEELgWB5F^VIUz265N)4FN11PO|__-Aqu)UgX+idd1`t>B@m(@!ENdHGN=~SRExS9 zqM(a2(mxCFYUq}C ztsiLK&i+M&aP4skbZxo)sk-^;s0a~cgb7rTm|f~K^W}0QBZO;@OQ5Uw_cPRk4jm#y zkP#+OL1N$LnP%DUZ6kzhk4vEI!#iKA{i&=75oCl3RFFt`c&WMbaD@or+T#-FYWLw! zs`ZL=5hBP46R03D@THYz`dX=P4xFbB@ST{Q9ev~ z3q{`?32KL3L@QdVK$r-B4^)t#r8ViBM~H9+66m5|LD8=pA;KA`AVI&nNq@lz5zasY zUG&#fw3e9B-vbpSXniwjO^guX3?$G+Yo(&KJwk-P2P#O=c4N{O6(PbINT7?hE=5~y zga~J#f&^{k*T5h9#{1iGlI zSx0qHgotE-f&^7j6{(5}6Yh)@m*QHj+1eDLbKBy(H9VbXa<6A||MbP*R;+(NzB{%@ z=CGi`Z6xRnQux~TKNI3&`n_+b2i8rA7b8Oy*Y)gkxm{v&cQa4!D{-#4<7c6Z+ZApm zGVAnw5`z#WE>Y!fMYI3vdl7@-nmf;w|p4OGg>e^DNyAQQ{Ky#;rHU zpN~72lU+!Ni~H$lDSDozn;{CjkT|^ffcYrl^ccSt65?W-j{3}~d6sU5DC|Oljz#^m zCd0q3C~=95wSO_6t3M*LR6$1Ag@m}cAFup`*F={Pg4Z)xJ30@PtB}lZpO%v&tgJc+@^Dx z(X%GqZ!St)g3hq|=Roooa{q#fEQd1zjoR@@AK^B}d{3?#(GG@U8-&w*sr%@BoM zNTeKj-FzWqn;02Lh>K}Dl%OXH1L?B*euuow<)O2ND%-BQgE^ zJ?0K`P9%eu%Kfe6vzQPUx9JK*j5&~~#3e?h2$|o^Ul}7qK8p!)ahtBB#Fzt#N?d~W zT_)`ZV`Ru@F(EE)(_Srl4y60dMTtw$J~76OMs|r3m!Q42Nfkhhr9whnOw*p)Kcg|c zmPj4NF09CecK>i($+-X6B}!Z(DkDgU`^~Weki9602~pUE1YW`N*NI4oi)pH_71ixAGDKk)5^|l27sj7~gt(ZdBMU`GEHN@fVHXl| zohmv532`w^M@Wi}ykcaC!Y(A_I#qNA65?W7t~!MYZn%FzB*eu89Zf1anv5(}PzX`* zbGePzqx@?k65?WF=Dx{F=QtY4;0SlAM8VJHHqC(Y-)RwyMTmLcSX6daXPEhY%MN|LuE-3x9>^--^D6JC}=Hcut1SQibUJmGggyXD+7ctlBy{ ztM-2gaWO%^bb!v!{U1VHOwcbKpufleA;iT5{n94=J=DK{4{-`(6TMXpDEFnPEoZN7FR*O0j1PoNTu z@UHyi{(g|IU8o|l^z^J}*S7exq|Gk5hU8@+fl4gG%Q$kRm)>+^nwx=ywAm%skh}~e zP>Dr&8954c)YgHcZUz$4W|v$;@-mP>B^KdjA98ix*14Fn_Y4Z$;&_jl~{zA@oG+bdfCqMZUz$4W|v$;@-mP>B^KdjOzV+F z*KYr&n}LM1*(KMIybL5ziA8uBi8eiQHmz^zW*{MLcF8p)F9QiwVi8_O|CNq&abh<& z0|{xfORgb#8AzZKi|{fsEdIbbyr`d>frPZ#CD)L=3?xvAMR*x$vnO)y930|iAR%ox z1+R=rzn8H--$OG)o}ru(6oo%a z+U$}mW?lvosKg??j5$vSSie^4?`9w&ZFb3(KQ99bRALccMkZ^m)xGa~ZUz$4W|v&S z^fHh@B^Kdj^!((WWnO9JW*{MLcFC1kF9QiwVi8`(`eB*u`1|U(8AwQ*U2;YF+1~>Q zRALcc#@EeXwD)(f=w=`xZFb3(aW4Z2RALcc#~~*E?q(n%ZFb2_1up{$RALccM&?`{>|4c7@qRFfgtXZuGcLRgBv6S(cp1yG z_OfdQXS*3lNSj?UbHvL)0+m>Vm$4@>$R0W6H8%qZX|qdaz<3!*pc0GlGUjz2X7?-c zG1pf?B&5wQnaSg2Ac0CO!poo<&ZZj9t(B3GHoK^Da%Vbu8AzZKi|{h2BD1N6bLe|; z4Hy0_X|szeCwIn{mw^N-u?R1NDl(gDI5z_cX|szeCwJzVmw^N-u?R1NDl(gDI5z_c zX|szeCwB&&mw^N-u?R1NDl(gDIL*Hm64GWDRZi|qKraIcRALcc232G>)o^YG64GWD zRZi}VMlS;iRALcc232G>)o^YG64GWDRZi~AOfLfoRALcc232G>)o^YG64GWDRZi{< zQ!fJvRALcc232Gh)o^YG64GWDRZi|qSuX<#RALcc232Gh)o^YG64GWDRZi}VUoQg* zRALcc232Gh)o^YG64GWDRZi~AWiJB>RALcc232Gh)o^YG64G`vp3SZHGJFImu?R1N zDzb`H!+9AoZNZg&;A}jpc0GlGN>ZcRKvL$ zNJyJqR5`ix!o3V6P>Dr&8B~#Js^Q!WB&5wQs+`<;;a&z3sKg??464X9)o^YG64GWD zRZi}_a4!Q1RALcc232I5YB+a4h=jD+MU|5~FWk#O0+m>Vmq8VorW(%8KtkH=qRPpg z7w%;sfl4gG%b$3->aRKqVI8Wl%+?sfKgwDee%CON z5CsWtOTU+~VoDt+?RNv+?;#4hI77}SM-!qT!ENdHh|=w6IE|+Eax+9h7iY+P*l0o& zB)Bd89#Oo|erLefo!ksj(8U=tA2ym01qp6TzehY*A)c=Pq?wx`3c5Ih=C*|A)*1#9 zq9DO->Gv{@G|Q?ltbW7I5CvVFA+uqk2~m*Xw)A^M^_9i-Gz11?+w$v zdVi$wv(Ux;IO~O;9}R>kNN`*Fy^KQJhUpdKi<elJw#WJ zpUuM0LKpYTOqFOt6ePGU{T?yzgMNC#&JW!TQP9O1IP1kQkPrn4ZcD$HQQ+}=`jfG% z+ze6B#ThbFC7KWg32sZjN3>k>uAWigs+%DSx;R5-szei_Ai-_v_lP=68|dyvDjPow zUED7-RiX(|kl?oTd&Hl`s_LWF^0^tJpo=qP-bpke3KHCwevjDQtfa0oubi793c5H$ z=AA?nq9DO->Gz0+eRJsk$7;G6qM(a2WKKvlAqo=QmVS@0RwdRKzH97eh=MN8kQo=z zgeXXGTlzhMYHEjSYBxg^ba4jN!Qt5=ZcQB~L_vbv((h$ZP3=%k?PiFAF3zAjI6Q~N zFpv-h32sZjmq9hPLp8OVAqu)UgX-Y$%o@W$LKGypE&W~w)zpe=YBxg^ba4jN!S4NE z(S#^Sa9jF4f@31`NR3V#GQ@a_Wpo=r84i4W- zX7~tEkl?oTdl^(yTU1lK8KR(zGpG&@-%Dl$kq`w5ZcD$HK{d5SHMN@|3c5Ih>frF* zXGRbSQIO!a^m`dpQ(IJ1yBVUOi!-PWHsvllBZ!13NN`*Fy$q_5ZK|o=3{lX<8B_;{ zXR8}QBt$`i+tTl4P)%)9P3>lgf-cUWIygK}-v}Zh3KHCwelLS+YMW|mH$xP3aR$}F z;rk7YAQGY=!ENdHGN`7usit-_L_rs4P#qk;Z^8&7Aqo=QmVPgTYHFKmYBxg^ba4h% z$l?1xj35%CAi-_v_cExawyCCe_vfOZi!-PW4&TRO1d$L032sZjmq9hPO*OTfAqu)U zgX-Y${WwMt2~m*Xw)A@$R8!kjQ@a_Wpo=r84i4XmWCW2A1qp6Tzn4KZwM{j(n;{Ci zID;x=OYW#Lf=Gyh1h=K%%b*I`rkdKVcSS)LXHbP4zB9}SA|VPA+?IYf!=RelrkdKV z+eJYaXHbP4zQfJ%5uzZ$ZRz(isHV25rgreN(8c{!2Z!&}qkSz9q9DO->Gv|ILbj=< zb~8jl7iUl%9KPewt*OI=C`fQy`n?RQscovM-3(FC#Tirwhwq#;3?xKBg4@#XWl&9R zQ%&t=h=MN8pb9yB2Php!0U-(!+?IYXgKBD@ImYT5Kqwv=g{h9_R%yql12TrM}2A*(_G=U}$2Szg4~Xd>`b_)|;&|r(e_KuEw`fLE?*du7_64 zHJsTkn7DUjtMzr=8hUE+KP)8Bl`8wz(DlsmosxM660v8(8mrRJZ|HJ;Zd<4zk?zsy z(47_uoNb>o(ff^%)py?8y8Kt?eFVDduU!>-Cr=`0{ix&rOBM)Ckhdf?gG85cz*}IY3*DK z6(q*BSrO{rHo0@}FD7cgG2SXLwzIx@_H!SBE_HoMs8x*=PQ91X5K%7Q2iA*8-qXV> zjj>QcV&d;#hq@e1;au&`MC$z?SUu{!ugjc!&qtu^t;&-_N4uqTK52W8wvV5Nx3{wW z-BaItxwVA~60h~2AKG>zrSs=&_ldYww7u2jMsJ-WkLe@O87{;lYKbS2WHqj5aC9s>1S{(Z3n|ta`zscs#yjwy$FWgt}E}LYoUOFR`weer7 z#eH7e*KC?*)?D9IpEwiGMg@s^2Udr4+s7(i873}FU1H9f+DboteA_|-UA=})47J~8 zI1?WYBBIjT3Fheot@XJkH!W0<7@GB)P>NULImxH-_OT-49J9>P_Bzv|<30jibIyJg znx7`2vo2ptB3jNKWfs5MLDzoqh=mFg<3`U8z0onD^YK&OKAujQWS+g-Ro5x)_y}}m zI4~@9<8fjqOV(G3cz;hH^VIfky7dd|EL4!F)@^cVp_Rn3D^()mQjU@4niD!WKt z{lrJ0YuNp6p^bZzJA<3?+CHSfo96B$ef6uk$6BZ$QElu;p<}m_I|mChk*r;PbKtW6 zx@XgFJ_23Ox9b|JmL;V#aMWE|+wFc8%(lPv*DJPlwopOh+|H4qp)aI#>g;7AW76{G zt)zo=yV_NJ1iElfWEeeX%rm<_8lVSOe8WNo3EXZBBkR~ycD%EN^}M?AZQKJa?4C?r zY4KE5sr`kCqqbqxuaVfkz5Hc;vGZdK6(r_-A5Uc+65si#I?ouaUMPt@r(kJ4r2AbT zfi4`i4I}A^-w={k(a`N1zKwZ62?# zTYZ<;&~2I=vQR;y^B=#2de2YdG@sFeGO{1KX^l+vy8f`qW*>nr9JLMO;it!}1z*(H z*_W=dP(fnomj^;u&LwlMOyupO&08m|O|9S2H8OndBhZDTHtnMdZL_*RXs& ziJZZ$p~cNpIJx@p_EDnYb}N(JN@wWtxsN~>j@tB0=S)9Zz3R8u?U#(SP(kA5PU}Jg zrloYQUg7Oy`jQ{5V6Be&g$rGM1iEn4roHpuv#ib;y6I^X8d<0yvF!C9LmhjjazgJt zpzUMLs##Y0_q*$5iHrFNbouuNKg|nT3)j@q_cAB3aXiP$3CCc=Xxr>P>$Q0G^v3)N zZB&rJn#eG!bn9(Bt@4gu^TQ(x33TBYY#0@{x3V%-Yoa%7xnrS%1XfXo(a7pxeYK~B zK9%O2k3biW!G^J_aUCnihSqvX;u97sNMIFZ7;E=8uqt~2g*VP39O>1rvBkoYu%2ny8X_@J_21h1{=oe;l-^ZOWxDn=FYQFK?18NIuHJB z2`l}I9=h(@&wK>Ba15q5TmSUDwXS+EeJ%Z13l$`=iZYCRrE^$McK6Z4Q+D?e=)y6W z-m04~g*D?&U!9<82MZM>u!=H_+$)pQ`IZ6tjcgTt1iJiV`^!ZZn)j|Z(3jJt@U87w z2U+&k(72U%)E`r(&{i8i_e}G`g@!ubnq)RANOV8HH1x~O+p5u7CTjjN)vUI(zOMLE zDj$KaGFLW-hV{6mau1qG#DYWP%#SxV&~4YIuu(yx^KZ*Sf8@TU5|?D6ZSl{{Ed%T6 zPYR~-5$LMW#0fphbWP1)IiHBvJHBsr{G`5ae=(Jf3KCBiE(v|}{xvml?mQxre$v}K zaJ-%#a5=S)K-b3SW`_nQ{!L}=v6u*bF{M2a-9$F-`*1HBnwW&D%0JZd%zXd( zoFWPASL&41&J@E&1&LmR9)(`qO4l#eOeNxyoxr}Zqol6>{Zk7GbY&};P+jVCPYq8v zmxv=D{BE6V7|@Fj{$ZhlM2XaQL(B5sQ7?6xO~lr!zgzbwSJHPkUiT5`y4&K9Q0c%8 z_2T0tL@Z5y&?=w3hF(4YmW2uu-G^Ta4R~@*Ex5w(A9VWdvUVPMOLr@E#7Cg(R?-Wh zJHsxigFE;>`tG4U*3N_h-G6=xUtNOZE`BG&XkKK!mEg-NdRL>wHY!L29-j?8Yd1U4#2RPK2yqVSG`(lhyn28~Svsls*Do_?--6--G(r-S6Jk@y;Z*Q9%Mn48ypZpn+9C)!Ta3 zp=3S+UHB`|UhVsG)`Y9|bd^j=ZB&rJ5yLRfJ7ugw6&mQ?FD3R7=<@%%6GnV*I+Yvi zMPDYeam+v$(uQ&U>Q`2(290#v^cO7L4)CvuG>xJOI=b^}Q?@zg{M5>JKCRiH;)2?1 z6u1BA*3snl-QkwAsnk1WzrRDuFm4brX7bt62V40Gbp5)^bTW3WYEDhFo`?fP+*&QlYE%;ea!6MsD-7GMkAwNkrzN1*cjwd|JZ zrPa}Dy=7;OD z#p|WVq?lu&g2cxin}=!~IIhm0VdAGD`_|6B-%pR4In+m>E6ej;LvvFfQ)SojJ6RXM zolV_u-d|rR)5k&ui9?@P4Gp_+RBbG}hlpJVJ_%*XGFTVv^s^k{kD8~;+RJxh`7S~mGH-(z*8>;_Y?U+cQYsjn@LnW#l zQ8QmXNyN#fwi9SMP=7U2nW!M~e9d&BiB*rN5}*IVOI2>1d9Ca)UH?G_g#^0ZZ1#4j z!}~|nxb6JpmH`JpvHr~4QWsjc*Ejm$TA6qKj!>$^=hf)f))3KSS1apgwRiQ^YVv$2Rt%Ysh*IS>PVWEP=$rAHJ zWwM-9H`Z(>B2km7)}aIM>GK<=S*Rd^>olz;c@LRiywF$Y&-$T{Kv$(vpNC$*c}z9> zbth%qzLCv3@wB&2dV7e43KF~z@N6b}k z7FS51Yy7@L=78gU1NuN#A~v*ZWG^)41~Pw_)J6q~4QmdY>#mxCUn?>}|AOxSji9DG zoZKf@^ZgMgb9SjXw60@vo9?c1pEk{H&npDFXAHzO|bY|(-mi3C{^s?iI6a5IqhXP}Gj zA9SCN&KXfeI0K3CU%jl_4_oYJAnngU7u^TxKINS=qKI$?5@pjiQ)T;2b2E_kXP}Gj z=X9S|&lyofI0K0Xtv^sHw~lo)koISwi|$KxpSsT(QA9WciL4_hsG6;Nxfw|NGtfo% z*Sc>H;EX6DoPk95f^$@tl(pRqr2QG_qWgs1w;*sv6cNrq;!>h-R6#43n}M`H16_2# zv->s&&WIwy8AuGe^^;oD^?ZN{r2QG_qWiYpw^GC;!Wl>u46Re44}xw6(*6u|(f#M{ z+ch{NiU?;QL1UHTv4shw{Tb-Od%mIw#)9;pMuNsF#bXO+AnngUm)uJhlL%)ZL1UHT zv4shw{Tb+zd*Wge;S3~btWrF-FoCo`16^`&UrZvLfdq|JipLfvkoISwOYTvONrW?y zps`Bv*un(T{tR@2QWipo=Pt@Uw9K8$lI^NtKM7fwVsZT~t|wpTqOt2pX$Q9*y{WAnngU7u6!} zd&&MgL1UH4V+#{V`!mo*wTS!nvj0xdSY`6q!UWR(40KT~;=aA?zY{c8nLM^IfwVsZ zT~v#>Z!i1r1dUZDk1b3f?ax3L)gtcO%l{_^69VBPNgzX9T&D!Sg=o z;^QeEXP6EX)Cg*HVa7ib^7Nc%OA>zG4%S^!8DSTXxqP(8^nW9;HbmN=fiA2p{Y2js zdF^e3wg%>9u4bn{b<(`|J$6APa;f6P@e@OSRCM66u+yj^%^HS>qlega+R>z^=_kDC{G(t|TL zsqFUp5pS4-pVqWdL88+;XU(2P7X)$+Nkc@lFQ2yyJ>6=K+~gM17tHOiI28|$) z-RWP~{3aRQX9AyvuG>Y=yMLREe=+eU&5C}>{ywlMRaYAoB=C2m87a>1mf7-FVD;YC zJ_23%*EEa<-&D0bbvP2(H7c*2efM$qEO03!gN18M-uuVQ7e6Z>D3~k*EmfM~Rqc|A z4+mzh&1<8A1g<^w&hW}r?V+!2Ol)! zEng6*{B0KN;{yB5hOK@L)W4LOmdeQA!+!orQ7c=X$vy>%#19Xd7qiX})aj6kh_~nW zx8o(KYt4NBp^2Y`uGUxgnF%&rd6x10rPg+@_u^YWpS^6Mg2b@Ghs>&pehZY`&A-*{ z`9tj%dG`k>hy|%`5oQg%G_aPs598iex|dH;|Fe0BlG@hZZ#JN_P@eoNeN@K zHJ09<`q8B>HY!Nq7Hk-ovu3u+OkXfpA56bzp@IZ%X*3HdOG~?zN@V3veaAbpqHJu_71br=}ErtfrS6>@y+YK?W4gq=B!p<_y~02`bHz% zsNS@v>0rLP)4wJnfq#F)SXXk0JuuBL=JXG@n|M76*BGP?BSo9?lPx;SI}x)dyu=2+By4nVBzGH7OrDMX@7P3 z+Ri}AcT>@tSnk*+tH(Px%qvSe`v~0kAx(F_q~BttN_5L?(YmvZE?o2d#Nt;cS-+HA z9~geWw{Ne8`>Q;Gi{|GW@8_#Fg7<0}o=a}6x>+Rf(*pl~5M8(rrddems@iG$A2N?u z%x&WuhijsLY`?g=y*=ZWVLq;O+P6*Mn&BTyb{`vU8Rf2;$usqFe=FJR<1gy}<}X{@ z&Dj+f2ePg9o(HgS+U9(8&zf5^Nd17{$uO1_Xl;j5lr*m{zT+F=a2xb*A8(wRX^u`a zOkXIJ(flpPdH0^Uo=H~(@cy{3Mr{p!m?Dj{{=M}y1AE4_8D{zn^pu-U8BA1=@ZaI~ zBwkl5@I^m;{^Cg=fiC}??YGONHQO~FqF)}8+DchvOz7j#QT1eo{~Gj*KQ9d(Pkls{ zR%ht?`O@I@z}!Vc_0%W3eOIcx5C1r1r9Z4LU%h1d2~%}eQwt2!RX2C@5jbZ8Y5H}q zjZ%x74%5F~JQzS%xdV+tcD=*u?^?f`e&Vfh%bc`n%IZIE=de32nW?I^Tdj1Bgx0ts zU#Zf;^{The)Hk zIhX8;`sIB2eZ<6Jo!!mjjJm0k$rK9b-#aTl?uM97u9~w zNBs1prCO5jq-r|qR}*Q&XngTyYssqWdg+O5Ho7kE?y8cFKCi}SIva;r@K*|}`jppn zkrKIm#HU~OR+)+%RJF$6Hjy@rS+kc@?NnWN=$y+&*WXnJs{A)jssafw$06G69UBZ`6Ca;h9<@#{7^Uz^6{EM3=(uVOt)8kH?&2{wP;BG6;rt#{2mG4xRmZ`1xPL5FN z60A{QypzH*-u^^Q8nsOINW?YVva~y#e*NFpFWfugbM46+R0$8SR7;o99>7POy1vxu zI;n|1vG`{nk?@P2Dnq@EYDk5|mX9`$Wd6)4y|9_CHtU#$uGO16sJn->+WBenIKZw#!Gf+SpX(>9kV~A8c4i)2zu)iaN%Cw)(RLM=W$@SyD%p_;{P@>?Djs ztSJ1KdZlP5o%_fRAF*wARh6;9e)U$@dnVF!PeZ$Is&%GL`r`%rEp&Bx_Z8JX$sRRl z#p5`{$2GnP)q1b1e)0LuKBCRs;_BShqiS@{UrnUxPK)^s&Du*k>n7)STIeeIW-c`& z!y)x)>Kk#02`?`<2Ogz64$CVau_<>JRlnwG)hoqe6KR_1G&84V?&+kfpImRDYwq17 z>bVQYRGlwR#UYHurLDPJI_p!ftnv|=>m^prcb`)=e%oduO*8v{?P{&0J93w1Txp@J zV67XWnh#E@t$FswA$~92-|F{5N8Pr|_da4k^&6q$D=w&`>(`n{8%Dv}Us%mHx7BkF ze`BHR+futj3woSUPnK+mL)=+0-?~tZ@krSuUdoR}0t*gIdwm3Ch z)xGkydO1sOYrzjaRl9sYs7$GIS^NJAs@rLnsRVTk(iU|zXF6Tt^SXNMhJcB#v|sjA z_dj2*)(^=ahv+jrk=~!ViQZGJvX6L}sHM6yY_&QYFS~`bVZ5_Ci9Wiok$z)H0TW#V z{%oTz;YbM@+HnsXcYpsri5BvXG{u3G1#iB~fdAFGnFC zF}+@G)vkb}Dv!!)Ax%$OxO2fNdAzM|_d-1rT@Qy>QD;8Vs#oJ2afn&JopiqYt-bEv zuC$NH@NGb)xVk~@Sdhs=n(hGYxYv2<`%d~)@3&2KJ-tv$Rj#*5UFh>%93s=E?au7- zUG%z1Wqib0^F{S*tu5-+&(m8-8^+`8>m2iTH+^~Jn z=hI}}_4PhweMGG+xz+aC+tt^#(pX5-8J5zEoa=LX=&wJjWuj|!^Gs^aq8%zh(u{G4 z)K%v>Lz?&0W0RHh5oKzpSE1WGRf7{LETj#i^!|y?XFGc9?LSsE(e>5b#Hx11T`Jy~ zv~h^*9X@w-<39SpfKomplqG>mGH$opw<(E*v|*U@hB`;-IrKlJdCf%E!b8_XAFkb_ zI=4s}hiH1OztbdLe?6KqkeGVsx6tY>dsVuT2`r=yaNe3Cc4Tj-5u() zd!JHClg1(PepuHjTVtTUma&wN*!f^rsL9;@>h|k@n@H1L*c)GT;y)RrlWr?xqAT0Q z??Um09Z)&PC$RiPwoq~BK=Q#lS>2L8!l?a2=!4=1)tOfJO{D4U$K_;BvhG84;`%R| z=qfpWVkrHIgQ|YKzvB>#+9YrAoTM)`C6)>u99uT^Vm=cNR{sq&FtdZ=(yVa6j?s{@#xHdTo6) zSsEXKOBlR5MrBDDQnxB5p^(?-dCHTCA@6;=9QPpMNsoi_c%?_JtiRT9_N&aebN0*@1rHjIwVzOqUr zdQ+zuoWOT%aAQ*e)%(ORYG9&0rk|)=Zk{##?>BXca!)M$Ts+=E+Auy#vBB!TrKawe z<_`;9DPGH@1{}Dg>Xh7I`iU`Tw^|?Pt)+8Txa%YEC=6-C=(qB`wQlNbI@!4!zN5Pq z8xyI~1+J>XjaHa`;^mKSSv^x!)kE5!@ez1uAkuV46;*pJvNzNhtL^nwGFWT*iC@2% zYdMpf=+BBC^wn3mBz___J-OvtxhDE-lH)!CYeuB$sS!7aS}(uZLa(2E(pM+qFX|_z zr|x8>tlM1g@A9jUz}gpSy1PGfZtL8^*1Fw*3%+_6*9<=~w$UGE!C5W!WjardpNlm- z(uPs%dE2acu#FyG^ty#ET*Li@E_}J-q(Lq9%oTt52s{=++Ax|JA1J-Nl`c^3uJ8B* zw^TpTa?x>>E<-b&^vF{mfyY!x(=$0Xm2^hlZmJ(wf8aZg!V$+$>`T(#Y0|8L4pxe1 z};gpcd#swp1$jt6n%^b;MQU+JivHFf7H@ofBDJYq$fp7pYAgY!|s zmO5>L*}fx1JO+I4)6S}7`nBrTI=-UVVCF2RO8vHa$*M)Z{21MF0$~^f)6@1uTpGmRELRam#i>X4#e^#&j6yNd_zt^3jMx5`Z&!7Fm zN4#++huX4dj|z@^Vj@jO6oZ1!Y-u#%FzV(RdC%PRe zWF=bDQ@8Ii)<@t`Bhqx2>DeaM##Zm^kx#~0=-Rn*Y3OYC6DrB$?WUh-QMS9)W!3w- zNZ%no0`JE{n(oza@X#6Gvypb5cC<>r@u7Nk;`gfAdzr1>U-eVXhyA45mdI!&h(AC* zzhk+2so`_9eN@PC##uV7g|1(!m(P`GM0-^~%W75E$`Xfo`o(Fd;l>tvTdf{G0=FWh z>7LOqw>fEFXsf@=)y=o9;WptXQZ8NRtWVcofADEv-!S8bl2Z* zeBZaNrP=z5YV&ZjdgE{^%TFvH+RHgmsHg6FzqOCR?G9;rqT}^|(=TOj-E? z=TsN>?Npn}C$ap*;5G%E_G$X+(>dDt2;A|mkmQSG#9@1)(T zOSuG=pIFlLH?{L=Kkb}r?IUozL)tK^7Mi3AKJBlcOV!3g*E^rYSCjtStE^mqn|@;N zz;-J8-vji?-|PDb-0qMzj7diqSG=`ufWGs5YYSazM(q!s-*r$;J9XXk6SrzQfw~h0 z>Tf!{=#uT1-3Z}N_5f}@}%++xZNRb7-I&ncFtbzqH{IN=-WE+tdXC{{MB;j&aiHJ zKwkg$jN2X3hH>!Z9H&kC_w~XI8GKtOo;C6l?T1frh85_gH;<3!Bk&v$(uPsA>O|+1 z?x_duNaiDOOGTRQ;my?5sWiH;UUfOOZ+pgbKz^b|qqfe9qW$!vP%YRJl`UpIGj#}%8$6x7>sJhB2pQ)z)+lpu7@c`0(V##0cTTO1huX7CO@2i&Zes`># z=m_%VkF51aJL%WI_umzd)fs*#!#EKyfxcL-u3lE}18dac(JDi_rK-pMY`$8{UtgVi z`K~kiP<{Q)@`*kIuccw7M$e#IlikXDp|7sEznO1r$7RQH-Y`a1Os;1nudlBZ$!6iT z30xBYNd4~H3H9;y4fU6sU-S|9osg!Z)G>R^Tm^^fs_%?6anFMH)Z@MHbQNI9RI_IC zLAr3}^1l1%k@kO&duh_zi@z(N&&*HYdkPd@GxuNHzT51!wWMDq9Y}WFcfJI#zWdkq zDxK~-uZHUC6Z@z6u4m$vO8?(u>`cz<`WBj$DCMG`-xmbH#lQ!wbVr)%=8gh zAtTLmgoC!s6y_N;GuEWGHqC!0z-@VII=4qPNn@>S`OVsBLX@}!J}KRwfrPl2zSJYN zHKo-Dq38@z*o8#d^hvE|BTK7)C&a~c#rP?$lpj5aWCWRIWk!XhPN``n-DlEo$e+^r zZQ^bBSGaR9zB6_}XPS``_qP&-X(VU~ovZU|(9D`=M37tTLPA{JzvSsd)#u`8F)~D9 z7ZUU&c<0s0hawpq;btHqE~e?Z?y7QeI*U*L{C^L60>48~^AEA>NT~!)qUSoePtB*N z|EsKJZbp79M%@fi;u7y)d!*9V9v9>9frPl2rneZVi_?n7AVgso67+5b^+LurF$huO z5*JtfrsfY?^nVC(F-`A?Q1|YPi9v|ME+lIHd04eQ=KLQ*TujruF4PWlP7Fd6b|FD; z;85SpUm1fCB`)#DrS&RB?nD2F5Es+*CK1)<@{SmUDC|Pw;OZr+SeDEGhY%Oj^hT8M z8w>qwqA2V_;>+(pSKB^%7$XA-aWPGAc2V?}m>7g8>_Vbt;jU`ny!Z~UWLR?JK z8){Vl)%Rj#h{7%;ersA!!quL5RXGBv#!W68d;x>i7z}EEe&BGZ;h>K}@KbCpD)}0s`qOc2zZ(5cz2Ns3D zU^oK_aWNfvTS46QN)&b>ky>>&TkVSVTOlDXrsdrV{G0mMT~XMDM8cmxGdrh#6#3@i z?}3E4n3i`$L}!S?E+jTBTWsby2_r)|0|{|4E$_OB&JcxNNc7R#tXu4GjPHSjxR{oA zc0^~0!Y(AXY&v8%D9O*#d-m%FxrLv_ZE)!f2Mg|h%Vp`q>6V3>7ixsRgq_W`t<#R8qvVZcERpTy|D9=9E ztwp#^*(&b~4gU`zE+*&~QP0&M5g~${hUw^X`<+ATUb*!Vf&q_sro<&^T~Ln_^7CHf z{>_&IAugu7(fpz<%??KhM%@fi*o6eGp=$hjeokuK3?#(Gbis;?)s*7DMF>XS3{lvH z1Z`=m`eJ_iUfc{M#KrX8ET5_KeI7*!M%@fi*o6d*7)s~hXVAsXKtfzhXWrRSrA?T? z3KQILGelt*5;XFu38^l{$Us6|Oea23LX~fsG)9If>_S4`mKa{Dpez*<;$r&p!yBQV zX37{DqOc1Id0S$11`^_8I&-z|q2DL+T|&=(U2b^4)iZ@%NXXj~+2=W;tu=1k_~_%yeg{`r4hQQ{Kve#L($#Km-;aBfC{GCluzH zPH~q?l(@uepEWYKUP%~(5G5`_)wwC}gYHl?+5Em0a zF1l*IxN&}rr4j`{m)r6V$LOU(LR?G??Ea^@V%pdk8KU6la$DZv7@dKHxR^MtS zTI(1YqTuIpTi)Rqoq>e7n2uC&r@3K>z}k6XIg}QB!(z-YeJ3 z`6Z?_HPpXeAt5f#koR`_GTdJm32`wIb>zip z6d^7qo+o^qEPC4t#qKDOTYL{MBk@mF}QtVvK#O#;e_Yv*(9d%u=Pc7x6=?;a$ zt6gG^Zs8+Vki8JsqcHt%=^1qLPY4592U}a7sP=ZpjdTF+Dx;L{{`JQ79b&QB)Co2&mX?%yjrZXPH*I~ zao+rqQsY(W>_=4371vDv9QyQm@;J5jSJA01=dw{jqRxU*D&M4Is_i@1Xx!bu@$XQ> zzis_{fg(NvUH-cV%!9|wePdqJYI`0V?~ueh8AopGtO~q!Q5_%6&u_0cZi&P`0$szFR8!p&K31D|uOOm-mn-I4 zBF+$j3KCELdPgnT_qTFhC}D(5mVLJA%U*hchaj)6OuaLt>AYxrp{H_%0a{- zB2Yo%r=9uK#B|A>T<`ZLqR6hs){rM%b)L+#eFVBnR*tV0%uVieyUJ(0-XNks5v7Sh z1&JAV)2lBFrgZMseT#^vGkaJ&g57ntv7>why0WQXLOF7zbl&-)BoWDH^{}=Rk&6ga zka+$|Jk@u8Dre-jVnp28GQw*5LJz%TTVo%At|`mchZY&BoSZMGCL;gV5mp@{tnH00 zRFGKR|9mL<$ElsAcM=nk@Z+&orFA{@m9(ahKo`CNj^+Ur9Azz>+)KZfwSa{R68>in z=u*|K0oCg20hN>4ct-Uklq9NS3}*m?2kSIUHDE#nvMI%4l9_gnJ$ugp@j+(xZN1Wgu(l* ztPPv$0xM?w2z22)73t|PW&X03yirxR%)igKRQLu-{0-^(C3zCr?N?a(>7B#A-wFwQ z$0fZ#>PRB{)X{SKNug^#0$sQ+&=a%jB(gtk_lo{()>Yr%90`0^C)EjClGzC}yrdVr z^4Le93*Vw<7&AXiVpk~glJ3&QurVE7xK7hk3X&zY*PAcuG1=q!whtuyb8&9{aKrjC zeQAAldomw^F5H@FPU_0b*7Vlpw0%E`Z>vSZ|D1{Kxqh{#)_6%LdM$&GKo^cNRP}8d zYyR+bs4jM@o$om;_=J@LFaH%9Q6h~q=I%8*R-3(cjk!DJP+fH6*Cr}R;Am$US9Xms zPh=gc_g_2UBhXc8YI3#go77INGwEoHDtvN=S@Q8XfxmK?3(zhS9$7CxIKS257aqy^lcG;@mH*yg5@iwFkGQjBe$(2HLNqyMCX( zZ=r$&?ssW++u1asvDy0Rz8gmR2y~tN(NsTFN#>mE#be^$K_e@kNYh8xO*zRz1qrMl z=u8n$ocRc5()e9-3 z(1Lub(z~7Y<#W3%RFJ?5ke(0MW`R1IzN5aG_mGc3*OaNP7?zEp|d zZKE3`yl$a_#N}iC)rD^#s6X>-BDO4=u3lZzMju*#)j|actbOSnRexSlMLue--#h$= zk3d((3m>TaO>U{ir}$k$Q}--W{pmi)@{5z(s338x_-M7f|7CTw%n>3Qj=Qh6EpDuD zmP=rxf&^Cmbo|jPwX;#brH33#<0H^@rsgMVb4q&47(EY?p1AnbuLc_y~02QJ7)0THMj;dZvOdl(>NJIYo`zPo?A9jq1m4Pfa}P zqh~r5>gbf+P(hC_S-^KZh{UbmCaXHjcB!qq_*qz^az+)xW&W%Cxbqp0%%yk3bjJ zsPvAimTjzKqx$Ized1eKrQ*1YX9h0q+|{K^O#&V{?+i96aO}b@#?~)cG>qU z>uL=gUtNMV16EOn(Ra@>Yd|7f|8hCK?|2aFT|5>wjBRZ`ce)NJsZXyf?0fzd{sr+V zS2SLg|03{aovQj+@_aTfJ06q!zeny;O{{+1s^~G#W%nJ|;!@#JIGqD1{;}0I%_}x$dkE+-1NM}C;xx$DO+Thu>%a}z(8+s~Ge>XLsW#Kpw3 zUm=naWERuW#qDRmv`etpJGV6V=Yi|^@6l#{PetvD((bb2vfJNuQz!TD5g|~CL%8(6 z6GVqyZ@0)2;=GRrG>emgN*uynd;XmuI_#ov?q=}%#@~VedEXqBID||8JHfvwtjCfO z=huY{_iqk_(Ep7v;TMTRpaM(9gquOX)xQwvg1>AW0+l#~{5AiDfWM##>suTGl{kc( zL2Ky05U?hir91svfPZN^Pwo*x`J01_*YzupysD&_b8U0x}c-*=@ZG%Drq z|95${OIo8QlvEp>mHF@Q6aAN}fB$Fc11*r~>A&~?fq*K{(uHc`KT98IfyC8g2mc=k zsB#QmpeFva^nn&gfOn|QyXrJij~hS&s=(iW#Ro@zm5I;-3Gn;>jX>ay{6#uP7Kg%niqQD=oIsHpeCB6AM z>m~Nscx|Gr9-aI>qL}%%@W0I2u90Y)Go^|HezE2kp_z3J3FUX_kPoVw)s(CK{w`%ES-V3y#GaLEbzL@@3hq|QL4Q%%ljnT=yu2^ z2M6sMq4og@jY{#MnOn_!?%KZ3X&0V@*KPPkXe{u$%I_evp(y*9GG}7jm-lWFNhR33 zXrS5$Bs40;hh}cIB*nNj$hEyzf=|(3gvJ7|tNdP|wGf>sQ`SvPDXH(iaF+o&IV(`@ z0}>jQ;zKjHnvZ{s=$gCXkpXEM^^4G0;B}SX6JBmZ2X-p6yemKM;+|wvpLBcUrS<^{ zjY{#MnOn_AOmJN8@_zNneEAolvB2vpzvU`NQ014(I+nzbquecvT9KUAt<^ptp;0M5 zG_$e!eoIy7vOLZdyxZee-RoBysq-Q*V$*N==e77BYnnt_f9B~G;d(2_5lfvO7Zb$RDbjO z{kc1m0?AKmpe8gHcwOapCEd@+_}T*Qqrz>!d;O&YNu@C_e$CkVJ^vf36d#&72$G~7 zUXY6l2NJ^>C2B%rfrRq=$9ZkMR#AB0Aw_|VLskffSL#kr@m zN05bvIch>2R_l-pf#PGt*{~$Cf#mAqueRkfjbNg2$kh4o> zs0ob)URU`YXK9GfZhp_(YJP=f?jvR~PGQY+77b0YcL%U(@r zEbzL@Z@)>^@IM0+xexDelE;r}$)wVu3FyKfq<%? zYn~$An6W4!K$&6c-Tf$P@$C%`SR5`8P^G*P&CFBY_xdF)Z^%R2el84MNw(yb;2w0v7*C)d5MGClFO@I)IQ!!zK*i% zP_++@KS=XEgx>plIJ&x$*~eO_eQ2($s5Emf6(5=_Nm7%@Zh1zf-o$^ijoQb@wBy1}9^vU-Nb=D-Y9E^GDk{yKOT~xgN|H3etYhABuOKp`TvzR*#+@%n zZ^K-*4~+`al2p~%-J{XXAQEJ(tM;L}uA47>vG}l#Bnt6TjN_?cDMT@)xcVbEHhkMmNx-wl{ z+_I_KhsGbI`L2%r8+wGa97&p)XRCc^uB)gtvkes=nk(_QyT4&x>GiSXNUIdJkLP0z zaZd9mDyV`qPxHb$9(${gBS)Vks(om#tEe=wt)(5*yobe8W20%=Jq-N7U2dTSh)Z6llpHB{$1 z%5trWrf)OB@Kg!D@A)}TGC@{h`w8_3RE5SCq66P`P;8vpUqpT_LK@r}hrJft2*mR* zMaZ^>6*{YLf+5Y%!Fq#_UnfT*gHKmICoL z>LNO+-5!zKMi|nPG%ekQxGlPjKTftJP!$_dfMOCn(fJwG{~{9N8R1QbAepdU7xY5^=3_f3v^vcv0 z2#aJHg|1IP(erdMr1}0n2QA2m77 z5|3ODqR{FyQB70@`vF>#exwW_D<;3fFWwzNAv2Gn4f6<^|FahE^F&5&MV(NSXSJ|# z{Ua!}i6`nY*M@)9Y$gsMY}qU9r*{-V)%jf%Rjlrcw1aK_B02_#l9r#p;I;F!1Y%%% z9=f)xH*(Uhg(1y%#_JGF7I%`!uxN&$YJKY*v|@HYq`R`tU&OZJJ|xaumxONJED%-f z4xu-hk?2!)4SxR5ADY*~Q+kt4@djkq{Cx34PE2cA5}Y?r zARZ*{LfIh`QL%*;hBQB$V+11ox;G{z6VD;v>YLF8?Nrny(gJ@=$wb?8CZh#sYT}%j zZ3y3=iC*ndPP=K^z?0_+~d+;V=Pxe{KF3L8o;lM&0X@CizPR0^Sv* z`AKG(n~`z$Pdv762=NUpLjK>Up?B|pqF2VnXnfK*RC$*chV>xcx~o8_qPIjAIEN6Z zf^{E}xNQFqdKLU0kIxAch|~Ia5wVU%BMP)Jr1@TxmXp!ZnV;~(Ghqa(U~NexoSk#f zyFK@@&7DYr@M-W66*me)qi0pdkd~y|v$~_`e$Vhw?MMPu>aWc2^*CD3 z!6LEJYbZXo^9$a)wvRx-_a@L%wf+-u(fm(%`j|e#yV`W{DmpxBFtU7C8H>cCouPPm zs1DhX=`Rp4{UI$$ZCrcdPL*}ZvcCR8nx8Veh-#lqLbH6du}Ju$zIX^PrAM0i3IxoR zkd~xF5wGx^fOvjtVLwv1@*(PcMIW7-XozQ=d4TxI5@@lX0e(IHHqx4=iz0g{D<{84 zzQgV2j=)zE`Vy!z)G0=8Io9auAfvyChn1e<`XTGEeng-^z?HRB+5H?$y|j6Dcct(|ZRz1%e(4Rfr5MIvNVI(}*8K;AcS5s1pQ zWF!xtjci{@7}9(elB*5zTRIA#{Xz)LaWI`>ZIG96-gU|A-XrjVzJx#(tj~$W!3(vB z>4^1sNGFv*z;uQ*Kb1twnvkPw@qtP+X1 zrBBvZI0^(zXGrsQ)V9jxjF&#ybJUSQ6|B#Rgw}$0xSC@f(rR;kfq*#!(tPG}>IeMg zTy63l*C$W~YiA;{>e_7_h@AKtU^N8-*5M#6Nkh|ui229q*#Ge>p$!0Q_g(K?M2!op zqM1vSQ!2l0>_e(QnTgjlek0WAZ(TTt0?t?=yDgSjBwn=YMa~EB#7+^<1p?OYAMq(3!So zSR^d(G$TJ2)g!CYWPyOSdr0$nOOKk8kFV)1?QVg1GjA9AHfIKU?XHg@&CebP=uPe#W#Occ_i)gHQ)uE#7o?np`y%2z+SI~Q z{aZ|reTJCmb=`z-U9}`o1#^Z-e7Y4$0t;7S8?r;VuGZA^Xh)od+6SchJpBbjiOOvm zjypCDLlw;7B5^#w0|_|X3%}}An?M4dunTEP@}Ckw9L#=Tx$ZO}H^5YbttI|7Sm;mw zDVGRwm?@+!Z10FfajY-#&M_qObtVb~Of^XJHCSF<$wOCT(zZp4khZYBBN9Ctv?m=V z)h4Toq6Gq`Go*Q+ek(#eo$HdttwssC0k%0r;&DhzGT5m(sqv<}K){v|r1@yDRzLFU zX)!+eaHa5eVIC86$@K~S2%1xjFYH||5VP%1pn{nybuNLlB<*h*MvgAIj7M#pEfBC( z3~5P~$E2_UwmuOdYK5 zhtupc0afsHSKf{)3nf0Y!f^em4}?>vVZWFdA75k2@tzV}{2(Y;I4KtTfVC(|avPh9 zE0*3Nh<^?WnjNUIhxn&T}H@LfTguc^IQpJ>-_f?FQ+6#Dw$orpEE zEkIR*{$mGy7Tg_TzH33y^Zd|9+IiXY1iWAjK!qkMe zPsEv0KX@h!MMCpwQ#KB)NE zwdhf6cvn!hn6G_K<3yA7)|{A|uIHiz!41xM2OtD3ka%#eke=7uk$=XV z@aL$A885r-j$&_S^z(oOR2{bYhnkJKk^jLOb0VYuDEY?gOm@HSRF5%Z3TWqSYZ@8m zffGiZrmBnesB(vTYtPeVohsA$H&vY2voB6=zj`BUuzZOMS|9;^^HVA>$IICt=d(`1 z4f7xYRpMPW7#k!`? z<@2P4JjKFQwr$5epal|N&ZJR4v$b?gL}Tt_--$+Y`J{I8@rkjykbtUFsk5nr?-p9x zy%8tgCtJy1Y<%U&Sq%jrP^F(bf=(#g`}?jO^=#xe5nbf-%gj{J0txXf)19x)W&gH* za?8L(cSt~$crvMev6ftt9xOY}+2#RH2VGvNJzelZR^N$u&gg}5NgiSwBDdc?!vk6% z0e$m&;xz+#?TA46{7I8sNI;c%R~>hqW7F@($P>#ZdBAfx*X=c>*X+)!?@Bxav{93D zto&7fGY7U)BHZF#zH^V| z?-_epeOKaXo6!@~SVCO9oSxOx16m*f?~vDb9k;VB>qg1;BYNjR0;DId1T-hL^u~ZKHpk z4x;ykJLD%jd_1i3eVr^HvkS|CcLIs}^Ok#DF1kh+mfz>IUe<44gf{g_mYa~L?vQ}0 zEf)u-AH9N)yw6#u}_s~Inr{TJ0zg$Tw(`wa*j-M2TJ_=@x@Sw zWY_E`f4pnuQP6BC^3mT_Jb_-3dtwZV>_mdN& zYI;BmB%p6e+H3R?8=MN46Tel>g#=WIcXd)#mn@I-mW%94-Qjg3y_3+A;aOA)(Z%)G zEI_%{*8hH26W>{ro0WXzHQ$zaKno;#4x5RV>Ss_gSD!z}DRT#M;?bp-HbY*|hc(XR-_J@{o?!x(pApuq4xf{@}oO!?R>SeJr@iuppubw^c0WFZY zQ+E~G_;D${>!OT1uPaxPy!}n(mlvz%3ItF&+HFD?YR;uwv2w=Y5Z|t(?StC#-8T!| zApup_re~w6hvI(Um8)ZCvgTSnS!+qQ2ed#UAu|(=m^_)b&@tmaLX!Q-yzJ_7X`4H_ zkbtU^We3oh&?q{$*qjqh)BBV0b1TVxpLP>`K-I7l4DCts`h8a?)`##u07xhwx+_f*GJ&;p4Ooz9>;Lu>qg z@@$$+YPNBueGM8qVEyaJ$!CwPa=*%NORXMuO50#wlWXYC607`Q&w-yM5%=OT^y1is z2wEUfm~<7LE9~~WjZ-*q62Tkw*eMfF3JIw4O1pwie^~k3$NEm=$z+E})^?01z1Z#& zY9IbYZGkHHhyNh|p!2_d%qkyE60a{~7jG^^kbo-j$)gNM6FF%;3#+vz9}-Xn-y0u& z?G{BkzbIzyY&K9$dMGIcQ}F%M!li4Gx`Wp+!^kVA~0{!m?T)rIwde zbn`8xMgNXO%Qt2gvq9~9s~`bYu(ibZRSO*;pSk{yS$sc~2UW0DBoei)-?6%j2FQ!6 z40VHbLs(lD>xt2MxvVT?gzSHBog1vT!J4dChub)GD(gCIto)&)nLDgg!CIzRzv>uJ zgGD+|l3kB^yTkeptO1I3AFG1uS-}y~_rT?z#AyR%(A^}yufB*OAP+tq)6)a=^ z+!II-H33yH{r@`wRj|bP?*vqdWyv4r-zQh!6;x@;m|t)AmfLm~P&fp8#m11~&rZ@I zw=>ZyzxsG^&=LAFV?WyGS|1;(a+aF*IDjrh*5zeM&9?_w+ZR?evSuuS7D!afJW6Lb zI)EO0t;dN^!?RfTN_@AIlxTr~s@a97X~fC`^jfzLCz^3$BPWh=0$L!^op00P8&!bj ztXJj^()4Yt-nQ*{Oi+YCKvkOdNt&HljNVmN_8pwTiME`W$O&kHgnec{jYq|3(psgj zFKfys_F+u{zVR?vAfT$(v}5#J*Alces0JrO+pT6}4xPu=u^|LnAW@}L4mDr)3MG9} z2pYSIP3`v(w^|-35Kv{XPo|3tKA{%9lzNG6l|@Xye;IB*F_1tDBwF|$puv4Bkjo*Z z?jzq#XPGs=;mk}wfq<&6bMxuG3N38^&V&=i>Go{n@n!g>%_wpxFqf`zqiD%L^{~bJ zeY9W7Np!h-Jq+I)U-{B9fH^xEW0!kl3A8|B`pJW|&BfEGbfuE7sv2OXQ@91!O&%@~ zPzB!`-|<8rGdoV$aspZ)!M^XKZ71JCo6>7@9~IMFSW!>`Zs{K_5Ksl*8((+FiDFK) z;smrn!XSMQt$pYvnp07e`zX=1XE(x1@Z%cc0s&R-!TmKB=U+@evD_6I_{0e%41IplZ*lJ@lTdE;hca%vFoz#C}esZ~|H&5z%ZLZMD5B ze)d7Bx0ju)%KBxRkmm7z0s&Por)JT)n~m_-P-Tz!kI$;IX4_1Nl;B681rmclY^F&% zMz~$F(*AHLET^cv7Kv=!RUn`W>FuCR9-HDfo0J{j4c2|8Bg<+LN2jg?S|HJK>IOQ_ z)f9(aRCbkbaP=DrEMN$>3~1OlpNX|JLdrVe;TiPCG}rJYVUaiSk5pal}Q z($c6`cYEA^*lSK4z1^9PpV^6cg)|TdsM`B-A)OP_3>OYpb|j6y*_lq@L>Ep#3ncVY zXHo6BPWXVyZBF>N-j-i0y(bxU*Hj>&s^5c|w7OSoJXcrQk#vg7FJd$&pal}EYA4h1 zA+7N7v&ycg`WL@>SRCk21`Mbq5K#60a3bB(+XH8;&E`bEC*M5GIT6VTXo19A=V3G~ z)*aWMtn7MfY-NcOJ4ce@@~0RQP}T45VETG$JA64{4JZ27wM1h%@sJbH0*SiuL3G_x zg1ZH+fyq-W6Almodg1^JSB75;+qe?w_TePn>lfj6NQ|B7DzZ+R;Fveb;XHC^*C{81;QOW zjwc(-s|o~E`80TzKlYvvZtR}TS2b2X&<3Y%A5UtZsDhyd5(Otq^Y7I2!B?t2=0wJl zt$5XuXmb5#D!x-ki>BY|j92w&g?1b$&u_uc;5PYD6BT29daATDKIwz`U6rP#;cT~I zWM!-A7+N3!pNWrJHk*#CydOedq^}bQsFI`W(pmF6;odukav%FRQSojFDdhyTKmw)> z9}_+~3_E`qL@I)0fq<%Ijat#Z9oplEmUFoe*Av4q=EP491U zzAF$=buHAJ@*_a;_hTElkBsp>a2O}PZ~|H&0b_-)a9iVo_h0Qx(z1UD1XR_3-k(N% zbj6zwDEqw{taiZ#oLI>TXn_QbdA^HacT0RRqbI3Xxf+24R7GtZLF-hw;2vj{{oy<~ zafuW4IRPz@fMpkN8I1jin(BCy1ANXXB%tb3>l9kORa1Q9_8snHI%PQ8rL_GoJ|N97|BPz7rod^Jb64tQu= zZIV_NNEQuTNF57}ab}DjcImQ)Vsk_MQP&9Xc)5(`PN;%2hAH*-*H#Vim>v?jQqY$` z3nW$~ucP5q2Nz6Gh}EksaOUY3xMg&>KtL7kvYLL4|B6OhS#aXz3JaXZ2_H^C3na*E zK7xGUJ4#e3!~p|cT=(lmykySm8##}(vKP#=&X`|=h!mLQ*b>k3TdbBD{-_HAa zp7;ypdE*5pG%BP6o-=SHkB^CKPvK*+eMu5IgrNnN^RPVTtIzHn#?5ki6GV#y0;>Me zwWm|-w8IV#%D(5ZQt;dc0|aqnaP)K6-QF4JTG}0$Lye zOIJynx_cqMUEH4B9BCmCP_<@XC`~kOfmeS!$9=5XwGe;fLl4gsW|z$ z8yVtcD-cjM+hZh632BVapT5g|EWI-oFXTi5C!hrqusr7T^z}yIrY_CN@lt1jfT~6> zQfR&24Y0{prQEHgJA&u*=HwqvKno;bdCYUk!2mpJZUbUB2@3>Nt*knmPD`kT7tc`2 z-GloA@H|d*;smrn0+z>oUz{f@+|$pTyvIHQ0adW%v%tS<9&BNCp=asVL=%CZM+0urj&0TwefGSvyNfM4ajcanko)gdliB&s$&_i3AVcO?B_c8K) zAzr(+Icb$xOCX>Mmd89_eJI2uI8lQW&;kj&If!l?+6v!%qLl6ZF5Sg5QreJxr}*kE zQ0hY!{7Og?#`j|AD&ZN(KW6uaNOiPPSjj$M9ww0A#yp>;HA$0dRs>og0aKIjn8o*{ zc8#x2)?Kg@2&h_^>ramiu*cRfl=eqWPQ-HJA}62)5-?Xv(wMOCxQB%v@m$bcAfT$x znt}BF&N|qk@*D1BL+E!rffK_x0WFY#(Zy$;CA`DS!hhnPyfpy{sJh}fn%X*9;EW)p z=Wav%JN%Xtb2$MmkbtFxBz3hf!3V6Kgx3B50xgh$UmsqIhFrrQaoh36 zq#%KSD#P>hXw%|SWD=vaKRRR>k$az4;_tV-NVdr=+G*z-wEGP2Vcs@{20460-+mfn z_Dk^<--MVtWa77zJOu)(U^?*`DGf}> z5&KM>%n4|LL}=J(I%K&X?$V#H+n17dnUO)MGA@7UCJ;~s^P42yWd z#QWDxh+l_kc<=ER1isN(Pe##5@&k=B*T?WJ@b<^XM#Pk_eeJ%i6@eB=+;@+mg_Ejc zFR2Pok3LhHl4=i^<0&3a0s&R3(#2JEZbOdy~tdUhCfuWgEVj8SILSygrWRU-Eh`cGjg=V zhd>J?+>iC8bzE!U_EGP-j~IU!5?E;`e&N$VAfQT2kM)tW+59?sWc*iO0>>KR_}3oG z99nmXE}pM4;!plmdkMQYtSZ^l&X+)oKnP=AtMAWcv-Ql$?zJ5S0*-&>T|7XY?ik_c zhm>BNK$Xvl`Sj|zIJUh6EerPBtH-m`BC z1XN8qHkDRygYYZsZQO^x%S!rX!4P6+c@aYkBu3gKQdhfnIN{-HPAqA0h|cvLLaxde zFtk7dj-K(8vko7imQzNMF5&wH0;3Y65h89TJIk%(Uox9==q%9}Hj@hYPgC~%-Q+i`)fdm|(xYE>}J2IcwI~^ffh)>IZXV_$<+xoY3(|keI$;+c`I<944iAi`*-ER zG%#ZwEgqn>+K8`2&jUyQ}}F=?gtM?aiS(Cpal|eWP`8mOAb(tuc}X?7WWYdsDiUo_^F{s zgH&q`^~sF|eF(HbLhOOO|L~~FlM4Urx zg?rqVNA=+>0=~1+ zVQVtj+LKv&`bXKS1WRI>wYa6z(MIySP1-X>}3SU0fSZEKzmLBX6;_dS>P00F$ z7~JA|D+1eRu%!pv>bzG?`yb}vK=8Hikz~$_bM*ef4JhBdK8AB(;p|qvHhdOeWi&FG zys+~?>7LanKeqx~2Ch)SRD-F>zc`Eexv$fPlgd8>Fr4E7Qw^r3B+auwg`e_$EVlV? z7sdzSJPsyJZVLU0FwJ3J;3uqhv?4`XuW3KdoVo6s5JE9VUThR65ZD-b2VZ-ybwS8YAQavRli zY+mvOLzV4{Bed?c1a#Wl=`Uh!LQA=J=K{QGOHBfa4FNI@=`stwJ>rNV%||mPJImqA z&*GImtO-;VnV+K9+ohnzvm5sv-8^KEAy*zcE`kt7MKJ>Hui`edCESD!IVE-Ro1>)Yy^E4uFF>2=907IJZFB;BQ zNVgl0D<*X#Q1xz35p~_2icGH5`-`~W<~>_#Y>g+Dgb2jEWkqzjvY$M3FjwA>*iE9ED{YD`^o8cCgk~HBY~)`lSQ9*4mNUE_;?j$zLf-YE#U0?}Fb7>yjX5>-EChat_!gqu~Bjg~FKqcVL7RKZvg zi4V`UWyi}yakuxq1meh+Q`9;!9c?(>07F`mem;7}o}E%*)ICgy52%7)R9+*Cf5hIt zV$LX{5 zKB%`(3k+$#!}z=)xh(D!PD;zeP-Xe)46R$#4&}dY{uj~nLU;MPe-`d;R4x$h+ZIs! zCE>`as0oHNPmg;(vQf$&JU#X&hALx=OLYFXF6a?%{1;*U8q3Wy(r`N$D*}l%eiv!$ zj2QIowgZMVUz;)ALw56Af~V%xAy9SV#8sMQ7J%|B_$f}nA0I2))kHp49FB7$S_{PD zysLD>`goL{(f~u6_tqY5DCd<%V!MN`1ghfi-=W_hhoa33>-|NX3bT+ex3R!@rmsNg z``x9pH>RLX*K9DPB`NK;iEP`jCSH=>gFscP$1|$cDh7=$sQnkQj(ukDy{4mz24MoR z_TDpkZpRFC@0~SSxZoBm>j`_3+K^2S@k?>FLFZ>E2K_7%~r^8Q)4EU=0bocL0GZ7%L*tDa==HoKcH}uj?YTSYS;C)|@2Cut!7LZs!?%V~jn4^$+-M7r)MY zMs>=s^_D5}hVw1auB`X@{8Uo5v`bC&H1mV{_oXS_QN-A%>fgV#8Uk7%vE#s3mCvA( zKg7R2AOTe#7SU+U-V1+--;PpbXn}5z9IELDKfM`;`!=BDif>Ie~5qY3KCHD zKB+glbN>Dx;n}ep2M$DX6}dvbQ168S39l(^RT!Z)*MV z@$X$h0;=B6h*4?i-#4WGNAv+zFg5=>0aY;f{7a-L&jIiK_wRfqkHH-JFTsC^1XTS; z-u;b<1XNv=8mWf$P0myN{dXTw6;|0n6>{BGIotbx5Ksl*wAx1s|1bZ4ihSg%-M_g3 z<`|e4c+W&;g#0p6FMn0pE2h`Mm3g0uQ=N;vO2614)@%A))s=h4=+Q%M*=o03)zD+t zsU$7i9U%wIs+?c-?kff@kT|?9_MANkq@<%O~y!nmF7_>m*`eYTGb?l>R%IcGx=+2)*Yxp3KJ0D*O1XLBAY0J(o zwn2Jhl;=pC5+Qd^*YfDSsEk1iB;;i(Hs+!cD)Ll(tlbkK|IE(!*v_9E5>VxHRmCQx z*Fy_hD^I?8dxU&)vb74o6$z-i5#`E;J;tcU8RaC*>sb-<=m9pWqxWAiXo18h6=HXs zTcS7Pj&Y*P%?SDVm2s-E4MhT~A|u^cpSVzzI^iEqOk5u!rym=jGSn$!&;p4k=Mgg> z)(NdLKEjFZ4!l`F}6Xs1Mp zZuPFoY?kh&mJ?diaW_p_4R(sUZ>~bmxz*sg{o}#;`I+M=%PANxLklEstdQx#xMp;$ zyBQ}Ad1TNg=TEVn-(v&9QA$~oGI|tE4qkz*ZzRcW<{hK27x=6m58hd>wof`a3RdP)s25gR^daJGRq4Y#~e&})9%6&4j)33({9?PN*0SPFn zZhZ#tR+8=*4WvOwtZ>NoMBzCgF`xI5;|_h$O@HNGEsJ!awtH`*!Vcn-Llt}`emYlp zZ(2%X@QGXF_*3~U4WnP zy&&PWpb9<{UpJ9gjkS5Vm05b1kGZs9x9}5W?D?-7vin`FSo9!HfY^paqeIu}q*?Vpi6w(QPr-&e7ot7IV#xrBO&Ql|S*kbsNR@ZBNXLwYt*e1clO_md2~>%3 zt~Jt#xt%h@w%5g|g+%f68&r;&gx=*TX};*IIotGVARb$gAjCOT!ARq^r7%O*G%gft z4;d@OAS6nz+@uj~1!{3fiP}aDYcRiv<@jB?80Sz0OAJm-FkoqXZBgvfIH4?o#Igm& zbgb)MbZWoyb=GcDgRQ810NalpCJ<1iA9s^BvObTlmzr`SIW?J$P2GX7o*XRO9(_ln zADuwWTUKYYoS)KvHuJsiRHjTd=?(2`n}vqow&29Dp9ySa@OC_D;Sd>GAOZbJ(hZ$q zEGS_PHus4Y2&mH8QASVZFF{+s`SP+Z^g;b0tuL!JeO1&&H`%b! zjgz4T60nrub65tAWb4l@rWuVy0;-;kd`UAJI;*-nEAPtT<8Ws0vVyMdFiwURNWjvL z?}Si3ikaJ(u$A=^1OlpN4thmD@4lGp;HISc$*|$9^Bi+#f)iwDfdnkI`HJ=Xajdwh zFH4FVEf7!@JD`j~?6Ry7WPn&8brQWYw&oAKx0#OaB-%=$p4W+iz#~_UX)Pe5Bw55!H&2M7xFG7YMqyOo(ObJ{#uj!h>O|6Laytw$~R&K0;*ta zO47Ed3^rzCWtOoeR)|4JWcx~NU3@!Ln@dW3ESt{A@Y}`rDt6z(cKQB9^IDG-zEP0)LM3MDItoo}rhIEh zjNisKwCRYy92_PPPzArie06{AEi7#f!3*XL7rwQSaERAphubYgGv-=yAG42cXG=#; z!8&sX3j|cbx&)uO+YR)R9u;dDkXS!ho3$K~fo2#gy$0K)9qiM_Rd~qpNTHSi zRZ1z*;noqPlq-Cla7YoWo-u`OTplLF*bYrJWG=Jz2XLC%r#_GOHWJC6Z z$6;B)K9)K97b0;*s<@;-p+g>2*qC!FFlNQM?jjB_zy zmjY6eVX9ICAo5z z>TGiBeaLx(9&?MgV2;77P~;|kPLx|~$pdo|aKFw0GPFPf`s3$$CH!RN&wO!6qacBR zs-N-ZY-{BiC~Kn;_tEd3B#)Tc6EArdC_@V*;9KDHUMqgEDjRFzin4wJ0af}3&DgWF z2(RB<0dpm9d0qLz;+u9xUSC550;)cgn=;ep)zDEJC135I|C7}*>xR0? zAu_Z;0!Ei4J*oARjh$E{&x?c#1XPuMHDzSvY1L&5#YdOwKiLG|+IfdPLuF`z1S}=^ zyIS*;>FnxD<93G#1XT4WW^C}ZK`J+IDW+aaf@Nrd1T3}rei?lEYmJ$f?Bc|J0s&RQ z-ObtE&BOBksa1{p7?SssRo`dLYHsK!LklF}*GG~p!zKAiiU+&G&#Hn1R3&^dXRN17 zeqs$JYWsLr@c#VvERfF*gBD1@uPFZxUX9Cr}`uYQsqj7F)15e^s^~_u==Z zf(^bO%?z~zWoUr}tPSwFABB?qJbygf;1M7YP^FX-cl{pZE9DB`t>>AE{A$w(HZZoU zy7cMMAmnEc3gmAQ}L zRC77Ky*KMMsH;Fg6?}($SKy`=vYU-3OAhHOyemkY$g0DtwfmlDHAaW~$ZldT%P9@n z$!Wd<0aY+%c^ikC%a7;PXZ@png*1mmP3<}?{@di-C|_Of!}NifTr^0B-6Guu0;*u1 zmZWQ;=5oOfE%wEN&jlK~6kL`O31XRJYlAlvO-b_v!q@6dbT~DD*ghc8N zYxXqD5Ow^a`0(FpCOf=wMjZ?N1OlpHna}ro9bhK=FKB{x8T1s&c1Yk7Yjz{QCA#6K z_?V$8?hrG%*3{knOcy`l8wH6DLu#|;llq}kZ0EyR*HtdMaVl>pI3imO*mxX*>F|2Y{IW`h7D(L4 zvu9;Ac0Kn*@DMU-KS-1 zaUXhm4dtf??$Ilsi9kRVj7R=Gk8CJMcweXYE)f}8AW<^gjveW&t+F>%-WASrkZ=8y zPWyH96bPt-@yPczFl#6`KDV3>*7cO31riIZ*s%_KW~x>NDwal7!`Q|A@3nUI5wPkCrT~t-qQ*uecVh6dh>VB?iWP5>tDj1J^=JGNJ z`Rkk;xlabPm!Sm`Czvf;SIYn`G*NuCI^rM?Yi)))>xcwY!Fc4owKE)Kv%%F+Q;+sC zv_K;FyDh7m-3%FzR^C+|(}waa&t<4rHBW(nDj1KFG-$blyfh~b)t%ufLklE4CfYH5 z$sZ-OP}1Cdc0>7*<3qG^5)lZfg7L`Pg9Q$<{+nWC-@cs;Es&V$X3uP{jzO!sDS5Y# zT_bttR7>m}hy((vUXRy*0@bmZZ{JMsDkmx_seMICLcGrLU$c) zCPND(t_*F;`b}Q$F*N%F_wh8tRX#O)57jDbE)Y-!=#&hm)J!c2r+Vk+Tdfkoef83G=SGO|{SL zEBDdnN?ZAnsYC;Qv=9iWg7L`LpKH6xj?EKL_m0l;2jiyf@s3`oOVlR{b7Ej<6Sj7= zBf7d*N%JGCUFD^g!%<mpBZ&ql$8 zwdMAQTC!tzh9jQ=59s8*F06dXT;%ckKCRN+iCI-7BGc+hE-5ndk_RrmhnAeKD?@CMMUq>^h)e#7&g0aHKqdxId{;I5?8%EWU zp#>6)f4DH)AO9a+XB`*S^ZoxtP(;EOMZo}30hN&6xz|7?R7AqU1{Dhxu>?CxWe5V0XuF*7t|6XLvt;``3N!c|Gs!-k39S&dg`uX`3F2GHx&M$1PnZ z@i{GRB!a5wyCQn22mSHZi#Q(cXoJ*3i4~JvVe05M+TnMfh%#Kf{c%BNUH-IDO^Ki? z`gVzbKFl9IOl^4fYa65%O6)6iftwZgXqCzOCsD2Ck5&myb+uA!N(5C|)^LO;GkQxC9V5o6 z2SwnWfYZ842ThUQH5zA2ue5lhW<;RFThJvXnl)wCUf*kq)ItdwK`Wm2!U$v=Jy_z}G7>>m z@*S*~8i50*IUYWr&jwTHWEhmS=;Ock-t+Oa)!BTv7S z2&$qH-(nq>%e@iC4$_qflnJV$&#_qR{#OKEd}_<s<>8HB5-M7GhXMQ zOi&fA=QW!C4Ljn7ozeWrTN9}as-oUUyivm9XzMW&Bd)<-eVv%13mjdjksFo4ImL1l)) zU@88Js&*vo;VasmU@4~hd7Mw<1He4yFoc=KAdQWnze*pmrHiY>|Bcx4cWDjQfd`bV zh69ksL(%vvImT;VyHnvew4nv)63SgE}}engyo~w8~ulu z0L!fnQQtQ7-#bvJZ$Z-b9Q}nNBHqRgciATJ%^_d*h+XPki#7*JT0e>wfN?Zdx!O+KDD7Y3>)`%OPtfw{FVtunMs(m8>TLt#XG5hd2wEG^7-)^g z)2brB?6eL(ZWt~RR7Eov#OnAByYpuK=R#m)yc8Wx6M{;;s8{@Hcmns!B16`7LjKQ;(4`O{WAB?oFv5v)3{)ICb36uXlwq-@vxF= zKLlw_Mx)i`DAsW$F6ufwxu{gX6@&ULk?>X5m_DzB(zJdQ?Ggi1m@*^-_Ou*?v>v3j zwp=ILEHs792M;N~e-D)EU0M&)T3h5aWF z{ziDTMgqKC9wN=-&>B@ggIzR-BwCg!nJ+sE%FU&)Wea>8bkRf zT4~&e)~IsrGiO|W6rS+pIa zZsT>yN1dg96zw6&qaW2ydScBIdk>%XbVX{Rggi3w@PikwJAF|5`-wAB3nk=!)ZJlT zIR5fJ*1eiD(y=!>ULyC3E*$s9t?4J&x}J@sJ`U~I&@+iGs?ZBfYrbJmHZ_vUpadPU z5MyLn5oq4YijOa0inJ9*+iK6@Tdb!iF4AzO8w%BAuKs{_CzV3tnFoi19hQ{E23oa={l$0ue1Rh+t6MV#L+meX+)aOI*iuB|`hK85}aauS@-q#wjg4=iI*NQF<>|OWp*kdTinc zOOt-<`lzYJh~GoH|GQ1ah$;KRFfFzhT+S(hlsFUU4Wnc2c&|m7oYEo>@^KjEPw5O7yBH!>ty<>` zy<2$k@cdoHh!b-Hu#8nQ418lI5lhN80oyH%e`0j8DK8Ya5A(ET{)b{)4&yt}C3QKfz~`3GOgxj8t{Xs}gkZ z+ransyHbpBu5$}!O{{=6mE9y_ghd(HG;9@*UGb1pT8x*h$b%k3D`AZ4id6O3!VKok z-oZyNy;h8fFgOUYRyA;1CwGY$de{KYciY4x>ptd`)@T~++zS`NZ1AkM2~t(vMTW5I z<^g_nUrsS1Ds3(t*kXs^DM_cHbJUNJMfWD zuF3h)^qgWuy>0EGlC=}YH};T-DcA4w=DqiE+sBVMrA0*JmR4|de4s~?h#spn(4?O$9?X^rgBlmPc~l0EuKtiyTC8q-yO8HsbjOrMu1HmLPG07% zx}M^m{pKd+!$TvC$lz=h{uh2-^w0G5zU2KCtIAiHJMQK#4LG5~mKmT6e!r&}@o;Bnyz|uz&KQ?KN*tZ#4O@~=>b|+0 z;FK1#WcNE`)@uzY<4Yh_S?%$KWaYKaV4R*Mc$6%oC0TSs+z?`RxH^63X%e!%h?Z)#;>99)~uRDB#dhetGEUCx^sh5 zT4bLM_Ct1dAZ+!nhE#R>unX9rJ+~fzu^8dE&=V)EN`dm$wi0n`O9Ob>!j|ud$>)?7 z?OpDPp|Nw}vx_ZKmESW*u<&5qZ$oY|;@6!9`0H63=xm)N;(j+<2>8Sxqi=9vI zY=Z@Jjd59QYow|}*M9TM9~bdClizchXlI)Qzsj29<$8eL58on$Lf`QW8?=e6X#R>Ax6af47(pF5jkIP^4FtMxTcB$P+E-d z?pEOQuqqfeF94~k!tFb}$G~-byyXWj6ZN&9xi?nBdmRHMBJSmB{=U&7et4+{C@rp4 z?fd*%Tn)Ux(;um-^tf|;fBQ6^umr<2XmANxm|n1q$;n{@;UT$>Vs6JAG0c2)rzQCVeG>j$ct)%-!7( zc{q(s`SJ7eD5vjtUntjSN9Mvg$2onbML%k6Z`?YuJ^Rt@B~VrA4J!PaossFWIlUNB z+od`&uH_MlfhP+d{Xc06C>aMEvsJxO$;2{}uKUsEWQTGLexTf%g_a=F2;k zmY&`5M|@zdYcrkt<0Pj~s93qBO((3I_nMboSrVzL&ofVO8xg0A$i7&Na19SdyWAjt z=2=;ZpjUy?V(j%&Cydy-iu-RZg;aHaq6e7vbJ5w)&fzk#bwy_!J?apDkYgkfbncGQ zqOaDj6Q=Lq&d)V5MyjG??=s=j`5Q6>&7al?a0+#zL`vqaGALunC#J*5Pu7o@_}C2i4ts|8e9TY;DR zYz*~FSA{Q~HN4~r!$0{yf8+F*IF>>OyLk{J2&$svt#lk##H0pS!57yP;lf!ziJ(`3 z(jrdgVMR1qzW_drZy{YPItL{am2X>P>ZpP66`D!}y*`u{QDHH8;JI}t1ig*G`X`Lw zaI7sqpfv@073i3?sC`!6fKi>c!}97KrE5h;vt=TG@;gYsz8tcTgh~XxK9m;q?!;t!2;mX$}oBvs*;%_#2`K?pog7I-EAyzV@Dmso& z$M?k!tLhf`TwMp3XLpwfdKD-w_Vo7L0BiXPSlzIjbgk%Ys7#D==J3mTH$40tDG~Jg zP+F|m+qF9E9&rcWP31$Vzq_)@pyViD_*zvY`C|nJuGv|(fyA1;s=d_p=(T8-ap5m$29K% z-*4vY@($G!{qr7Q;?VqKerCz?D}bsV&JKZbF~m;J`sH&kh z7#wZgc!`f*#fYiNLvTru10+}7C=sjIwT0X)e}279Q%-4-3y>azw(mlq=Gy%d;b#{B zqi=TPi^}xnl-6hpw#4A{+2P=OYadXR83w_UI^Fq2*18zc0iyAxW-4UOIVcfl=LbM@ zk2r38v@NH!SnJ-p7e)oogN8?sN<`;(e$eXvSpH?*a87BlN^P#x*!D*;{@tj2T8PE(ujhFJ_tGjbbi#2{7gK)#H`|t{KCBo6u z2S(0X#aC>c!YM6QDcBi=B|qGT-dk?~Rh@NGVAGDZJUOsWG2+EfKMaif2wtXn5@EO7 z2WFXU;|3%9aY}16;f)wRF)4wtG+!cy9diT!yF2)WCDS>j^`29U_5nsXf5m;Es)A1* z(7n=re%)qZF(NKc?1E8ffz^IJkcdNuZgB9Vj>k10!YM6wCOz8_zr3q}5d)q{#Eh*@ zu*FTsN9|1FlomS>k95Fm5mm9E-xHv!=o^h-fc0^{;qK64gu2=q-Ot9hI566lK+_LBS+_%Gv5&Je*!4+{1c>3Zqi3oaL z7m~z?^Pw>#IHkp|y8fmZq;tVAueTCm2Q}bLY!0vNlFTVB{70lI!YUVR)AKD*RbIo| z@OkeoZaOl)7;&qN0p`W|;NDFyCE`)b8gQj^KEM1po>N+63Eg`Q*&`KP@#4Ki)H1IG z$3#zj-J)bpX_0H0{R|S_nqhYHH$YV{JS?I2i~_DZ6<>_lsJjZ=ocyuhrB@O$-KYZi z`@G^0ZQ?nl#jhHD64Gu4;DT-MC1UAkv1-7eLjJLAGN-hdKYx@7ullva6G<=9oYERi_tIwI@}?J>g+7spO4{3eSEC=?vdVN$Y0+ab{=^?zMd8+3_kpVF{PTd% z-cte^o{ug@7$2I$UoGm34d&gFh_a=w^VeyHux(H;PH7Rz5i|l{wr#;zR9*rbKDUEr zGmq;wPYLF2>a>NKxg~k&lwO>+CG@-3#i9KOQ{J!Z3ZN?5evpasO=9tIiUzvw+bR*c z@qxhB*XOB2hD&V}v5NWcA=n}PIsbih2T&Dl4bbvLFO~Jj4++8W?YK@Nc7JXK)gJ`% zg})LwrA6$AZ-4BhYYnX)0Z(JRF@sZDqv5lA z;I5am;7IZXpepLAWg_8u82+%?53Yr`BqDSJgT&xzJgQ?dr?iOWGz!NfXZOOA6}N$^ zsHc{Rf&2Z@s81d=JyReNrum+5?%X1NUF?oWY0>{U?2i@>d9bvg0H})kU764p_+a3d zZ?NI$dx#Qch`+A9dOXyXn3|a>w^TRn&{h#MpI?s6A_r*Rp>|#EQNS zP^#5lKFD$)F;YBs}j}G;YSUec-sIek#njJG%k(&=#5pJ z(xSaP&SRe+{da`?0fYdNJgn&)2%Att~Z%_EJFs;Iw` ziP*iz;MDHsV$PtHM2vDYff#o&me_eMr?f_6nV1E6EB!E`s}WKa^*%CjIeG_|=hEZr^vHD(V?zqEoxp+`y>^URd^3A{@4zjt--i3 z`V-%H^Pog*>Ff`RT@C*D`c%pLh`nnH2VtniU0(R$5KtBM475D4W8u|k?DVcBEKWNk z5o)F%++L*R-r>od(xP`Ki1j86PGz41s-m7jChX2eqRFo5Fe3Z5MC5mE3fo&na`!5W zIi-c?d>V7`hu?5~P?2ARk>*An+XI}eHDzDvZb3GVRKb2c}xyPi{8ME2iki6zDgV%K+| zD(V@E5e8nEckdN^{a}ccSWu}k^zdHJyLH~oDXr1;E$~FgDX-zlc|)Ws>KSBW>?M(r zYh;Wbb|wSO37V=>}h8mWrb^D;4}V^uuAK;-K;HkcprJrSOu*7TX1ulZezARpHci;G^C5 za!QMx-!GNKsmXR2*R?EC74-}<5ml`KT01w!>+TgK;6vxyH5FHun9<1uocCK_Zq;{lVkL-r!Gu?&XvgtDX*72sP4L;)#>xkgBL>kO_lv-JnAM zAe^U^mk6Ivh5YvUdpy*A52v)~pXY``*)45x+BLz zlB18f>%g6y(jqS0U(EBD3B!rsO_8doXOM|!B`Wh_4Jrv))@#eW>w!yCJ)R^XCg!Qb4TCwU*S8p+uKs6BI$9}hkbR7E`lElv@?NRLLDjzJCA?k>(O%veOBE*v#eGebYIm#dwLv9mkE#hi=Wx zk*cU?kO}jzb+LcaZ%At_W@pHGmxxtPv};%J%kDZ(Y0;+MQ5UDq)S&Op3P@GdGswjK zw8}VTy*ZvNw3LX;t!fgR@(8E2SSh4(Wt?`y0(*6|M5>~mK_=o9BUHy)q5qWX z5|Pof3d}Ov%iCYb=9CsWyqyfuuzU@)*ky%OMLmN|oH+athB@1#^2u5v>?&J8VrC`} zn{|v+TI7;>J^+s@^)dHG4WugS8DwHXI}WwQOkWMPrbO%>Q4&nL9pld4$2q0N|1dfX zU9Py|$}84LRn#-c#E40YAR^xzy(4Q%M4g&n`HQ@>eAV@1oYG>4yngfGnX?w(EVf3f zqMkt}DmU&7&BQLNjoaBsM2VMAc$L~BDl_URr?gl>IWibRYWd+p`x;19)HBG$(_&l;5<#Q+DJ@2$ z-uA@glJ;=E;4x4Y^$aqxzgI_0PaFn4N_>?F8qH5>(G#B45hqt00G6KLfU2lxkcmZN zZ@>zjm%^sfrH~RdnxE3b8_a5hCJh$DmENV0s%Skg6W8CUX!Q0VL@%(A2pY{#Y0>jC zX^PXW4}$SQ3#2OQ8Ds(-T=8w&Yp}gi6^WqH{FD}Je^z%z(>>Q9!>|fc6|LuGVnmX9)WN6Q-@-s`4WugS8D!$fj|v#$QxY3rs4WpRnxE3*ehjRD z-v*b$haGAoRZ-6%6GzV);Qm47(d9#3iJ;N^l-6k0KGERoQWf!~wk}c?^$aqxtIs{y zx4Z@}eNkT`Xf!{iH5#`&w;?Ra1}na+hg3y9gG~HhbqLn%vd0U19VCKA^HW-*nb7Va zJjt(*NrM_7RZ-6%6HjN)hy6<%<1{}mU&{nxE2QrSx}!Q1+}hs+;N~RZ-6%6U!SL!mTuhCTC@WM)Olz%%wWK=7qjZ zu^`$Wsfv0AnV7t=Dj)Q{ISyZ0S0b9v%i`ne-rxr|BB!+2KWfWBv{_-tf4w*XH0Gbi z=F=QAjpkglf!JsEdR>Ecr-7U*l6?=v14;ZiJ-Chlospan6$>{ZxUei zw2DYoG_Oo1qFeajkV~m>YWRnfdMnb^9^8WToegl})1B!b4~Q(8n>47SFZ*_R;f ztP@fd%`20MojK;%VaOA>65u8gG&Y~o8cm}Bb9}e20P=shB3046GMUiS{RR_XeTTF0 zUJ^lL^C>O*I6c2W4U6CK`nxAm70oM?i4enF$SpL+>O-^=K_l%cE%wKmbPXQnn4pMZ zMXI8CWinxsuou?;EQcSQREeOG_LLT@w>I7d)!ZxM4Mjn!qIqR9VVyf0&eW-ft9Le) z2pVZmX^}UvX9ff>s*cx2sz_BduS_Q1&T0d(LAB8NZBvP$k@l1pZR+IafCY81ZIp^s zMf1vJB23H_hYhsH^&ez{#^zI6fW;D=HQQWecBlZoAtHTb+;j<{+AlZdCc zbv$3h+(uP+$SEyiAjJskxdYiSH9)LqNiu567*>bppIms>$1j}bw}@3w4b1Vo#|fAn z$dIZ=g;#;|Dhgj0lnPCTN}pGd#uPx=iD>a`kIwR;u`hm;Pyv zFCTW0ax-RM&f~SOCGw9Br9dWTKGs51RvGku7$Olg--Oa)t;u&SU|8?cm{U4b$}#a1 zQ5^FdkKyUBN`g!*8T=2_u`|NsB|{{F=FL!AtQygAIs|_Z2jZL}IP; z;MVLZjIG#4B4{2HrA16?#u;c8`U0H1MRXX+i3-ap1Lz#i*LE%eGU4s?8uBz(A-B1| zM9}Az(juEY=ovVB--p4~T1h!rg_Fb@;Tf&D+Fk=P5&v6*ovWXLxjX$Nf~# zUtM9=8+(bMIW3eHkppYAIBJD2ykBN7<*}H|bAho}x9VE?-sLi}C#gBM^KS;;zBMI+ z=H^gZ>^HF`5xkDRfy0A4A$<>OtDkx8{_T0h43lE-;FjleVE?R7;Bq4jsp|IZ7ko=W zM}E+!OflkBhiQ=5=O*MY?j{j58k^E0MtIF=m^M5YI%oHgBCu)fu}o<2CeQt9g!fH4 zBdz;r9o0De7@u@(2p_UpzciD#GOvC!vLCbCOA;#JR~(C1haiJ(~!lomO0RUL8msUh&}Y7;4^fxdS#QR%ZK zJ_wl$Xx~gCXr2b8#p-)^EOAtW6nI*pnUtGBYaE%lA8m*a+&9A2ML`ll^Cl=QqAbc8 z;=-P3Fu7}xlm$WC3^I{f?iSRaeh5~7mGdTOh61IiF9rJ_ zt30BgG04P7#~o19>>PAdx<~|lYbh;uYHGC&-nF{~)+;+pZ!N7QWTIoAdOUu46yBNm z7-)pZhU%wzbUg$3)^tp8c2FdpCKk0S_!w5xx3_NV%^x*Ou0NVh(b;9Z%m>8aMcM!VOao z^4lx^;Ri0rZ9}<+d)d;MPh}M`Nez(*nrkbUajDx{o!bE;d~mA^(sR))N?Nv9CGA%L zZr6Kl9 z_m%olG((y`Z(`@HKo4|`o&i>E^oNZNY7D+IeI6XH*rW-iv0h%ARvmK@fIYSq)0Qtt=6= zMMi0n=OuQW%KN5+paua*Yh>D1r)_w#L&b!L@VmrmI9RuxM9}^Kr8S!D0k@$^`xCHX ze|w3bwKJtfWMgGKqg0{ls_SJ{MS^WFR z&v5&Ecd3S>1kJ(I{Q2B?G!&Ct?ST9vf&W)Cq-ia6MYTk^9esE!TNBt+y`IR4Tjt+H zmo$Aa?!F5^EtD|Lwbh+`S`yBmYa@v0b#Y=Dm^d`rmMRfcr9YlJxeOFOt|*8dGc0uN z*A2n)!H1NJS0?FR{wM{ORhuzFu(kJQ=r)u!f=t^UOzfVWxHxk`^&wcvM5j;-B@R8d z)@iO8L95J;g6Q49k&lJ{AdE9RE)i6fA7iF#c}(n?QP4{e`i}`8j2{a)h<~dsx;`Uc zr?8@9QJ(hiKQAIa34&TE(I9dzlL^PUaTqAB6(y)j|NY-&329 zV)i$aA9#%|GkexS-9-` zI`h9ok%bcaW}ETsET~=`~M|;DM60^NBr-9=%2o#-%AN!{rCU-=h}bE zphS^{o>zZd^!>lY|L%uE&qY=G@Beq7{`VwOqR2uC{c+Lv|CaH;r{qr=MHZ^km+`+R z@qcAdqR2uC{c+Lv|CZr8WC*tEfA~)sMHZ?G;&*$GRnUQjN08V;wRwAg%eZYHPmr91P*{i=OBVlbRZ&#NAXmt95LM@c26Sst! zOez8SF@puMI3YaabWjWipSvOvR2BDalds0L1Q?nQ6-0+>XRKkm(XHh@lnp)6K&B;~c|Wg<2>P;<}36IA|bpp+^X!o$VWsW9|Fl{Vum8f~wN? zls|lNh5>Zlt1mvOi+OAcbq^P3Us>_Jc2d&{}}LHrly zzVQ^>X0(`3?D&D{zqj|@%$GGR5M`8EWv#6tG8^IKzeJIR63xnGv+h=_`MPPZ1o8G( z&S9(Iig==X$e%Kb2&x(!oz6F+1#lE#WPqr@*M zI@W)0HTbjc`FH&uZm|hR56|pw4~>`oOB7isp+9cf_@i!*seX6I9#wQc1BXn9%@0QY zDT5M4Dm_uqwF%!?S-&@+{!`>}UW8;6y=#0m9Q;3zqyJS!-bdtf2KQrQ2ad&|tJ?r2 zs7hbPbvHvOY1NO5?15}!ZC2-4?6vTKL{OFfc+`~A(6ee|L7WUR)|t(T6L~VJ{~?N0 z`m+C5#|T2VD_84ZIH{-ETm+|*AsiVIVHFr5X8OBIXa@s zq^hImmU2DO@tgTR(StnQB-3~MB#b`PPVaGw&YMY9*;{7ug<@rlQayVKuhtkteLaMa zs`syt`agoI^k@3()jmx~*G`)hhYo8~^)*~ki$!Xe(DsVRQS=OCwcUr~r5o!df~u64 zBXmbfnm|-)eeon_gf7eUiX4d{^=C;0RZaRhSeJdF42+K~D+r^7S-wNf$KZlHgCv5g zsz(pfwGw-bj-B>i_$bqPv)Q5}W6|qXGl`%okJUqUO&Xhnv)M^Oyzk4kuX>I}pQ>RJ zK~>~h31Z>(a+yITV{lrDYf9Xt1-iZ`HL&2zIH}zxx36jqyp}m~bquD4T$Tu`nxUM? z{9B8@wmx?_zI1;q-B#3zqztNZSkff(Zw>cm+qXjnjr!r>!dntSRkR)xIf{u34?Rol zh9MD}KXu8L-=BH>qq(fxw9UF5J3jDtqZYA@ZK=Adoxk($A7_gDVb`U<&u-s7Xn*0k zqJMLW2&$sLR;=8T_|)g*;wapo@I)f0O8!;)njtQwH(u`cN+PH#O{#adHL~y>*RBuR zOqG8XRSoe?V}JceKv-q%%c0RY%JiXB2375CwUhnzQMXg=eAnglL3MPYL{OFfioCm8 z0%naFAg)!*dDVRmrM1EjqiX-Tx_j0=beYPLEcA}8))aVJ{jw8MEzlPw|VHG5Ts(x5j4>rFM52&$sbu}0(i&qN;|vExnOJ8~IRMW1PnW)RQz@jKiE2L!wS zTgLzHnqD<{2J+*PIm~U`7?wTc3U7_s;#d7lt$gU+E`}b@93_IPa(_gz!Wq}Offop3 z&$xr$CqtUy`^)ttf~q2p2ebXYH~HC5hXfH-uFxk%%!D6GvXuy`%75U^D$KaUGfN&6 zgxNn+d>d@>$F`qsB!a3|_OfNVA!0|fA$tX(N&f2ly?t9ud0bT@sLJiPAzPq($OBx( zd!o5tK340zEDQ_hT1W&{(dSsSWZDk)y?C`2IytreLlj+6{nagM)yOTG^;Q~fuzyYb z-Pd0tsLH(WHl{=$otPm%Ud< ziZxjb6!D(JZ0(+?rx4pAN+PJr>*N)-F76-xJMfqIRol0xFqduy_`@MmBB<)=kMr!% zpgFwMfUklmUtzeftEK=txXWcwmHuuPwS&bjmF@Sj$9xLhj~w}@j8Zq9xp$A!e`?gH zpI_>RGc)C7+sABsonN{OXHCWbxNLck`7E9cwLiv71XX3GKV-F=R^{J4$_V0J-}9Ld zt}g&POPQdm`|b}|l%@&yv@R`(VNFVCPrwe)oF6KcK~-1s?y&3%!Tjv5l7g7_!%Fe) zeGOjhj+O|jqW4DZ+qYEJ8e6BsOtV;tpep^fD!Q|xy$ioHp0|y`JK0zMT%RJ(LOsq- z^L^}ZU+vhrDDQyt1JGV`P9mr(_2>ciw+DG5!_0U2!a-=T;;2MW)&5uM>~FtzYw3Hw zKf4XVvwIIq1XYpNxp+!^qK&mLvWKAM<_w9TD*ZoC^(hT*D_jNPb|^gaQp3^Mqy9KJ z)M^6Xzt{}s47jhOV{)X8$~Bsi8=`!74jYRD{vG!zYQ6qxEf=+M>6t`-@KMXmTlFVk zcIB!-Tg6mGT79BTy?*OD-Q=BI-m3j_#?nrq3zG&^xqK{>+GqA3k*u&*XfZe?KRT(j=qm# zr74$L+*RuZQ@qBhu9u#$L8e=EGftRG@1345dLK2K+BwFmL!vQU4g0s3T4ee2ytazf zy;)$P&@&0|oNI<#oY(Qo7sI47DDk25Q?@hKL3i+zg?OVJ_l{B59@grv&+PT*DcQ8* zn62mmDO5#i(Z{K-&74^{1MGMFx6fJB&(!w~o6Yp#j!*S_ddJ6m`KG%bhMuE`{OP3@ zS@h>EBJ{^S>JQ>$*Ow4PbeE*eqYHIVPV--)NTn~MS70o+_16>X{OP`>UO$7}5qF@>yC>fr zLv5S$*SZgLUf#QFd@0?VUCq zas8Mwe~2OrJ+J(!lc$(d6BA&OM`GU^Qb&XZ2h6hzE&S8d|F zC_MAe6QCA)Uj6ak(GRNut#k(Ieev+AJAa6xk(A=}Ut(XnvG&K5QCKf+@}JR&a|4)}H$|9(yjY@rNj~ z(DUk#E3C1AkXQXg8D>7ly6|NaabepWPR~VE`tOTIUNo9&YmBwOL`^;Yi2om=$U+JI z@t3Y*OvdYlx0pqCFxDOa`R^zWJr`Ax@5Si3!$M>2r=^p`P8)p~wNOHTJb1bV_@s^$ zb^91=V_k&!AB)@O{D&w~>Cg1HZpW#{+AkU7ab68ug<9x&^~YIuW>B!;ttg{yd1Kup zaX%j0h5d&pQt8iBG)6A2RlKpbw58a!==#(@M3IG_SAYE1J0B@wtTPv5WY4#x{vnFS z!s&TsqI+MPL*eyBbm_{9D(wT(9;92aoo-sULOyq)zR%gi!Ta#)&F%4g`$}rI)f(N{ zQU$!~u+5CpGEt#rV|B^HJfYnIrq%b&d9V9gq?#{EvWE|_21+m5meQ+(>gZB#e~_$ zSqkE3M^*KSd&w5Y*F$Qdgs)R7d%d|TYm`w<5SvQ1RF~DWQX1shNCZ{ww_VG!me*&O z1NFO9<_GmtCMP`A#kL-UM}ALamCtR^`c|-o_HzHR1A;)L>hkg=4RnNvR`cuYplbV7E z8Tm;W8uUrKyjf4A7E0{tvXCWwI;*W-QcvvvSXMpeZ^7y%gh~We(fcp@IAbfSH&%ME z{5S29S}3vV$uhR#^d;?FV{1{y@nH?rS~HVafVC77do-{Q>|IwGx{=K9$3pt7nD`rZW=EUR5kE@9~M#& z%XZl6pR3skYgy{+vPzS*@klL{_*fXmJoEao@`v@r5GN-#GCovcO~*`vdjQZu0JW>lK_N@$L za}(FI{q1T9Vu$SrR)6_g#UXaML{QcBHLcmA3j5glY<=x>(dGcN^|`9NsoEdYUqrAu z&RMJlR)L4j{n&{o$5}+}DsXvmDEke0tjy^0f~d5372Dc2N9p`PytTwai6tJ**y~Pt z%>09%u&A_vogVjIIXJwhL{Qb^o9$Uz@+($hrG7rjXXQ%fne|SIoz)Ymg%Tr9F;=G5 zYvyuKPXv@)!@5*AQ8g_(N(5D%p3#n_UNlgqeJ~Ql)lJJ;UZ{z>t5HX!7D~8Z^1 zDWPn8rzbk~+s2OEvQ)c&Yad9X@k^430<%k zEA!b*2^;)P5V0cpG z9v-YoUKM3njDD~9cI|=XxVWhkTDnUFRpnd?U@_Bel(Vn$1d*I^hq>-@QPW*LkXk5l zxS>0HqSR1!e7LJG!*MOMO7T|PG-)gmRCT3A6EgZk`cq0a5pHkGSL z1XXo)a%FCF8Y`1F>=s0HS~d$k6RtY#D2&(GT)P>F5>8U{FC4vZVc#91w)kEzV z@)2kmRMl^LYi616s|;>CRS+#J<*@VZdZ>F>e*kKsL|~ya8yxPd{PU-egD(46`5jT} z(X0m&K~>{7I5W$Aio&{#7G<>GoXs5UV$_Kj&V%z%XO@1vnWB&WG~3de-EGxO**K>w zmx;z{1+1=HKh>+mHJ}zs&|fRoz+R@Pm)(4n{=@8$w!CPI?BlQ1tYL0zmI9ST&CnyI zjaqYdHRYvQWuz8LES|N3B?q@+8y@T1iML(`sMhXnmHezq5eP8r%9?bs>lCq2;`hcS>`>xH_GyE;AjXyLrsn;gti(^bD-l$6&vyk|)ovF{cGZvK z)Tz}&waFW$bo0Ln)Iy2GZHrmJjKi$X4t=bFXMAsU&6X+30OykuK~-L3mNU;3&USPb zF>#uX<~`MWGgFjlbxs4dP-4%CW$Z}YS!Ueomv|Cym+PmdI*d@<64QZNC{ZPE5z}71 z!2Cb|87Z>rt6nIbtPDH6Ln5duDSs&|zveER{_%|{1EU72;kV+Hxz=ldS|~BvWf8ON z`GC1)d=||w#`%;OZs$14e+1y`Vz+Ke`m{X=>13Rz@chH;t1vIv++PJlsMOX zA$wnFpxjzt3UjEDdU2?fLbVV?&tzGt7>`WiG~ZJiq%N$09VKMv1s+{um@lHWRMaHYibw??sk5vb1p~Uup#jIETN{UI8e*9`DwDqcBM1w- zacanY59NBsa*3d-W*LiE?1|b+#mjvJ(c;56HL+G5C3NUIPA!xO&tAad8q`-p$M(__ zea5Rj#?(?WjfY7DRlQ!nh#ehorz~F-Ac)^>C#Xjcnkl8seR%%DMJ&3&Ua54e5vQup zj~B2cUngZ;mZu$%8}Q8osf7|FN-kw%>@8UfKYfoSJ+YB`V4%IybB#<;74>i;X8Vz+>earIGSIaV zQVS)5!WXlBnJw9w9r{t6l=<%JX}k8yu5(TjK~>ZzYBV`*6?I`XU&SHA4ylC_cGnlO z-%sM0nV)`ascv(vdT0L#rGI!GiJ&U#6UA6YM?ZC%rkgTwzZFsoB^FO#z^o6Xuu7%% z{@f|Kxte91r0j{dlnAP#K2b#7YXa42CC4i7+KH7si5I5CiT?B148t^L^F!YPP~!d7 z6*ZSAA@$58f~u&8(`Z`z2dg$VGnENDN+PvTB6jpVwik75m90K@(CTwr)o#yPWmlF) zBB+XbI1zc)I81%^WWEwu@DZqm61VoJu)Ak2vldfIi8A7=g{qrJY*CIqekKuAMLnEY z10tc5T0e2Q658SDvw#_aE&MPD1TRZfV{pT_@$w+ZO_(+t|C8dYD{>*-5aWiKxlxeN@BY8w4BqX@5fByQ^y2M;%)GfKtEaQi-4{>U}ht4U77!my9+khcpX;S|~BmaV`s+SV?)X z_oyhNM3cU1H`D#fTxF_6P!;t)Vs4^SjM^q*qjD&EGEfU8Qku+V$xEv%i{|S4gA*)b z)Z-a@l(K94N(5C=Um|MiYXjBHh3l1OA$@>aD3KUCm)Vr7qZ|}Fc8m7as(~u&x>GSf z<0lbRMSY1_eb0P|>h)rc@-?jmPzxn){WF*4->Ron9GWD`c=%+nI-$;1rDN&35689!gdsz=#IrF<`AiJ&U#i9}@P(P8S& zCCij2w@iRqC=pXGg`Em^Q6gG56=giQUrz0_=nT`$3_{+QPYkFDHmrnmk6q&oRO?M%s)UBuMrxr%+t#z#kQ89keaq_0u=G%)9`92uZd8{Ds-m7j zL}n&x)e}COm1{AUNG+7uIyQ;FtaqHnsX69eOLU!o;wWSMH^>v@~N_=)HiJ&U#88n)Rnl06Y@GRx_W<#VF zN^Fjw$;?N5XBA)Q`<$W8{nR?)xyr46Uw{%+MLmPKAEp6n!$xNn=Kmh3g%V*6XR^IF zODU;#&qWzC!u-|q3+^c-Or+;G2q9g|k2{lt?$2$Po6s)>+ zeXi85b4Vhnih2eS#o97dZFcgW(#0wrsD%;}EoZV_KW&uU?&P@>oLnJn^!qf%=4Tv0~Q=1%I1ym!jorlTc-s;FnsXi@{Zs#87` zC`-M@0JTse;l@nXqJxVP>^DM`VOGDZ`my|brLJd)L{OFNaVkvergnN+sEi#I3e-Z0 zb)HGA|xX>BGER7E|5_#Ypt zt65VwC_&4-kyZ_pAQ4nWJ%bpB)7hy>d(SB&tJOnlp~U%> zlbP>>XYBJReP3vXoXl66==T6=4s zqk4vwP(L}AkqD}yoEt z`TqZ}HmyRNkToqxNzwW|Q`%H2B0JfVow8-kzHeExXU+N&k>Z*eWl8oWi4@tl?1aQ` zuJ`Tty?xH~pWE#`?&jI`oS8GvGw00Qk_fEAoOEe{)3U4xO!9?=|bCr&@ zT0y<^1EP%?Aznm1-->+xku4Eeg*}5xwXUx(vD#)v{eR7EG*jpQkKo(gF6^%@l1cWs+*4G*vsJT9mzAO zT8zB`=kD}Ve9A_0Y{A5)RST8$G4+(L_cVDK7v^7vGiJY)J5yysQX$VEB1KvE!R5jm zMZf!Sj=c;fqWtG8gPL|y%I|9Y;J>bSVA>XM_kW+AG8)!d_UG7wiTdYfE2o#I zDEr(ranZs?FTgQl6MWO|EfH9SJ%d>9e*X;ZzNSFvj2MnBnAoy)hEg>0pmHWf6SIt| z`vG)JGU0T`t`dP&*fWTEx5aO$BfQ${ZxI|@Ffr?0l2TE8PI+gl*%@tj@&|+)U5Ac~ zLL>sKuxAjp;VLcicF!f4w>pSp3np^^o1z$;x~~j7YAV_&t^W@?e|io}#1=dzunKzy zQM!99uB)~m~5M_OLX;G zacseaX|!fZI>$%ScN@^4`lk$bEW$(ZLwygu%e2&|Gl&J4pQWM+T|*{7e* zumuy73KEr~?g~uX*F&^Xd2b0kcx9^`o;HPJFN3pKv1btbIAb=#e2=<{`_f4qTQKo8 zc9wF}y^iwlwI)BY-GDV<{QADqzL`v574{4&m0sj_Xzq4RsR~Zy*n)|4`y{2Tub*OT zq-i6KZGr(>&hRXCf<#~y_6#ajExopf0 z?QziW&1i|hD(o4=4PdJefqz0g*!3F4u>}*Gyv8ftl@!G_UGuH>?(aT`GTsDzt%pkl zR$})X=8slvCLL5JHqm^mbt*anx_PJIZrfOiz$)w+#El3R zr=iEX<8b_!I3pMNB219*5lYvC=`a#K>p~=OudBh=Pp)M(S6(|u{g*}6)KQG9KhXb^ULu??&7EH8VHCPE9sRe1b zHSxrsi!Z{on{~;@b>0$zRoF9#c;eG*@G--b4Dj~m*n)|^%?2sieT~8K>Q6DwfBd=v z|AyL-lJPDQfmPTuh`R?a-iD}{hU97|7mh8M$To@n%UIksS8z?A{Y%1?F>ny=aOx>5Q7(uaDJ>+20A0;{lR5N$Mi49oU)1Xf|sAkKiWdUxOjqLJua*d`l0A-P=v(Nm7e$r@QHCv;*k?RY`F@E&`qSQ`4O7cCFhk@( z>hWs~XBc9YoNf3%aV02kV#&TwSEU?COyKrJ4rJL%$l2P9L|u6=5m<#YHdU(5&zHgF z$lheO>b;c9i3$9>iT5#QIlL&0B%|{5q`03ub%*LnS*)1A?_Wfn z|A@0q41>t|VHOgBRXDF#L_ho%g4>565@Bi~Vi`N;z(UU!q(zjEL|_%pFjuMcou)#!fwp9qqmPtHjtM+Jim0>W31>LaiU*HehISfBNVQ*rlTbC)4fr3EJN`a$HX^&JE=2cLjWT}Mg;R^hr3 zv4$Jj6^#F$gx_aJO7$O@!0R9}U)|{q#3KdvjvX%%ScNNMM2>J~2;AoDVA;>{QXLB> z@On<1C}-XcHa;5&6JjPw1Xkh799QJiL>@MdO1@UN95 z5m<$5nnV@dz7AmWp$RN0NRld%FoDY6}ziJ3*z|aL5w^ZqE08c0nev>g9pS%C(iJeTPo76)Uoc7cHQH&raWpjF}u; zFoC~!#5c}82bk@6^X&K~GJ#dNu257jJ2WR2sNgh#Y4W}tBJD&m1FJn1Y;YuW#IF%nwf@=4M z7LRL5S$a7CPR@vLX4IPuP>qB^xjz}UU;<~#t5jER#48QwB$K}`#lB6a-&2coW1*;Y zk;8U>Q>yv5RnJu4#5QH>`6*ps!x&dl!&~V$LYbGGOd{$&kSv%OenUkSL4=p@6-0xf zZDGjl8D!bUT?+ocuqwR8EA`aJ;n3RqxF7~v7qfF7(aOS8@#G8n-^p}}gE(zr7EJ7T{EA*Zv`BgUrI8>8FDzyq zek@mlqT?k3t8zU`DLhS4cIY+{#H<;2*cDN4(9~@Z@wGN(kzbD~|H@6^wB8kJ7IjLw zKCCJHJ7B^b-V`VkZy0I_*W2vt(1notF_vHpCYIjGr$aVhRz4au7DWD_E3ByS1O(6O zBN12?EovEVyF61SF4Ysn&t5m!YmpmO(xorK7EGjQU!=!pmMC9z8wz4+;w5&&xd0wd zi;)Pd>b@Y4R)xJ$HuSD9h=SzvY~HzY@cSGk5m>d;)_{equ2Lr3s04Ap)_GP{_!Nfc zMGn{ILT)SHcV(quHta@h^__hs`2&@WQp{AMtw7~95T|xLv&tWTH)*@qX z2TBB1&8x4+&W|vJzxH1h(M$5P*j{Q#e5VHxY{5i^RSs=B(g0TZ))sAC9dMYv2^aCD z&7Km0RqB;mY}Q~4u=)K=w6T|;WMd~<5dBIYf-RUhd*c*sTUr}lpVst}u#<<_D}yGa zU{ptmz^Y!6C+P8(=D>ew-ub7p?X38b3%NDPkr*F6L|@xBhCOSll+HF)bpGZh@aFCv zC1cZn)Iza_5mlP=mJ<4;v4D4NiT=}81Y0nHpH`*nxM2?)>Eu8fU3QTOtdgI~YT10| zG$D)}_BJK$0>03;za1d%Ay>SDcGCyl?ZIT(8)fsS_f+qp6Lg($Qv6o;n$Bly4~LOe ze`^zL!9>s2o9Wv<&XA~6B#0EVBo^irO&a&rl?bf*HRKgNKH3#_EU4 zZmtTMHGv+w)Cn9%X@09o4rVOnasmliu?esR6ZmOGPSK2pEUVsl5-IX)F@aU`Q_V2H zNe#azk>VFUp=5d&+PAbbjNIBysZKpfZygE+yNMrszwPZ!o3;#r9mhwDr^<4@OH(f- z5i+z7U<)Sj6N+4e5$|ayyD4OS?_`O2QZxq}3yR=ylbN4j3E`tq$8L z(=Y9(xjJ1S{``2~mhJp#=a4W6ARgkWK7`Go*M`p`H`25LTQGs2P^>Id_E4Yj8D#Q2 zSBbzX{EGh zrCy~^vUVwIi{_HA#XeY^dA9aG>-yFPrj^PBR^gR_s3p_8&x%AG&*@~G)CN|q+*nA* zsL zj}b4Z@q!Y?(bAOJ=6<2^&n_q~Zkp_!y&j9%C%S4xAf8Nf zWe$68!0W0wi8xaK9v#&3iITL{lwn%ru-NosKjuAvePaf5tkT@B;@Ie#a{rxK4I-wc zH9OU?2KV?ls-tr~Hn&5j(r%Yw4Wel52X@wN z4-Dw0LxyRQ*ijm$H2tu$ zPxY3L&UR*W{#s>DuBP(-*L2{WFSUVHtL!*d4N7dy*7izOYFT`#L8LBe$H$w5g4v|@ z65;UOj_qoEQfY1bm10^{lfQH4qm!aw{gSpEtJ*%dW5LEdl=#QLY7imYTJaOj`-9do z4~ckGuQ@B&yhrJ~O2sfOvb-w?a{E3+`8V$O|L*zm%ATYoUO7+QngTm;da+_Vmr~80 zKlwA}D1PrWwU+r!2Xd1~Q|1hi?9plZqzgeT0W){>ST*Z#hp2ypi?zB=OKF{!D zSufWr7d_&Ce4xh;OTg@#(3Tlp>FEiHJ=P zV*Sk1m5JxKP)v(&wX?&x)16()@;*-)R-G8!iM8e@m6yx+)gW%oiRWI`50&qm?n=bY z<(*lbZ5c|>y~`=4RjSn8@%%`1mQwC~k73oe*+J}LK37H@*ieHA-#v=|9af=aRGpWI z=A*({RpT7xX)?`QGAcWnsfi ziP+*A$(AfVr&vDiPBASiy)(!1($!Ct1v^hMtXi@yoE;i-M@fG)v<5Mijpv5{RV$Y& z(mH;R=e7AiX5Jt?NeDr0IQFEF-N0$cBq2>dqBQB+Uh%RFM04=)Z&@1x>W zICH$ZM~SVPN@e2T?eVOwdg5`f&TMhiX5~V^)l??7P8rP~Wo_}*IdNGc@aV#{N>%^A z(Y*DiPD+c>m!uIjZbvZd@=8>Ar*EP%k!m=a7qmA}lG6w~6Q z^hYE3Ps{zjeJ2%41fEwgEmp5hNAi~j7Rp3^N199K&kJC)Y?df>FYl)^aV;>OZ?*5@ zyKZucMBw=m)8bs5I`MpAS#!l_PKh)p>Kk`rlXB-OX3LLKnP`(aoI83x_MJVuR3eHF z_^~TKQe2d>xS z{&%0-|D(kjTh0nizGO>&3=ibCb*|F=4kqAM{G09_aGhG2T0r*V3YvQ844reM9z2Nu zBF5lax7xHpRBPf{0UWF9IH{@Lj{4B)=c^h-(4kKBTZJ<@Ip13%TIAfMR*M_KzkZJ? zrd6stM=faGh3&}$;=!@1_ynaP&W$0lc4-abQG_?`SLsFER=7yS%62#IdSry>oQ7uN?%$UadjAd>24ZuLvZ5DYg<3QC3L1H);(wHjH9g z7rC;uZkSo`la;(}lE{_g5-~@3Q*)@nWtHbHj{*h$#cPojQHR?XqPH6}4eU4B} zYcl)w=zF_pvf+C@j#VelU!cE7xxpu^eKm;u?%n8**j~i#yrD#dzj;8D5<7y)w#^jN z;?yBM2f8x94{6(~7RRcN{+DRxWDlr%u&D-dI-bz9W3eRjK_$Zk?#GxGyGvuj=-1#_ z66W$t>bvc;@@Xx1ALtjljLJm(9eY}RdKful^g<%==)$z9)i<%Hd(*7Rw15bHsa*~= z%`=8IJ^#>8=T1|H8G110u{Oh_K*SS!yU-jfYhtuJf@76V;br=!SO+?%>C_;WC7RHv zC3VP=tKB7H@_;P*>SwjGDMFuNT11@>_|kj(jma(Vo*b*Lp14G{qJAhNqbb5)lTG zhkV9}S(^7FfA{~BdWnux1wCQl4h8Aks7yExtfE!Vdk~j&BdI6io{wn}hl?;^TF0VE z&q1}N-tHLnmhP+X45hV?QJHA^=R2KK9!?&ftuGOH1Y=rc4&2jYhOqm^XFD1q}W&T1}h$w(XAWmL4oN`@f?TO}@jO`vW;v;kbrO zbUs`}$0j_19Ses^1de53TI7ZABkXv^TNv1HpcG-rDtJY=SG-pOJPeskG(GIW_=JzZ z*AC!Vg`Y$wUYzU1W*yZck3xG%#L@|G>4uzYWm<_2!?f_uGrU_PJ35Sy$`iuyvZMmX_ab6io$#<>yW`wksPaV&yWf8X`!r9sWmxo z9wHI*nth@rdrjfn)Q=R?B3JE&9}6AYh*<0o;#h@yxJ(=}iC``lZONKSMIt&j{7PR{ zS;89ar!~fh|F}R_*~Ok@_weOdg-0rGPvn<$>&8r0IFkoA+$5ssfFIO-a$|V1;!cfm zuD%t*K3lsIlPXt^Rd~k1?Wt7L<6>BbofpYp=_nE7_Wh#U6I()&Ltc&fs_l<(c5jCd znY`4VV-=n`aeJa_YhfSeXc<60Y_gGvs5gITPDN|TeVkEa-d)q7D@&aaM7oY@$gv80 z0NkF)FWEnU^^594dVH%R5&!C_nDvu(a4~mB4gaxiUJvHHAdAPWv_OGI3n7V90*5vod-*YJb!H+nO6vnR0)R&lJt9vQbM-ucKlR@uEjd1&*N zVZtlqCr$0IfUW-68vgu6_yTrm)?>K7qrVj2z4Ez|iedzXM;b`6UJ*n7Glw18`3!Pu z_vcuJX9*nl6?fOfE@GFee?al47>Ovm_nQt&uT&Z~*I}4esd{{w$F>fxf^M!c9INmw zArp@`E@4S8YLT||{h)b~|5&jO^ z?8HPfus>Q(F)gyy3zjm!r%i}zsV~PWJWI&L)mCfR2xA9Q+`wHTY(ML;7uOm<^|m_{ z(<;?+j}>e~Vk@Gzt3AgmJWI&LlJ9HT{RysQUSKPUn8Eaz#qnm4wK={Mi4@b~%gb2Jb}o)2o2%cmp(jk(V0#ZZ|9T?D^kQ8zmcP;+UN)I5z9vFP z=CiK9LP=!wSE-GvrWWki$+lo}e1jwtRoDnmqumcPDjSxyzwQ)-gPAczkf`N(=Wnu*^{^4$(iOW&51U72F!H4K3x3xp2|e8_@gY$(S+!|2#^Ro&tqD1S9}KZtZhVg=LSl1 zyL)YYcG_A6AM<`vnP|T35Q|!>MXHa6O9b{;m=^am#2jUNfB%KR!CfRDwQi&ytM&Sm z^83CPlZp8y>FiU(3TSgZS|YID#k5LwZPOv<@A?L=h#f_&+9y`ur%cL~?!~p3OmrQx zkA+Puf-!!5Bm(dDVp^PrsDFS3-?#%ld;3UhhV${-Y~!I@%Jf)cCKI`ydzi;c4o^P~ zl!&9&|7gI&bIQ$Ibr_~qD%-HP>_xU0>9JLZ-(pjzr*bhiOq`GU+vYZ_tj|n$+W1 z^)=s`DJkN-PoE4b6HZUcnMq_TayPt@MBs6UX|Xrq|D3%{bRd4?Z8%oZQ&z0S)cO$9 z?HrW}zhkBBamQw4xw*YW;Bkj(aq5uy6QZVOgbQ5QUC-lQ_&xAp;R zzr~6qG;1djc-&!Hoa0ql!scgKkY!q~9IN`SH)Hqy7(!WQDV2#&5AU)2B__nCftN(! zaffMfs-t!>Yp!EV49mPYR((HJmo@IF14p#qQkf|0a)%9Rp+inu`AY;IcbL|kbX&** zqqWGK9Dj~gOJA6>Hl2PdD<*xXGV%M}4c6553k)0ISt9Vb!?d`y$M81u-Sq*?K6U0; zb;+SN`?~OrQeRueWTM@HC z?TSRa1hpsjqi$bjlj>fEaF-Z~z#|pYB3tD46}IQg1=un^hGP}ZRFH}F^b&iq;v~HN z*+(L9b^@lw$&q6XxORyXIki%o{YK8aIx(QF*EcF7BytU+K`KzbU0Rx z`PPEb*v8;KXFHV%PxD%QT(ljr@ivtRJnk?pavUE_q|9YsAs1j<(vC4K=6V|$}8N_a-R3;+(Xz@d=y7mD@xcHap)Kw7OlRGT~kCFY{PxOa}jRk_bHR zFfCS=x&K&jr6IA|-Iin3&aj5;tBoGKwR%WpVs7Ct<}y&5yqeKLBJjAww1^s9`pXWU z{|yy^9$Zoltk0Ir`=ONYc}Hd9O3XKQ#P2Jp{S}G8<8CLS#V*zXj`M?YX2v{YoajysFDRcm4stdaWel^*vkW>Q)OrG`w7+mz)|@ zm%se{7t;4Ra;(DrRqj{6#+h@goLYo9G?R!{*7oeKiwUS7=hW!!jb57Z=vVq=(!Qn~ ztMItP?TOoNR90M{nG*daRuZwHkE4jJ)PvQzhiZ)4W>YMAlMi)B(@&NhtML4R+Y|Hd z25TM^ZAIeUO(ddVU2AsZmlbTiyrstM6KrVB=gg^3l*PsztMELC+f%77+cn~Q;v19Y zE?N>X`J59g%x(k+{w}RCi~4P9$lIkfA(dlQ9INnrj@uJ?`b``28xJ44v6ST&VD(`Um5Ge$ZFtvTrX+3tZ;8Oa8>YpXvIT8;ijyfZnOViK zs&bbr>sYrg)VJM4Wx~9`ke$#y z1fEwgEl!pH+KkuQ@eKaN*h+KBn2C;T_N;Hp)3Z0JOnjf&n15E?fq?!_5`pJOOpB8c z${X|Q`L`fol9Mzi+V!<#b#FXX#x{6DWul)|Lp~?_47@1oAQ5<;$F#`Oo7j-I9+3lj zFFQzc`-_n+*sfZ)l&S+Cs7!1Yxe{Gccf-a8AQ3og7Sm##7*?O3nz{>oMVSg#wLaOD ztqM{r-3L@rnIQcvxI@$B(BOEWL}dSK#9IA5pzx*x5dWEB6&^)$Z;v!pxNf)(ncC=yM7;XZ zk=>bIABvldt}zCyM|b3PYL`L>ankMQ;P&i-%P%G0DT^9k?7#w=>Vo~~T{U{*mADSP z1fD}wEfbDacudHB*P^c{Kil^c=v>p52>k4r7IoXZoOtAzY}l!1$8rC`@7d?NGrPY3 zweqBn=DgQyhn;wlcQ&*&u;W;D=5QOft9h|<;9fD6iIB#vxLN)lSXI_mBJg|0w5UXC z)`}0!*#jp9fmIDM9ht+1OUn8uFR4r%du+#hO+E8*sbK}&K zoM1jG=Qh;o{heXe&1F8UZ1gWhZ|GJk6E}Bu;`Z;(L91!{(mTg}4AY`Ed`2hkbS@XH z2J1^baZ^1{c6#YM#UD`eoZ8WW9|<;P;Ga@$Edon>*av0mm2GaI6|O)0Mfat}C5(-=Z?1 zW8%S0&MpUfp`}FN_l#+AV|qbHu4l6nJkGb|SY@`*nf;fiRtB{xqcXALk{dU^l?W~m z+DHWM8JHGhaF!b%yLmDkdD%wFR>%4DGEvm7J2xmk0wXM6Gu#{STO0Q+fDLx}u8g{$ zEc#XP*JwWF%71Wu)+>fp7Q6hI`R_N%jJfNnOe8gp;tQ>I!ordNBm%!ROpAP9I!T*2>jMCtx{bt3+BxxE)bCkGmcg3@;Wk`nYjvI zkxyk}$CUv7Ut%2m-PKSc@LR*Q$nx$Rz;}%w4Yp|wIaXaRa${3=oKRkfnj)EaxXzFJ zHVT2mj?EpfsqtRB3@LJ7l72MJ(^}ZZpj7bAgR$8p3>v|0<>T zyGuRe%Gyvia^^S1@Vq83{92Z{0n;x<98-9a;r=tBU1v5%@450~Wg?Y{utx*mRRgp9nbz4GN@>*&DieEMdh)%?2f^i;Dvk-ZwD6pbqd7ki4b|feI98=j_F-KQ zoKh_IQYsVi0a3iqHCHHFQb!_i&%m^}zm`Yx)NwxWa$X&dRljz6GU9na(QSW)%EX8E zU3gZlhVX5Hr9|MKh-sDT?9OoR+|?GUk6B8UNG|_6upj?6EB(CgQJHX3h4HKIMsR9$ z1BsY>qCKlzze4f(_=I9wR8D3O=f-~sl>E(Sxc}hyEZ0rES}>e{$qIvRA(t3d;R+6! zpx#5d-zgVpQv6UN@O#Fz$WHh^gdc9|3ob(+Fs#CrC^E6-Y%CwYvBA>%{-wNLslzdW-!rDg7v!7XJZy~-WK7fHScNN`Wa8?Yo?Ls&eWj(gp+w-G zfoZX~t?J2*>U~kVxfyb-!j)PwG3Zhco_qbOvfso+BI*z5$d;^Gq}1Jazed%T@0(CQ zH~tZLoO&YpbNnrWzhp#BgKZbS>}(0Fb9o>USDb)N4Kal^VMC?w9Z}7(A)G%r_z0#( zKa_|eqx@OKBtw|Ab0EdEhyk?d&htz1VNUXGiAWnB$oeMhf>u%=ifM6kR(wysdt5e* z8*oP=uxG%uSnqZ*Wg~5elE>}K8LpMU+3Gm!Nu?SUt)`Ag%ivnqI4K9RIF-|shIf>y z-sTMFLy8E!O*3l0_5~Dek+UXoJ~gJr-*L!=E$B6vj9v7U;S8$hpWjp8X8`_3M%Kut z3cSCJeS$t@!0OiwXI2<9E!KCn4mVxc>?@8_m}oq@a`+#ZxQ!R1RC=}w_S<3 z_Gfm#ZFAN%tPRwjGFjR`#Su2K0%)qmyKe9%pX*de#Iqn9wqm<8+-1Q;-^H&+HK1cgFMiHwgJQMIfa6&W|G#qW>yz+F{NQUx zW#+m~?AeNLtky=RytZpaalN8k4cMsZBtGE7Qspjel!&#LCVYUwb!JM`?CL6or`O}#Ja>}3g@1ie2q<3vJsu4nL%o%awn%5#ZM?dRl@c- zE;c`XkC{JZrv?%BYwQSRUw971|1WM&hRK0N#2xl)|1{wkJjit111 z%zejjE*GAC@H{5YB>%RXHBaqMyfQ1Kj4hn+h37F5xjV3%bs5OP%Q9BV^9j$n%A3!e^AW-fR2;|maMVa% zGuYpDY+w^zds?AjfC zlCl_{k@1{}XK=B;@<`xLb>Au(ZFWf&(s;hYv#ZEe%XT2;R*T`JcL(ysdlbDhOCN$& zda&e00v$%Gl>`eTa2gj&I~nT1^HDmWQtirjA#Yd5!Eqy3f-RWX>OGQ9tzD(C&IW?m z(Z`e|HQEgoX96Vxt1=fy)3JMW;N1bunNAr`8j%N{b70RgKY}fo&^{kaLF<=t?Nlv6 zwBDyr0zdDBI>n(9fmM@IV`!&lmCC(X%}G=1cDg}_$|O?AY@ox=Yw8Ar!ojh{5np^> z+bhE&_4U*+h@D*~&U(3L-wl#}PbGRM>jJi5BDdg)dVEP3+{}F}hzILpV1Liar2Y92 ziNGq;pT+74yTl#P*K`zdVpi-p=-OctS#jAPumuxoW-rteeucu2uDXIK`ZgY_q7umM z*%KuKtELPrRS%rq8HW6;FNp5N^I^H|1mZJcEMN;J8l}Hg>%H#`kqOpssQem7 zViq2j2&_s?u2A1P9tia>h6|#bUK)IEIgH%wc>u5l6HEG5tMhvYfu3&{LG1R}0e$`q zB++xuO9WQsRs2xfC3b?`hQkDLmLG=c$^dexiUYP_BJHgX9qJwcCl70g15*ydivzug z(eVcofmJ07RMhbsfgV?82;#w#EKq-mAtQ_L0k&Y`Z-ODcc*_r(&7Ua<_2W!9R1rmt zCw!0yta2*Uqf5ON=oY_J5F3`AgU-Q`q@n*?z!prrcBw=Av;#0N(-1FGDU5j#LQX$X z5lmo}bq`~z>g)~PDeDEX^+^FV2ni;Spc=3R6D=(*>8cnX=<2vZ5CE5;%^V=(`xz5V zVAa+iX4JQ`18|Eyf|#LG1TzeL$%%&s1Y0n1+pRHe(!vAWpJ<32dK=bXZBI;ntt0}g zQqMG`cfwpD`fY|FX5V`P@pIadOH<4VwqPPU-j4QL-5%^OCP?4yW)nfPh~a)TQIRWwJlBE(-zA6XwFqDANvwA|7%DRdpJr2 zR=o>uO}qWJhgOrtO{`)m^9`~eS(9^3>JsM&-Au0u;^pj*Q2Mwwsp!;B zBCsm2t{crxZU%{u?+fDfz`qcA!b?<>7Hg5d|`^*2q$Pf>S zz^cpZd}#BG2CysSxghqQ*CCcm{=kLBZUkE}(fdRQ-R9f~+N8Y{g#BDC(su20sQ=AZ zBCx9C=>XbigBfHW{3wXdKlMqu$x~R<+>2lfCU!LIN?)2;z`@~P1hKhPk4(3`0s}|* zO9WP>4hyFRp2qM;`?nx0ZyS@Y!!LvOW`$r2CdSq6O|AbkfoUzP1!45UkbK;o0lAj~ zB?7Cke-vxDs5)dt-Z8MM=P&s|Okl4q&W$=gOED{-LHzf(fd;w9)tdssVet5LU+fdF zbvvbwZWjjQp+tDKiqp%K)vsod2WK4tTQKn<OO3_m74!Y_eO)kDE$vkDD$L zST%LaN%ez^A@DCm;|Bwd9akR3P9@AP39tnd%e&;M4c~>p^idjOclYDU8|z8r%(ZnA zfmMbnr`0R320_yjS3!(Q%vbERCz1ReYXMs@;aYG>ZTdF|JZ@`7c(ppY@09iBqsY*Ad4MgLP^${nrLq2Cdu^y7Ttc5Ib+W~2BqtwA z1Xg+K6{uVE2T0G<_`$5HRm$Z3_tY&umuwf(w?h>?)$*2Mj9gN_g|&<_devo1Z{!| zteSkTSiL#O6IMrQ{NU#o#&E5&4{4I7MX&`EuP;}q$1+bC(NaVBztsh+glJO!v9?5D z)yjnDYUP9**ss|wh&u}`AtgAP7}(b)*n)|5{I@ztafdIXHH4o*Z8&BVO4g2PC=pn7 z=HMr_Ux71l6OA9tU(*=M{&glSr2)YfOca>w((pJJc=!F7AO>Yw0QeDNQP*A~uqxBJ zT3xob6=dY91(9N62W9SrY_+o^*n)|}&y8ppw1&1!LzJp)AoY_wnf#!gL}1nUSGu%C z{gx1RXMr!-V;Q0OLy>^-ip+k=S{E$6Y6CRXqtBuID1e-41V8A?C9H&?oWaw0;_Ztb2@#c z6-3#W3u2+M53DJ*A@>Ud3ASLu!m&A3`qhUG3pK<~TUUU*I%HSND2c$T_jMXl!%=l$ zb-_D9TpQ{S$-nE6Xp2aKEtuGpL(FcRW`+zs+Q`4 z<(glDn9z5fQcAp{L03=JfozxG3T|7BDC<=(D9Vw7$x5m<%iF>(Ix z-HXZ_vmWG;BF~}^ZrxVD-sK8fU(yvkgNs;3W(y@UvIl8*%v74GF>z@5d37xzG=ONWQAq?=VZS0W0jZth{;WS4`$r{t987%fuU233^nn9wG(Kwj$&QLn z<`DAY+aqr2>Ca$Lh_uLXj6Jh-O3#x)LQe+d82(B<<{qT(rM>? ziNGqnG7uSCp_a<;l6cY(ilr3*CVV?)sQ>%q2fqesRvB)snkh5RjUnYMS0bn!xBic+aZa-D!ft?_cZu9C>!o1 zkO8OnODi%=-2IxaZmAm#ccYv&e}{dB?dQ|anf ztwUjFHU7fCMPBJ+qWgeD>LiyiSZVlB zd>dr!IN)nHZYKHKpq2D(fK~XrM4U`9t~Ie=vJU3Ex07O)_`9aeAdZ@pn!wlDns{QZ z1bcGt?K-G<;YP3p6Zi{B%%aO%lFe`cd>vgS0;}Se#!_z^GdMJ zW;=o{n806p;xwx*O^I2k8p?Oe1Xg+H^`VVD#VL8iHK+WWO|&J4|D1>MA6gS^!Nm5Q z?sQ078yH{sRuEJA+mOkt^Wo5hb_826fxmG@-#yoebX1i>;jGpYfmQvcM9@7yn?Xpf zW|i^SRS-=|;mr5e1Y0nHztvT$O?H;Vecd-u^>ma7tjhiuOs8$M17~rxgqYhsY)H=a zpD?a%GlDIcSU!Nztn}8Wm3;Q-$lC6ze5^TW)j<%>&WxY&DVv!}e`N3KuunNb3#Cd(A ze?V7pcX(J?{L^1i1XDCfC;RsI$}omZ}Nv_-;+fffx8Zac2Wc}5Yg>2&}@fUJ;pCl>_~PVo7Dd0g1q>(#BeJ`@;~}66G$QYDYvS zj0_w^%;-VD7EIunwTK8iXF#jFapD}v6%v6}hfY<=A5_S{?z z*n$Zhdlz%NT^gkNjwRbdVk82qE?<17E^QVLclDo(nfgbTF0`LJm9$D64A_DRyoaDt zO*_31I{PM);Zp-70;}-OhRFB1@*FaQ@?m+0NGX0bVq+ln8LbVhs|s-JOw1)^55cT& zJ}fQmD#ge!@i0%JSHBs;zkQYBw;J@T4E(a5fQfskL|_$;0g5l-=7sQYKsjW72$y1g zm{>WsBem*M5315M-v%8v6vOPy-;nJbAQ4!FW0@+IMfo-8@vREH-UUf9OH9;0>`bjj zSi`@Rr=pFL?YCk4Vk5H1SdMaH6^_ZORLyKI!jg%`V?BCI9J zyxv+OunNb>MZVAEQ!t>b9qHMktrQE##ND@6l-joe=0rss*M8-I!8#XmXhL&|z$zT; z7iYxB90mLQcBC}TR*LCk!gxa+`qZZ#82D-8C0DN=hX-4|$#ebs5`k5C&qAEHl(83b zfB2A&wHru#6PV~6Z9td&bBE5UnkY_Vt%J}#G>9}_VJs0?g?CcK?31_^QuBgI$dKC7 z9t$R(`)bktqr9NMx8{qbo%v2^xh#^L+pm%ctin4&A}>5`J^YN1B1c5cGqzx2S^uBv zj09g8Z?E}c*|vNWEWZ>(ZcV6=_M@;0?}dr{_Qxw=U}jHpeE%nD&kGaZj(y7Q2&}?; z#p0W@FalCVoI2pgT4_%h6V|V8s<%3JhNJ14=y{ZJB9`=&^H+nC5ab4?vPAQb-Vrz6@J_t6WQ6-*)H%7Y~WtMJ~vSoM9h2mirSiRYtm zX^$QgKV7e?wTFknx^AVy56<|~0_GJ=BO47GN(5Hny%2F?@9PsV=s5#Z)Bfc1y)c?Q z{<{(%rVDHnp+moZReC1r0QOfZ)w8_au(XK5>b9{2TQG6ExC6Bvt_A8_f5l(^>F0hJ z5MBb^X)lSuD(tVs+#a(7dR}-4D`)p1*n$ZhVH0&lyLLm@F5jWY^llP?RoGvNJQ>&w znfBkIbLZ{^TQGs+ej+QZbUU2O)+Zy}!XyH#u)k8NhF)C<77z4Ev33`NEttUZOK~F5 z(Nt)YZ$a{l{3Qabu)h*tkbhP}a6?P-b6Wtx7EItcthkf4_B!~J)tvn7;VBVVh5eQ2 z?bjE>H?J1NOT@{r1rs=)tWvE%vI070wk2EQoh1URu)h*fgDLaCqk%K2_s4}`3np+} zT=ZR?#h^9LlPu`aQX;Sl`z!I~^&<&-fAu7NPuLM`!32))i}mi;IiOtcL}r;akO-{8 z{z~jeg^hvSF#+V!L~)l8@{pLo`xGkG>KBv1Ag2r2Rb?U(ScUzSN_FAJKsY`of>;t$ zf-RW9`z_*zipn^+-z0|YP1lkLtit|E>}}h{K*^*SGW)qU!4^#5eIxOAJn0KVPxd2Q zDn0-vunPMtahmSyP*`NypY-+r4A_DRy#FQY?rKMY-^;<|;OqwyfmPUFiG8*23XF;x zLh2nY0c^np-p3PbxIUer`=NL;Lv>yvunPMtvA6By3f1*T5HP+7*n$bXA1Sh4cDTb) z?XhH({b7l~D(tVsK2CKD7(8Vxxo3J5umux%UsdEYG_-@f7YW4pL5f6R74}zRKWe%; zn8qZM!o%wTTQGt5hebsAs5yMSGMRK$CQAfXVSgn~Jx!jyaTe6U1d z72b6cyU2!?(7VY?7_mzxunPM`ahA8vV5mC!8YWlwm)gK8?5V|lkTej?e&2_QMMES4 ztMK|kM2dFJ2KTl(;81J0L}1mBDmPku?2B^ao#wYnaMpv9PanV|fBCn094m^GGt}RDEfu8WVV5UF^ht{|800?8yG*=2GMiN9%BWPNjO-RF~}U z)RHvxt4FX3$KhmRO|2ww{W+N|{$~g{s}x6D3I!oZbP24A)9v;`uRuW--U%>^1viRGh?iU?d;sJlJ!0yW0|h zRr0MptsjlzV-H`?-gEXU!xl`)Hv>)99?g$U4a+%hbd_NXCLRR@vMzzz>Ng$sh^Gp- z9>WVVk9cZ-z9Y}GTQIRjCz!RZ<)I#*u|>2oXxLcJ@(+2Y z?B)`IRq{N zzsPnRaZn<#O1_;duUi5i-u#4To9BlZwqWA#xNugwJWUy_J#7f9XZ_f%#FQjsK=k;Zv#)W_OHPCJ|VLYnnvn8Jo;Ir!Dd> zPg*TiJ7MDS{;q7Z(>?XS$)1`v>QCj1eSFh+H9tmofTib=K6|4;NxQ{4Xw0$VWgMiB0k-mA_3M|2uLjVF8(ZHyi+ z5mP7z}R_09S`P=uOJbfcl zBCzVfe?3{{qf<)y#=WAA7cZytQ|IU9xb_NX*n){RX1&;^%s1+IgY|+4HlN9#*8#8O z9qlCot42BYW;6XW6>*=HAXM{aa;@;}oL#FO8Ma^|?NV>{#lA#se?(UhR?TPel{dY- zT;5wt1Xh7}AC{+ND1QU@ofR?tWwZF&F#R0u^|cwcU?OQ-A9m*GO?A#~b3uHsn8lk< zckp`sQ%fSSO4qV4JGk$NQfGRuxA@v_Gn-$Xc|W`5&~Fr5FcBQqmt9|*r%u}*<0GPK zt7h|cfmNPknm&*StU5sZvf(KQl)u_P1W|lsHm_eYCHtb~Es8Ce*m<`vdvASGT|VB> zSKJh9kj&2{Ecd+g{kTM6)jIEftV83y%9WWt1QAy+nJ;+rFROg>e-v9V@zA#)o3wnd z+P6zjK|~Bn<|llcc|3c%N+Phzd|f|gJz}SF_i~CLw8tg$`gZkl3U)4`*n$azqy5<8 z%w=lB#XAL&xjmVOMQ!zb-f56TVAZ7?{n&=JTNItknS#*GO6I21{$w9q+lgWeCUh#q zU!F2ZeRNKNAQs$6=8m80cpVe#e@tLiie7*AZTng!`=q8Gr(0PvAGdp7c36ZC#THCx z*X_?14{=mGEqNyh&x&NOMHhJvYJ5SB39NFl>Cf)kELXnSRto~YB=d%SRoVAT($(04 ziP}y3vtJpn&gyt*DJqrq&tyI?F3cl*#cYYdDz6s(+2))@O6hK0LG1gL%=e7CpLO1L zm>OF!(ZjYsyOw?MY^HWCL7c2g<~uDiI_^5{BN15D%C0}Vw|SltyT?EfVSkeOEjOF2 zMuVNz*n)|9f@o+y@a&ilhJuK%PX7P4pY`@?Q_+WlC_0c;6{*GS`y5+qoArbXsADTo zht*rIZTVW9dyr+2b({t2NY{M0(sLd+P>1NhdQhv6!D{8N-N-tSRe{(O4wc$MbN~Pc C=q?Qa literal 0 HcmV?d00001 diff --git a/khi_rs_description/meshes/RS030N_J4.stl b/khi_rs_description/meshes/RS030N_J4.stl new file mode 100644 index 0000000000000000000000000000000000000000..c2c884e54c49f4f540d5f140ca81c0726988ff16 GIT binary patch literal 388484 zcmb5X2b|SJ_x~SIn)E72M>>ME1$Or)L+>CUB27Vx6zRRXOMNH;O7BHL5yVDa_9mfA z69iF|B7*cPN>keZoS8YfC-+`|f4}>B;WJOpdCw=)&PwM(IQ2lVY- zsAjLOeY$iVP_|;Zs#OY=95}dBq4K4S|I=UV0^B{(P4WJQ_{)u!m}T0(<_^3!A<#U} zLYb~MW@EC`P#yOZ-0P3Z6N6`S{$Gd&%})o`?wTbvIBgg!7RGN@N{KG_Dn0#l@QEFb z2%VRo7?Jx$^RM@&NDWSh{0$?~d!cyb-{_h0F5iBthoc3#QFKj)G2>+eH zID&1B1gHHP+zWdlj_*j~!-erx6qo370^U*T0VFu>FFE&GQh&Zj+{wJyzEUto z(uVQXYx}(x-~1txL~GaPH?XrCzjd!){QV%cYg}Rj5WjDABGLIfoitk}Pf#&Lps72UVUzJ6r9nPt>tAlBFG;vP%7 zY`t(S=QeKP#NQbg+rRZ4Z!T$j8i<0=>ba-CD=6AOE)&ZM?sd4*LVM@liRLdW{{Z6K zjrHA;R|^QNU2cg+v`#n$#N@hEz1{5{bMbnYZuEk(f^ z=EF8AWV&;%I%dXtDcnA*XWMyabd$#oU{xCu7=(;8nUyH1XxYpnwd-*UNy6HV_Q3wZGo4&+;RMu~B(SCpqj8s5_gI^Z&#h27c{KX$l<6PI=`u|LZ+OcMuEPiBFx{P@9XPRzHUt#Zu#0 zs=68m^^_Ot%Y?e(7EbUQF^t!s)V-keYoO$u;9gj2JWEwqShF{whLeEc7EbUwG>kG( zPfa^tb#g;pae{m4Ua3po9*7=5JP!o7aDvyNVbq@g#98=h0r$)a|5<%ipey!p8)pVy zK8OrgA3MDY=W^S>QPgMQ#H>f%?5aCg*h9)=FPZvH3ODU`;eNE>q_1|l7jGxSsBrmf zN0c?(ozUjI9D3Zz(()QHjL}b4J2R5@Ilpvm@2e|LY~J;TEYpnhcve@eV@{QlIo6Cml|3uQ=$>tD#^21bx~tp8NT-Q{lpLXYRr`XaXze5!?$kU@akQ1mcw_=k9A4=Wa?| zgR`TJkqu)akB@wG8AjnR%ehmERCBE*seB`q6Fl-6#w!pHk3(FX05Os0#l86GGK|!F za=IfRIwV14;Bk=GD6eUp#SJ62TY@`w=T!Sf^Q|V9a$A8t4*ai|#^e9gUv7WB`~b8^ zhsS-YjRNBCN=1-`6PRAzV7WbP84?*U4%k|K^$7Q`R?Qrq7x%*BKOR_QcTW2~5UXGM ztJ;cBN4SqlDuOJW!1Rdk7TIZ1BXRA*pIb9k>+j|syiRIxg1lt;y3V#U1bzgfOXHZ> zM617hyqO|)XbaC5(~I7lZLhC}gjF*(sdwYf?zU;yr3NR+3pE}Grr4*7oCIQ5?9kXN ztvkCD-ckfvc)pl^rQQ^KT>&Isy*ME0a?$4Q+bgoWJTLBr$DgGbY4>0KD-bIO&5unV z+uZ$OyducL2~1xvG!j}6iH$AhC)Ldz@6JgsCp9=hUZ|1sOndvaFU|uotMrUOj`Ef} zq)8b`kcH=qX&fK8zBY{XTk8d%K3~esCaOmeXDr@G*z4b*OvC6hKbK>$dd^C* zFwO;yb54*KYQXq6RV;b=@vW^Rtp4IJJg{~g(zrtn7&o>WQ9lf86U^K@ll$!JmNY)3 z1@j~V(>v1_v3nH00%tY!o56vt&z^UG+o(n@<;A^F14grrquDTO9PSpJvj4pE$EdDS zgDjlD^ph+PgM&w01LB7(iGjqs2c3WR_KYCN3pFYv{T!Sce;tTcod*QpKC#NV(`tYu z$inl*bp3sw23x&)1Bg%CPY5IynBu%Kd`JXAUZ^o=-MHY1tw_|(H9YuBzWUA=X-7(e zEIeOKzaA(R9AE7w5b?2-0!iJ|JL_kUjv&YjHL9=qD!I;ZByN@-6`WsYqTT1c1WAyE z=ZooJueaCs{0NDB@}6y!HrS+v+xuUYs_JDvz56OO{)1Z7MWSYEZuDwY|ihz`{?jNgDcs z%*im8?&uu2aPOeCc%Rp=-#QttR8UNe#*uy=cZkn&vKSi9}e7 zt3PMZEVDzp`F5w@$^|hEl$|fjWgF8A7c8(p9{X_#^z;*C2`7+V{>#e$K%f`WxF(vr z@C(^L65aYc?#nxb+(H^e;M(q(RbCUi7zTP_Z>ZdJg^B4Jx$AraXDQRzL-DvO$DeCb z%I8Izkd|-)YXfRU6P3O<!pCF!3pw08t0Xjqk2Wr zAPahN0`j-v|7&7E%Xm+N6Xb<7u2FZyG>)P{7WCo-)RPV6(&dI=Mtx@lA zf3F;r7ZT)!Y5zFqy`3!KgpNvD<6OFF^7#bM3)AFC)gDmL935@fhaX$N2XD=plg1nH%KBdMWo>c+! zMX#>Nf?k}!*+7kRBPW74^z1CtLlWfr!B#|<#qk@X5#)t>I>uh z0iytCH6XA(ZWW8;E$C^G7ZNZwajw-GsDyuL;Tq(H$DvHP0tnR=Zx2s{ypVu;!*z)! zpgnl)dIWhPf!_H4@mvyJX!EE9c_D#kgqn)L|KcB7csa-mk7KE^TwdReS`P9;0&5oQ z4s%X)VSGew5As5S#-k$ezxWq^R^+9Ro7fl7FVW5ORzI%=ssErC?^imy>K43MYMxhD zoFFfxb*$9H(Zn-e$vHt@Na)C?iPm!lL_I6=LW1I$D#x31$FIf|TDS&z(eY4(LvQ>; zOW2i=cZH7TckD89Bl2jDXs`^iAE@mYxDLvUzX_Q_CA*{@a^N# z_IIV0*(Dnuce)t^?RTFow^tP0?-a#x5LZzq?|w{ps?fKs-y8*BzVG$W5Gl zBlhTkarQUKi|tblPdM}xDE-3|zNa;YF+N`*x9s+Mvaa}Z98OSL?XnmPM1}tcfnG%5 zQzy7Hal#2!xuvd#`BOc-*N%M*?-cUqkHc$W*Eaq>WehC^?=v!>)v<{I3Kw-Y>rJokt5=;Ax>ok}13G`JUUC&O4WI+xq{ zx!2t7amj)6Z%nl3&t7P6$$Zq|J%jfc!x+`3tXS10*1a=F?wK%Y&jhrZNzV%5Ii88n z^3;ovN_DpydPQcS}GqiJH*YByt0@w#|AD-&-yto%UeK+w5yxIrw&c)PX59|YY z8whUU1U%a|@!6^(V)Grb-iD|8S=62hFE8!|PxVcFvaj|`2p}2&krN1R;RHNaH}Q$D zBKCiqQ{4C?#x3;pTc_@mWo8?AzWggZU*7i9A~Qeio7e(-CZNciTpXYUXUfc^xZQ_%CRq`t-bBlLj-$XvBD{kQguS3JA z*72%!4|YN9hmv!GdqJs9+*P1T-nZ*j>vz~+G7a_`a0@4R9U4ZlPYQ_oi=Q}KV9x~C z!1)kk3+|cV<%2uhMRSRQuDGK)|8YL|QQ zb~20%K;6i*!usK30!l59 zt34C#>IJP6y&pQ=V9x}%aDtzqVSHyDvtEY%B@JMI2`9K0uMt=wwT%-$S1;$bo3sY^ zOPDx=={*x(eB`4GqG*w7;#Jr;(E#>La0^6JkMKv)k4D9bNw9BX7{o+Qa4$Z(4C9|a zW5jgWP1P9oOz=3!Yn0ctVN~B+&%zbo)*K^6srEDE{8~NcZ3oj!Z+~iII{S;0&m2ZCF|38WQ~B`%Xdjf|&S`Us@S>&?C6q(;J`j-ZhktB5{8a7#FWv?5}_ z6E%(l$q7u8SK-)1sd1)OXV567i5oz0OE`hFBDO<`QDfPjdKM=zOPko5|$_ zofUdf9k!^@3pBcFVk!{a5>B9oB3KLh2&!H5qTX};L2uCD1h<3}sG$hfcU?|UFF`Nr z(=+Dv0gZ0Dw{Old(&d(L0yPxzBD4dxM^YF;y&b)3te7L)T%8psxFwtjm192CDr&ra zs-?>bOq186I}4?Ts@<Mm+RHPGFk6hC0jG_}HO|!9Z|JIDxbpAKz(W5sWBKV4A#0TaDTSn)nF_ZV4xl zR>bL(s;=IIxWx%NEA*l|^rDX}IYu9D2`5lP5vFi#5Dts2~49GreSo+ z<7#}s7?cE#L2d~rkX8gl23fl>8~6yM$qS-{)bOH@M{r9xfwUrE{-74bc;)4VY4U<- zCy%S%{)r~az}az2IDxbxVE&LAFn?gA_VU6sc|p{c$5n4n)WOBJ}Sfb-~^o&dQly!-VXDJ)PVT|XJ@H_ zmT&?!6v5iuM^Npe7xf-*l_53sDnn|ZC7eJFMReBV<0BX!JTK}cdVI*7RBvZ}7srQZ z2`5m)8&MXwhJ~%TRRhp33 zgOp}xC661%??4>WgwFS02~`eVa;d=yN~4#q1+AfLR}$P3jZhj+hj#-9Pj?pks>5#O zQ8UcX3(qvuj{HgPT&6v#O@p(|hWkG-Gi3Y)X7boks{&?|&Z21Z>khZzy#*pLO}l2{ zZNQRwg1aWS5v^{gcEbtsg0sbIYE!*;_idJXf!neD#m7z7`Of6MYg5cSBj=hw|NVnJ zPCHs*m!4H5u;=~$V(Zb*d=?)8`F{sGf3?SZ;puw+lDuK;P*GvaSRb*2c^w>^Xy)&~ z)O^+y@3-UMm~{!_{;k*Ko0(Wj+Qmxg@~sA%_3kY<*H_yQ#ED$j;=k{jARc}^)#euT zCIbJL_P`oOoy)6|=iDA8O8=JM2`9+Qe^yOPU$>UuFDX7OpIh$hqaD$hFW$qzecCT| zU15IoppV&2z5zP*?+oS}b8Cpv^-A~%?sdG@a`TiJW)8`M?{kj-Dw|!mK?70ZYJMNV zy}D*uY)e!5mT(0ug!Ul`r9MTD+zKmwVAuh z#HVENoKrqIEK+2q+3|6A^UI`t@`*A%|Aaf+nrH?D_ri3C$KCC(B8c>lhN(DGtdGTs z>r1Dbh2vY8uk<`&a~kffXyQ{KxR*}bk;HccdP|LT?OY$x;>INN^w05T`so*KP8-Hi zAiCw)vf*}H*WzB7KJ|0Fogsp#GOE3MbK}Mhw{oTwoG6lgjCmqWadY^oKW$FKerh0a zRQ&=3_rmn?G{x;m;_aLG7P?_nYG1@h%-`4B%r!BK*`dxeo709dSQEK`;9m29$T=~K z9Z4)JTh`4}WO}8ulL9_s?&G%RoW6#+@vr9`P8-G~An>g20KvU5J-e@AM-rt==8(jg zJKOxl#A{DqFn`~) zEYS8`Mu*de(E^BOX&Y5)0|fVK3dH$M%Yu=_b5mY+o@D&C;?d2ce8i12#{*NAj|~j3 znAzbp+*z6QvW(Z~f#6=(ftb8}Y%r2=+Po}x1DrXS;3L|`ZVW8A*fUV7eP)N#@OEY^ zMVtkKd+BsAlIXEE!JXW*jM*{MA98;ZMjG6!^5vH^FQw6_~i&NAwyXuU^a?O|m+ihWCW+LGG?AgRHuz%39oO_Ug%I zGMwR*6@?uhW8mp)o`G)8ZR4zj##Jru#mBs#xMFs9=M??Q%J%nAA8{!67;`&lbYES; z;WR|iHr?E}W^b?#4<2c8FCHcQM8>)8+$Zx+So0su^%3*B50$msd33D9X~TH5;!QVc z^?B=1pCuOe;!(m+oS5I-efq^8)`Wv=e1x0wJ*jc!)fx_`VFi$>w%hzcYVpy?pvAog zjc;upfs)4`ZWu;XnNZgq+U$8z`ST=;d-1s9*SNE}qWftemuQson2)%5zovN(H17TV zx{M_hy9^_3@fi1ht{h_ejw2TL;&FxR8AjDH1>8Nmii(A;FZqZU@0KzTg2vCY+dG_w z_fo$r=)U&T%VK%=ix&6dam7#kec%N*Pv!EW!ngN*MBLPzvUc;f=;UzPFc!wAb|(ib ziu)h_ZE-IiSNz23kN$8DJs&GR*q%agVnem30UVFnCUkQ+Z5YX$b~+EguOWIpNh7$| zic&iyar#j&hsPLrg0*?AbK9;XR(E_sa4#Mu{KVQ!A2}D&HW1@(X7CYP2Yw(m?sVwq zaN016EKGFf6=)=Wx|vaMuO3I<4Wv9(Bk&T$D?j0OukY-g(L{7Cki|zFNL5*COi^sb9`S8Fn!fc<(SvKP}(PKtd!M*k_-4Vb2T8v|)6=I3bwgcyn=Rem23q<_+$V{BVDX zKxNSI6IUxWH{W}!xo8{o6W8B7mb?ozM$Q=MaN01MPCIWpGn$DTNm&K=O3s%rxDSYY zcLszJ*Lq(!XOC_smMzLExR;Z*W$=sPW*{$|m0#n9YgMei@l8e9C0TsLvH0=9??L0n zp?(gh4WrrKNmjRZ4Mm2$83p$m)MZQXTOdYl=p9D5cZXTecWflejm#vt7xauE&1!y) zOZPWeD_YkUJ^G~c5wG066vXzpf4B$sE02bE!xyc!jG1-BiBDe;-0R?l%DxS&r82Nu z@)Kptr4zCFDu_n=ANYtui;GK*O!MDzIBgh(7QHBP{83Vzvu{}3>q^%ulDIgzbr|v7 zfr6rG`l6!QFBdHCRq*>d_6Ardc7k=HU*os2CB(du1w^{mzxs%QXB$e5em^vGI1M`o zPFEFWvt<*Nt{$|w*UdfcB{6PC{V<|?u^3S%e-4r68<;b2WW^#g?F(=P z*+yLt%9>U?mygX#5G4yVFiYjU8{l3S*UXe&RnN+GA|qx!9VIp$e`0?0aI?vYLp45> zUX@E_aySk9GV+Xc^S@oxy0Gn>?<$qA0R3yYj$?jwrtY!CsVb>_t8hLi`e(Hn4Y~=V z??$WKrQsH@6JA$CZcMTp{St5Pn067?-;X==5k1WL)`|SBtu&QBkmr80U0#QKaT;P` zmVshwm+@ALGF2?@#px8wrrUGjI{Ivn6QD6|$WSqN)*IHMQn`H^ysrGjt2sxC%}t6~ zW#fM{xfic#KY`bRpX8Zor*4xVaD7gDYdc+RX8tg`zW2tV-jfV_Yr_e$a01hGToM1Q zZR0d3K0<1cg?pj4-YKm$o&ix`6J+58rs=rSxOC$i=kBS#QiCkq3pMoqZLM(zhHecjtPzL6Sa z;a;er-=WYN4}thz6J+58rs=q@tKuWvQtR4C4YF`A)X;BsXpM$I+*+#$vTy>^bX;kq zX_Mf-n`frHJ4hDpg&ME}-+MzE_F4jQM-yb>1g7!$v&`xZX^)V18aY8;tQ_*~0Y$)B zNkX4hkmt+vGy!qMy$sQT=f%D7xUNG@)CHo#Iz^C$6PTvss;+bkN)57bFVxU|L2LY_ zdWj^+!U;^%aiyXAZUjMIsG)ni9Z8Ud=Zk4Nt_TZ8RAYz^JTLBr$Mx9M8W2a^nwlUB zCooONm4=QCQiCkq3pI3%(Hfi}3nws5$CU=25ylgq7x%*BI#z0pCO}|3;TBF{+D~MG zNIe(gNjO1XcwEPPtx*h!4>ds+o-d~9xGIO9aij)WxEE^Zxl3#4SxpjT;RL4XxYBr} zX3hwLyih~W!CK>~nw=#<7M?Gr>A2F+YlaAdyikMQC5$A_agmsD3 z-~@T;a>%z2Jq?e5Gm#dauhwG(tV=A6Cp<6ig~y@Z@SSR1SFkRzU|k{!vTy>^bX=Vk zw4ep+k_dvlPy_k`zEiC=pqE&%E|COTc)pmX<4Ob8B^JgLo)`DR)8V%ksOngpXmI6+=`9Ab=&4oZU) zWa0T@nvUzUf|U}iOQZ%_xEE?b6qV6I5fDcNtV<+87EWNAjw=G!h`93Od2ug14(%l;`FNP;Y!z%(6K8agsW5afj#I<9C9PLPG?i)lKpH1LdIT_QEe!o5&K$49LJ z>k@(Sgj+a)X+Ht$5)0NP5d?W*PI@-b8n7<0U|k{!vhaK{O~+L^^o$chkQZv``ATc( zSxpjT;rU{kjw=mVm*C79L68?}=viB9z`6uyXGxHS=Zk4Nt~6j>f-8Usg1k_J?r}sC zWa0T@n(l!XSV4s}*X^olo;900~C$YSHq*tt4B-g1VZsA1AG*j(K@65Fe_d((& zoY6KovvZr~ZQ~YB@LgzzVHYjqR_J8O{RW)iUX;c+fZ;8nTM44(YA4w2*R5aU9eH|Z z4Ac0IE$%7eZ@U>rqgNBes-`RLKi9kx$1R+I@5P(FANH|p%Uwu?QjHYv{ZrrBGN@!S zC%BjYExLwZ4in|m4|Ha{UT_>D8b}n-Q_PTnOXoT8Z`)>r%dT*`FN$n)(1nhP7EYS$Hw-yQd#t$bbt@qZ- zoYYQou7QyOORjg1%QPp{-r9d7h}Q3BcxS8p@e3H3f<5h?B^nVbM>K+H^nxAuGN;J) z;Ff4aWP5Oe(&zI4FL{<| zMAW|P5k#XG?JAEt2EDV2Mnsl_=S6AsqTTV4?ZGY4h{*Qf1f|gndW<~V$iB-h(TK>t z%Lz)O7k^v9-{!n8Q5w&LzyAa8ybj6iR!XhjYtU;0xo^7RxI}wTzoll&*S@2#c<3GR zKc>&^&biw}Y`&j4o(PQLoVa#myj^_XBK?~$XWuL24oj>j@ccNzz34d3c7}2B)Ggbo z{=Ot|9fGS1+<{GLe7irf?LhnR-R0)>Sloe~kSU#=1z{eyiv&uXZPu`_n95`F+uMbp1GP;RN6J4tqJ)iLvk-KRZJ`QPwE-I9_sIZ-$W{-Y3F-`z^dJ)bjV$vM0h- zP!Q7)=kfkVuvf{?QcQHRfGS1`T-MPM#IM<6nk2&Un10@LJ0+OKE3<=1eyC7eK7 z5v=4cC+Muui|TOs+7veQ5?xmhp(VK`oInjl{HEKy9FUx#+C?ww3mNvL1r5v_dkJcB zOE`fVifE>LBEG-P3F;;2MSXg1t@NP532q4|P(u+z;hjD_tDT_13F__WWi6HOhU>G! zuPh*eZ_RQ`I1wrb)Rl}pSXZ3DG$BlH!_x?@YMd5>6nk2zZBAp4C%$6nkhjc5*9_Vmw1+N0%=9C*p5BXBQQ-~&@1Kf$oYd?!U?1!=MPR` zn!HF`jaoKG;i#4BXbC5fRs<_KMh1_dvqCSb!^ruATfzy{h@3w-LA8rs)E6S>4{ix3 zP(u+A+vVB^V>>6Pm+1LJmQT$F_yq(U9~j%QzhZCKGk~mJB2YsSFyqJ(g>w`qsJEjR z%sw(Fbyl3n(??u`#`{@|8y0_n*4gA6nk2tI#sg3b!P zs18;1;qwQ#gcGQt2tI#sf@&ANs4qm$AKVg7poSt~r7!!gUg^tvM+@~5OjDm$vjJR9 zNJ3vtNCGY41ZpTEXPcL*^=*@FE8LOty?w^tt|*j#dhCX@#pRo5@C~}z2jw?w!wK&7 zT7yUNWviCcMANrx$nSWE6Wr_h-v*fwy(n$?o+QvmQ1kY6~ zAEo4(C#|beu5v0#a4)Xs*MK^5sYURK8$5Bh;hCM>38>TZ={r2Qm|kkX{JJp`WMMQXKqI^yoX}}Wz|(LWp5MY1 z3lbCS_sy*Q!MCLV|9+%`Ou)*3s0I_7DRh0&bQ8kj%+@w`}C z5|}^chJJ}|?UGeI4YK?T5k-R&IxRJ@p0Hd>BXyl_8!(0Wk_FRIh$tGI&}pfG?TziD zG}biBCL<8$OBSZbi6|PJ&}m6vzr}v0G!BXNo(5T%9w(w`a6+dgfnx^8i|XyuS{Pn? zkOeiO5LzSEjwN2d;)G614cdRF%5nCKcRUTUpav&G&(E=!JSdjW)8GVoY1-SRm+0oI zIoQ*He7${rQ3xmp-p{X=wy>wc37w|e_4f58x;_6+Ex&uN>qlDHnQ$U{dw2xYE~X^` z?eFdDOLVU|o4qzC3)AC76b(-3v?QP(%NU^AqkK#OuN-7SjVMGE4NmB^)PT_?G(-edM(VCv;kB=zTf1(l}J>u~!bVphgrzYwYQ}*VEvHPD>4l zBQk0zjkjB!^ZFH8P$LQvrLH)k(^3QCh>RLaW9{r(o(5S^BMPDCkBxcNFNUBOCv;lQ z2H3xF6sz9;vQx*?APb{8p*3LUlq)9m;)G61LhpJ5jqq8GER5!a)<6#b(2El~EeXC$ zFX{?_^7U2&K5y?q4tI#g?(UFgnqyG>Rkg0u3wrGFV6oU)~X%PpLE zHe!)oYR!jsuK@00saP$O`(meC@m1jKb=<-Uc*Z8rs&z*sE`n#7Vadtuf#d}Df@f@! zD3#$SASz`a=_dYlIljU!^*u|hpWjCuch)8^vsYc4W6x@N+}o+3h~hm*yT9)57A(^* zi_gM|X@4)Z_f4K{!vMK-3X77BfXzd)SpNjWEXn{4c@4__y(ka_LWcYHx#~s_W1tj_T;&{>RG%->A5_%4YlCnt4K6= zhq_amHxI1ZpXejFmtUj9iI(o9TQ!5#s%8@0!Uo+TQg?qB^ILA1Vq<(;kar;@{Uzh{X?gvt?(AR4{kE``h~ z)E-1|OEe~#?&9#0b4xTr-M{)bf@t)DyGBw&-HqY|?@N@%GlBcC z|3dJ)LzG4hI71Wrbkw@?EYXNiU9sBr2+9||_#K^yHkSnU>S#o$&8aj}Nae~t5MR%Yh+k;!85ux^=a&Usu z=mkASmLsz7a!WKKvhQ+&(&)vX2>9!Y_a#c>necn0ihy#snBubxrEz89pK%nUR({+P zjZkZ!e6WkJwP^&&9s2rT2G?- z_%*mC8WAc7ofRi2jb5;uPHL#Nk5Wb23xf2=3PUJR_R*}+F}FIY30p_S#gl`@I_(?1FxKGsrj z3n!o-OAXb6MIY4_^I$ESxF2(6s^2i+jPfff>3gn)-VI@#4vO@pHD; z$7>wVLgm1I1=m+*=*lYvtaF>?D-nG9b4$GP@+_R7dQ;=$*Pga@Okdq`f_uSrq8WPA z0ZQ!*a_u{m?{tz{P+MYZcu0Obiw;=Be@|sg@AEB-}iO}&}wllT|Zzum4 zr2U(C?vzFv#yso0$go)AS)vi4=tB{X=S6Asg4iWOG;^ zfCz4hMyOcATaXi!Mlarv{q4c~5~cA>XjgG){wSPbf$7vwz<0^)F8>RBf;F4E)pUEz z2Q_3GkEgs{I#7M*G9{(pW~Vz_7iJHa8f4*Ks8K!jXMy!k zCTWdDK%CVCSvY}dI<7R%WK6bpH|Zla$ilr)%;RL4XxYEdD z7-Ij1x1__kmpJqkcAVNrsGQE zjq$IGV=-Bz23fclYJAXim+2cszFC z1haACQF*u4FwO!|NE2k?1g7b@(&(~$kZ5vkuGAn4_d<X1PGFjjtFzMWAvMUty--89lh)Af zAqlc@0@HL{XK5FxPF-^x6@iz4KJuz8ao)`DR z<9gg^jov_fsR^=h0@HL{X*5&gTxyVod!dFN|5`(jb4iee6PTvsN<+u12!gy&L&q_# zq2rY#$inl*G#ytOIUw#H-0)TeL0+h#i)lKpG_JvHu%k&IsX-R* zg&KNZ(HcvDII0P`CqTo7HA4hJUb-AXSTlq)Y*;hUSxF1eSL-nX)(j4; z86pTMhxF3z5rj2^)_^sG18W9JKMFed*N|irhqytSTne=W{?C~IDu(8t_a;85d?XmhHe|J0c!?q4@r=P=Zk4Nt~6lH z;KG_Af*>zhKGok$MZlWDg*AgDbRU&hUPQ<;`3P7uxUgmrJTLBr$Msmz8n9+?Va*^3 zvTy>^bX=X49_JARd7*|L^IAiXb4iee=Zk4Nt~7MKiXg}fHFWIK8aiG{f-F2=Ow)0t z0c!>q)(jB@d7*}m!CC{>3=XUrBtaIQFQ)0Z(ttIC18ar|g1k^e&m~#|)(j4;86-g# zo-d~9xYB?%1I~jH1bLx`o)fhOtQj0wGf09gJYP)HaiyW>^9X{xP=oFbC<4|DIG;;` zEIeOK(;WmP62;p7edVrSwCE@k5gBMaDncp2Z%+V07Dmf!5q%t@DBN9<*EdLo6Xb=* zX>=)#lLggoDsEwPkR6wiT3tht2Ia-QFioRbY2bhHk6ZqQup`Ssc`;gES+mnb%t zt}A!9Awd>Kb0UfcCv;j8G#-`4KU*eM#uVmD7N*CEC>os5X-Uv{R2so^Lhc>Je96M} zIH5IiRoUW|oD(`N2^x<|!+GtDR}Qi;Jx)X^2Pbq|68=$JuGG4UR99p{4NlOiU!4{H z7yrot6Z&zjr?|Q5+cCNbcFje96M}I1xpI6FMyk=*Qmu#6&Sa=NxYgl7;DULTe1m zH{L5bCv;j8Fdn`8iHYLi<=LJFSx_Si5v3fQ&}pdwamBlzm?%EKIoIp$WI>H6L=+89 z=(N;;SgG$P;%rbRVV*ZW$buSCh$tGI&}pdwG2gqN7%>}23u;6mqR$^5q4Sk94$N2j zej=7**(&w^2j)u_Oh+N2XmCQOr3Sw{h_mx;xl>l2d*uB@PROeX^<)W0?XG)k>sz`-F5H_ne@gp9u4k?_d4j2+{*>NlOh;v)XLg+kYQ18_z0;UYOp# ze{4}aD?09-mA7Vy;uS!zNCGru-;G9)9@YqH;F+m;UFRh&ytLsO5rixuCv;jKSKd^^ zJTLA=$MFoK6X7*Vw2zSW#m^*Knf{$X3nwV8h>>9(g_U(s*S@yQD_)|SjY{~q-xwzOeyFoGBEz)6og4;IpYk?7GUa>jBz5HkO zyWY9nU+r9$wX1h7o3wL;p7yHewX1KJbYdnZ1g{PrC4bYK_Vr+^5m7Va6w@fO$UeIe zpCUK-@rd*B>m>r2{_NrE{j@fI^^mt9X{aZ>ufLkf-EnqfFy)b!K7xDkwt??i<}c^w z3T_H4o)hmQxEJpWa8`Cn*BqNUP<%{vasG{o=KR?U?Jb#)I!|(qGpjyWY^U9QH0-JV zN;s=^r?v;n9%|_$NCWpa&>5<_I$QUgbLh^4_(tct`Uvjjud6b*Mz|S`O!nT@>KE*> zcCp9t*7UdF`iF11HIL5?w7u}u;^)qL3H3_#q`JqCE#3NUhXhN-s9%?-p2*9=bCTcX z6!=}vQy&c5wo8A*knL}lUs>e)Kn&y8Ju#vhe3!H6yvDJd;9l5cLZh~GVtLW3cdT2# z#i=Ata4+6t3}fDd(xT%O%iY#4KA98Ti}yFfxCZ;R4~2a{5zE27D6Mv2m!208^bJ#f z?t1^WEIFmsmm~KMd09r^1L{{Qz2EKPzm~<{i8YL^#S+bX8EVHjOh^#it5~Ni!QZY; z2@blGiGI&Zzr(xWXkjZUd2DjZeWQE?|FtYm8%DWBHLO>g_ldjz&Pc(%PL0ZFUoP-* zFk@0i$4{(1y4>2(d+xSZ(+~6!{I{<-Z5RdXFSF{_J-zLGqk)2ZJ(*X`u9qP>IB-XL z$4{(oe%%`JS=#uc?K=Ai{!3PzHjLbzPgx_(vB{!oH^IGfrZnwuKmRGX{%KmrPrSZ9 zhp0Awa(sq&oB0U-OIDnQ-wof9PE0@6Kl#d@HwE{4cX$gs?XACpYv-hL{6w}@Wkt8R zg!lq^13rTPk`<>RUd6vG`rddaIdx1O!M!H#?rQIEp3Z)5aSF#zY&dL+#m{oa8~e)m zh||4C+eao9vU}vcZ*$r(z8~LP49qwtu6+vE_e)Lumy;gc{h$5j?rL_=p_gHWyzQm; z#O9j|w%uKDz~Ww)zL{okzuLsUUFM|iC)%YOF4`x59G4-cw~yez)Wm7S_&McJF}vTU zZDU7Hw76ICkssM+@6PtjHxAi;;@4}V#iv`}h)Zsr(noA)Fw6eB_;7pbtB%cS!+7zc zx>MAC>oxq{SNsJq`$qGvHYfCP`PU)_AcADe%L1__u^;hCm!ssBj#S;zODYW zBEI(Ezq`fT2EJ9?qP6Ip{&3t67t#vu#cR}0{MEC)7(B7gwjz~M`Uw8JTbwqG$sJ7b zZOvEY8jjvE(cfH_zxIw%jsGG%v^l)TavkF0=Bo?0aSPE%=;*4yJ6JxsikQ%_lKA$Q zaj~4>Ui_Es;TNHMmKPPr#)_o3wkL55C-`rO8wS2v^AnuejFRtf;}%ZnNUhImdbTp+ ze*-Kr{Lx31Il;a7cl-?FdYJ_A@`_b5TH}=iei0A9vrK9Ht{(q|cK9WaUlPRW>*>wg zt*^v!3n%c)dllddd@svy8&3IPnCNH@ww{|*F_{zGi~puOd^IBL2$AE}c2?n2A8+Fp zPP_=;1KbGT1zaP)hB#LiwUi??!;Zge^9mTQ%cdf!7Jxk&iPLzSK z6rP8#6=suPD*R)2eUa_Q0^(TSg0Y<7UesgMJh%hC?l%#>@`qO<+!BpYbL}%AV#5fu zL?hH&TaCNKieqicir#Zmd3_Wuq=)Hx**`S#UxN!zU@cnW_bTFSqY9$UvO_kvaDwX@ zM#%$lV(Qqe!uoWlFE8%pUY=&+zv0d^(CGMCjCfqRu()u1g~KhJxU_qT`B|o6nmCXm zw>WemwK%yhugeMUm2%J&6aO7wYq;N9@EU<%4TVzog3_;nl5>K4VX5&fRb64t z-h>)X0)ksO!Ryd4%0N9e?R?eB4Ryr{?uDhs(yO{^4@3_jo(F+32n~H(K%Ng`HdVbEw2&782x0mH6v-C^-I_GJ_{!{?|MVhGtOh*-De%M z%9PA0YJX74M{qA*CaA0P`NfQVe_Mx&6>xd1W-_=Y?yEHTy(9}{@CST0ra6Yo8=Uaudt z_UCFO39@j4pCSCFcj=rWDejncb800Y!M%8mz;CSAD<|4_j1%YbthQKSYPEtq=O*Ij>P( z(}t0vOi2spjtUdydo12t(QrLz;}t93rGRT^J9M8R?ZJ9hi|cO&zsNLFa0@5k%3IQf zoZjJ@hmeY~RgESwm-aGd?_ipBP) z%kiD+-{9?sFQ3hf-vVDlxDA-W!MaeLRADJsdg19#~|ixpV~HdmY%LyjyZytoY)_cD(Q75!~zH)hTxSQFF~% zfByhPx*Vn5lZ@0U3f8b6wn;%VgN-vopVhO?yfeDV<8Xc6@T7I;{dvy5 zAKLmX7|&rYk%XQZWZE#U)JU>&Em-Mnuh`K?aIZUY6HNH0HNH%CtsF(yItLcM<#G!r z^twcA4A}9RRj2TFXX89S!M&giCX_{MR5-BGda_`v)2(qwms>cY*AiOejx*OP-s-fo zwSQY5!M&jVaLu4KZpQr2ns{}m^ZuDmF1K((uQ;>@&K*uTf9fwck6Gmd@J-o^>%XZ2MA2PSO>W@?rja--iH;Y`ZWOCWh)b=S zS>XhE;qf02EHdXV`~ox*Pj}nE39|5fF^$J(Ndn7}rdoedbMQK;!3pw0jU8QQo71lu za5X#Q^yQ5ifGDL2vhaK{jmM`-qQ~iO8#_1dEKW_kE;TqoUa0XnFvUz?xFl$dJ>9Kx zZy>g5f-F2=Og{l4tt6(vSv@M+TvT6?UGTiP7ao6>Vx+kvrZH$NJ$awl{+`Q`I1~tYH)(QP$T7;_U6h__y*5x(8vbFVNH;Q=ZopoKrE5Oz|-9} zJ(yltq@Gh(YH)(QP-EA^IP+ZD@t`s3bhnt)GYX4GvlT%Wo-d~N194Uo{{xM#&!rM| zliNxSPLLOBtok*Fndj3PpfL|L`T!v`K^C4brq=Te6J+7}V!8$pwIwkQ%CWo16l?pKAyR`AzxomkQe4e&%6y|*qSYst946oYeDqEyfBjGsJ63`jzo6( zU%lvKtLTHZi$tYR^pO@$U>f2IBkHUk;m!y}ACDj}tX+r_wu(NeQ5}fCG(i@gFQ(}@ z`onx%t-o6}6n$h~+zT}zO4us;Adw!3S3}W9S~!7eKhddiXZN>I^zjJtLJf#9wu(Ne z(GQ6Aq39zmJYP)viQ7e+yRV0$k4KOfYCy!WRrEoP$3WBxMIUM5`C{5nW>aOZ9~z=BghLiAYueV(WgBS zEkn^qT6n&g_7mHROmTLGqK`+A7ivJn2!^81ejs*)qK~xjd@=1OK*J&piay#)Mm1dy z7DYkBA`Oa(oX~oVfV#4%t~fzy-5z>2!1jQ;vZ$^ow)1>3O~=t6)<03^5AKB;G!rSJ zI}kNPy+qD;oWQi7fSxF*?~;Xkp$5&UN`n(*;RL4XxFQO}d~SzEl$`0g7i!STKoRMH z_$f4M<@$pYnD!G8O9aIdvT!fdpf!=wfLJ0ZmXL)Ln5N^3fCwj8gp(^T?u8n-It#^J zh@yf;QEA}>ru{@FSSP*|iqsxKUZ{bq%+UOi3W&y`*+5!&zL@qCCajP%ys1{mWZ_<@ zfve@vJXjZqL7`bqS~!7eKLInRU^AyjkQWkk1z;F@UEho)tw2 zBreCmO2#9|!U;_0fOu73u6-t)zPzahi*TGEFVvuDXBbmp4ObF~4q-8o=ZopN5O?#- zHQWqXUv+}GOY20+i+iC)D7H_7a)0M6CTegNx|y!xu>@#G&=TJ61y>+$N&Wmk7{wZy$pBeaH_ z3FR<==o%Weat+4`Odo@F;tqMu`9iOhn`**3@yoDvBKJZKT4iEgb*pRvQBaR_vTy>^ z4`KCMUf|XC?TXeWxY~9zz)o167x%(6t(?^=y!FX3Hd}?u-Jg8rjl`Kxze=tw*X@H| z*b}_iCB1Vrw9=OZ_rf%ddBb?K%d|~y-cn9+xSG({1|C6Pc(xQVRHQx#1YUn|f_p{o z%-pRBZs7#RtB}T+AJ6M1b~kl9$$qSGB9p%3^0F3GSuOkX_wD$>p`0E{8|Z%1PG(BcOI82=1k8UFKvM z#qNA%VXLH%>!;qRf~z<@UtU^&T}{uvKlnzjn3$S35(M@Jx}xK~g!eK38$6ho-f5kT zX_{r&arqu(qDc4PbGdUl+>6hN{yp3Ecifl13lL85S&e8cb7;4^R+n#pvUI%8$l<*U{BmS!)T|9!`B||UR-;VFp z%3VF7D2nBno^70WR@{r?xzu1+ss6g+1ikZx1ktJ-+jdXzG`JVdC6NSj_=grwz}o}( zjI7?~_;Y zm?k~+_4i$#uYRLSY7ni6Sqn0H<=|d0iXyJn716z8J+H1fq2H*I8bm9iVEU<^2KRz! z;9Yt9iK88xcp9A0Z&XPQqSc5x)O(Vr!Mz}=MO>?^v%>%4AJ!r#^cz)j{vaCt5(UKe z7$UeAU6W%@e&X1HcAKLS`W-B(LA27q|KcC!MSD`^8R~B}U>euEq1kz2R@MIuDFJtOC+J^F1^ag zUbm0ef}GGZgCvMn8htv(N7c}AUJ^vBa^QdQFT5N&&P#%5rJ?*I2_1taLG=HdfHKMZ z{HRSd=AI~CT5s`kcwRbcOASA>`W-9}ki^7_%SOA4byZz zfNB3q|C=EfymD}YM<1dwXIvpa=fx6EP>eziqE%hh&i8IegPptfk|p<- zLh<#>FK5d1bDtOv9;c{e7(Mx|FRtaUAhCQDhKgwbAB`ccD;0cr@nP#lX~S5X=_Bj+v<=*GH#7Ktw{JzM9a7`;qh5}m z=+JV5)gqy`8|anJNAP!vI1Rh*x9zm*e^vb+r{V2^>3>*R)5N-)oD_n4#ZApA+dOZJPL7{w*)Nr_vQ~1BHvh-s1b>%^ z(}r>E)C;0_zVhz13->MV_2S)9_CaX1pJ%ss{KU`~UlK*8lyJAzzvd(OyF{EejBdLN zh&>&Px^1^zvbfjH`!(%zpmFc-*Bw7Gbxv8~S}(cxC!X*T{9PhW8%E%1MKR<+PIvtq z$1LtOXnbq?2x!C~Zs_=lxebH}yr15^cxb1O;BOys+AxZDs4Z%COYNT77qqySoAN!` z9#>wi;rNL~6)OHjGj)Hy7t7{pmdFwZ`IJ^STd}8l6YSI(}m8 zSM9_*1y49%rJLs?4&@$WZ-t~J!CNCcw99}VV7_nm331{A0 zmYd@K^FHEo_EaWn>^0wYI1S@t)Q?W@EtXrXNh-m;nm&EOJilpKuTMG_Y$w+jN@&}jR5HHXuN@%4%~-O`_(ciw()iN(E&WFKQ5PgC3;e(F!#Ph|V0 zqx<0Ox6Z<*(|km&857JT(D*P#X@}ELj$R4w=?xw2^R4omuqrZX9aRK&_;z^Q-To?R zAFg+0O{?qL?`I{rRSGw-U(R_qz`ZW6nJK-ho|P*yM$CLV%DsC0i9PM%W|I?#YJ4cY zDwoRSaN007FC8V)%unUao3Y!sBI`9^hK*w|N0Y1$U!567s&&J~`rqQ5l3kyf+`B7VuRZ&jUX^IKfG9cMBo* z?hc9-EfjYTuEByO6e|Hja7l0}P9a#5cXxPk_aXs`yA+51XZCL1ndGXf`XG%GV-32is@S>h*gWeuH=F&WE829}Rqz{QB&7`R}Vi zTBgYRa98xY^FU*XyhwjrppBBwXNKst=k2|9uElBi`YcAy~WB%Nh`h+rhZ8rEQu@ePyjWMn@DWR)!qRh4U7_$=vXZkpL#)lcs zrheM2uS4b2|EZ)njcfBT%a$ zw1}|2Y7|-@Gsnnx22Ijp+TDOsy}0P9Rcu<{D0ZiS%?8)1RBMI&vDPTp9N?vV(@%+pVl5guiXay9bW2(E=ShgQ+>yIV=>n{KJ| z*ZCuj9+xNR)hdR|^P`t(@4ZgxJU)j#UPi%e7ZWyB7-gjL8e=247JT2}icA6?Sxw)B z%0osO%7+m)f@@)^MxTn-(xt`tC94WncWhlf+6XPt)JAYEOjB=4QsmIp39oaFGvE#Se6*@@ceM&%F{^EgJhkTil5CRNvpN|LB(?oH;z4>Ya_T8KWPVIa{M{m zk#%v1;iD|I5nPL(v?58@e?1`&$~@S3IC7(n;96Mo=zjCGE&lig&nE3BIcuKo#>9M2 z1wrGLYw>e)Bx%aXF>=e2-Hph!PizF&vY*Eicx#?xSk|sa!1=c}f@|?paNzro^-qF& z&+Tla?fl6`a4jC)1D<|79q3%yx}DK}aT+mpsUBR5UtREZrsp$xyVqc2+{8bG4QdnK zR`!!QrIfK&p&8U4`?M%1D z;r%+ys1dCMaS12ped#6p9ayQ2sEl7{7R~>&(izV9$@lnRJSVtT?BAiX|F`AZ#qjUY z=kKHcRI1b;Y~<3%+idWtL;Pxn@9586QszbXHjanv4&V|_@c1=Q-8r9>oKrg+=RdZO z=LFZX$E^7+e_^%CzIvjqYC9*%F_)vY%@e-5V!hyZkoXM~e#K*c^D_yE3jYs*T0~&{ zB8W}3EVp`A`o(zjpj}{cHc-nRb?9E;XXQ-m&c?^VdORn%7LPzBNpDi!R0=$Wh}OaF z6F9-O>=A)_Y-yoiYBt)qT|Lps39iLk8fLf;uaq>2U5!Nz?4{yb_C9Z$daZJ`)legU zR6rmfC0vWs@YV0>oT{TnQ=@E|7zdxvd2iZ#aCh!8#{8xA^c;oz#RtM@Tl;sYb{R%o z#ab)0udpuNfOW|q#_i-Uy|j^H?7ki`$~dxMgl>EdP2dtv!0Mw7hc&8}SfeJr3N!NL z+3rk#Fh>w4xE5T4xN>WFb-}sF<-&~2v1`PWUM@+FFjut^(IKj16!gyAlleDccrXlXf;d;j9T!jsf@@LQygn}O{MqRL{}8A}gz1-zZCk-u12Gz2L&O~V zQqQ{X@C!$AE-rjCEFv+O@foT%u3|j6Q(e`UiuepJ34NW1^pi7_w2}~=BAbXzk?S{4 zV966}{$|X9uJ_X#hau)bCo?{SOTr2Gj$Xs>xJ@D;{~5g#L=ebk#%FL5 zTnoOa)9|Z0Gv7-ejRAmd{EEF`aSP6%1nrB zz$KjEZ74})*A+CH#e7q?L3{>o!@A~WoDF#WB)@eJdd+_dsB0iT1J0Bn745@EV(rm= zG^m$cRMb2}q5t%05ToJKC2xaEIKi(Kh(XsrwQ&YwG*pB544mLvhc}JZazSjIbs{d# z?tfP3{?{HVWgtESeou>~!qLF538=OB-HgxBzMfORGT@`q3*s|y2`6|7CFzuMUM~i* zEb2on3r=t?-Xie4y=$QHy>3OdT7k9VD{u5Da8~2x+H1-XFuaYf$Zuqm>Kvy$Xk@RG%er4OE`gP+!eTe#c?32Eo&51 zslYhnaf5vNj|6G0sTi)+hx^2u-lu>l-1tsH+J@cL;2BTNlEC*7nc(W;Uz4K^eCPRh z(d$6STfZk9o6%j(IOB;RNWuyJ)wd)~?pHTx@7uQOnV-`dJTI*sCA{Aeruv<(EeMiuBD`IQcKY24 z`Dp<5x!SEs(9`#0)vc8ah*A;3wHize*A5R}Cb#$nd$8Z53qjl9j($(RF(Q@$iz(`g z^pk{ zU*W@yk>?iJ2(AV9>YDph-QdXW`rT8V49|42is(Vu--@N;TK0O(>OC!Cg5MA$!5WG9 z&KwD@#als=x>juGtXR02@qK9y8tochIjDuZN{6hyrE~ug-i+2dpYZT}bK|j*)kbhF zyPw!EVsTLH*LFtv1*vTW*Md85&3%4to2L;8L%Ve`T8w-zN&;7{C>7U&yL-)js&3Dh zp3VtvyBURwy|fWr3!Wfo?vs1l4Nh>*zSz@f<9o+Oa4p{dlC-kxhJ+OjyBld|nzIj; zifi$Hf;Wo&gPo@$iWpg=>WZ4<9@<~F-WB$6uWQw^5AbP%cC~IDEv({w7`spR)N`~? zQ^we*)UXj;3)6T_n)e@jSCn>+ZX95oj;Wl4AT56P0?%GYcxw&U*EFt`C}ktK7QcIe zxF0EYC5+1xWW0;7Xd}25A2IMWYJC}JhN8{XR?E$Cg?sC8ETI<7!S-2n_mo4f#IXS1 zI@h?Ka0Z@0W^L6}v=6O)s713HpY0$b5Y)Ut>W0QXs5!sxcpvb-k)$P#wvH?Vvly+n zx4|E)YC<$qC8oupYHrYA0V1(W%bcC=$`Jxu?p}w-$q$wwe zOmTOVqj{d6_0Jw-gpC1?GR`Uf&xH-r;w%+$B%HuB?x)6fbG4Pi+DhcbwJ;}WHwX3;?15W1*%?+aLTLc~ z!6lr)H13YZ{&)4c!unj~#kDXe=zj-}H%a@?`Bk+|61y z6OODNt^U)}oUcd=^Cb_^P83M7)X@Rn{N#W)KRm7)pVfGTHq(2Bee~k_)tbSYcIxCw z=TBYg7?e)is)awF4!TMte(tUgY}SPH;(b1k!K~ z9=oWNz1mw?`&KQFT((DqR<6S@2Bp_Z9!A;78;)<vO^+E5-p{vT=XT6LLe;aXJ z!innZ9ysP4nWG^sN$sD-DBre(7(o|i2XKOG)lj1yJ+CgZh%a6ljNvm|t5_q*SA$Z? zm=~q7gmY^;v`HDqiQgq@LudwLbJNx;yaV6MC7gJWMb>Hz9V?sl*n6O)@ha#iHJ>rn zpA%fG;F^xw<*r>U8zrEf+8@JcbWkd252%Y1^P)7C3fm8Dnl^la$Zio_k{p4wBq=Rh z8?%OHfE3)Zvb-pbT2KcKOKI9@3q((g;F9DB(?+qu@E&z*DPe;Xlt!&NA3JH&vv#&@ z_ycj%BDf?u!nE;bNhu?ALQP?V6O=}+`|liD+~l#Ajcn1SjLsIpCCL${jRqYu7&E)K z7B)CRY1A5>H;?wVUxa0&77%kRf=iMkOdIOri+YiJ=Jmk|N~2c&W;dK057PBf7l^_Z z!6nHNrj6$%qV!B_hl_e}g3_oJ^6zA4vwTaedc0%=mn27+Hp)!()K3JD6E-+OY1B$F zJ~rWD!=;vu$5TA@GZw)m$q}ZFWj@UVXinq=rBTa&!p%j?1qt>fxQyjN*QCp=4BAZ2UNpgf~V{V%$C1$DFADo~xYVmnYk~qO7$q}ZFW-#xT zvgTb*P#U#h9&ydb5GlReIAhNXPyPFemI+up$lHlp6U#2qX6%^+Cnz;Buw|iM38sy5 zPsSQUR(tDJZ@+YM2`3h(T&j6`K83Rmam6`xGR&x(E~ED5+FA!ExK_EfOSL|^Bsg0U ziDEF)eHUL;aK6H807jq#ty3E3D7^k)^vhQooS-yn z;XDFYv1KC^h&~pKYJ17QrRS5vGkDuo9GRX|9}{pfqanH4$Ph{nX#+Sn9Cu_~ohp zslM~IZQGAIajoS(O6E5+w5Va3t<`x~+#n-zb*vt+{Z=5CaDrAivs9&FqzAw{`1|%8 z@tojVv|gD+{#7Fk|A1+F_A*t1C|?|LeC+b803r`h7;fbKIZChd@r{!cT#M|Pt$Q!U z5F>8QX0e`gf@@LQEY)iuhWc?rtvK??Q1Uu!jP|IIuS28< zF4iV&n(Z*XrIBri8C7E!DO%t3fi{9^Rk=M!yR-4WMU*)dVsz^kqvWbKHGmUbi(g%m z6mvGjSf4XST(z9wTJ*bloi7C9{0{_5I6-N%b@TKdZj?(ArQ8p%rt!SE7OrTpo`@L( z-c2kRZ5aETD5D#vl{vw+sNKv`y_;2Ezx-{qF{QR|VB^6>oOOd^#2C#Y{o!2aX?l~i zUYR|Z3D&`5u&Q}JR^vIrwP^J*iOp%IXcI%ijP$ef*=%sFr)^usW!SOQx<335g&Fmm zw21rdaYc>KqI~AWbry06GTSQX?Reu_z!tgJlvFa8aKc{mtog^9+7OlIcjqS-p5pa4p_9lJpOF zOXLoNd*h#G#;L4YOK9cB9Kdbzt+mcup{jg5N#>R<;>k%EgoCjW)Ozry-)X zR>|mEGSFyKtWY4AWQ2V&w>GyFHh50(y#d@!JcpI-ex2g+bO(VpxE813{ou=bM*Ta5 zj4^BT1air@_zBwJUwniOo)f%RgS(=cuonK(F@HQ?S-2Lb;pw^D!Ppm;(iqetYao~K z^@`^tNkd?bTI@efcWyYcm(Tiq6{YpcTn(OX8EJ%tPS8tl_!PjkvVK{jP4wy`)?GW1 zGVM5H)(&sI*76f^Qz!1xLOY65*xwRM0f%T*I#q+EW=(cjpLpktvEQw_?jq5 zL)-K+h6Vnu9N9cJfJ^;2Dq;o)n2zfRi?!#pvI+gs8^cDfpzwMQ|-xeVp*5$Rd6lnnA4x*E-%C zK)&LB2}?q0TwkGnGG6!iJH$f<;wOvXlH>?;b%wT5p{;}sPEZ=PpxtDgzf2nsfT(N{ zT#_7N+UPf-rkWa_fM7j1L21;2{+DqcHf;|ik{n^$D1NWES{~Lyw805VqZV9`GOmlJjRHXYVi8=D9AVnn3w$3L*LTxK79bvg7l5VWlH>@}20ZytAHoxm9|@vS3;Zq_Jq^n z3+|9)^wvxp*@3wI!X&sPIl{C7&q~w<;9a5(PEZ=Pa8^LC)3mV&2&YAGNpgf~qY}(K zmEoBQ+TaAGQ43aQ8Lwi~2HbP1zgPs9BuAJw`rU7>Hk+MZMH`%;G-`Q#87IH`7HHY1 z3wPQRU_P1rtzaCNZ~|r?8LxZO#=X#5>YT-MCsUzlNYDOy9w7!&1YvAQ%>wr(+1p4=ur#D zsDJOdi+2+)2`9kocf#F-Wh2K+Pdzh?#;GAdEdb4 zLmAg8ugeTov&_m6$R+udcaE$*XN%hMoPYo?rVz}FmzL+oy9pWRLbSoPI4wy9BJV4A zF7!~FynhwIC2^Sw%g^pi6*hQIFb{$k19uZ@VE&YNHzDJkjyAX!r{PJ_ux#q=w$0U# zWe~ol#Nq9+)1$ zCH$J;Il*aA;Kjh*gu1Tt{5XCUaV<{c)g3O@KulThAjR%_N?WHe;+|B^+?k0_wKu36 ze2E~*kA!=l4B9AjVX}yYgj$>+E&LsKhMIeXk?8p0fru@F67LI#ovD6LCEk+KTYdaJ zwqh^mf+?v*4Z@8qv;T0FiX^DT3HMulw9)%7Z&#@}L0U-f^u3etEOQ#m2G$z?xCGOj z@V+Z2obx5(WylOysYvo8;ob-EV}Edhw2&_Ietgibie#hztQoGhA_;170!nD@9Qe@& zCrAtFlPSwO7F?v(HS2BGoFrB~M825*v~i|mV;~XDXWtR=WVqxFC<6{(}(-#m+$6JnM|LPjAZO?R26YLP*f{k2!}M<%9FN zt|(5B782*S=haSBr5;=`V~(pHoFFYE+8n8@o!mtIaid?GWNnZZ642__nMhcw!I?g} zT9?}(EhOwS9M%T^P{Ik)!ry6rL_PaV&D)31aMTJ&;GaqDS$ROl{N@ZeS`_wvh;+F# zT2cBPcNm-cNc6w3r7D+jVx+!Y(7l6$8S$Zv_fAf5Eu!r<&{~V1uZu`S1?!}uuNB13 z^$wRyik<5V@0k68y5Yvd@sne@1jdoj!hHX<(loA2V(*S{KTdEh>=$eix&}?6?1kVx zT*3)lw~#Q`LDZ+#6EFJVcD?rlZVt(Cl;n4B28i!L@iC9(P+U9#PAOOE^(0MJZt; z)m3i8r+mg(PH-)Id>^!eHQ%C@@Zl0pR4wEwY^;6BZH)B#J(d$(>%o|OA_CDl!i^uAaq+Qd?`k;-+m;85f2`A(&*&S#j%L{DXIltx> zHu6@jZzH%Cj{yST`-G(e-zwbrw&UndF5$%W3Il|Vpz&y9(LFyuB-S1OXd}25kK80l zffdJ#dX!KcJGq1t{@zQ4jg%SDM*n-MgpJz4J#7Tn;*p!MP4Um{K`!CM?RSrbjf~k% zuP=FmYvqf`FRpVx%ZGCl=#yZ(;~b8D2&Qq(Ku-zNNoQ&<;RL0V&Y~ER5c9$qJ2h9% z7ipY1c|1Za5&oGq=Mql9d@N|3k4=3fnsg}<%L%S!k8)G%(j?Iz$Z`oM>@jO%?iUi{ z>crNTzFfiyJh2q(XRZdL-<=iLV4+Ljt8s#B@rXC@uIRu&J~;a%oRfUHgcEo^E7~wu zgWX+6i&8c1@2tiNu7#(@BH^CfsdXvl(TZ!UOF`?(RQ4~gmx#1!!))JhW5C4qcs87n zAi=eK!j_5O-8N|b-~`v=evrEduRngjgA-hfye0I`V0ZMTC$1R|&fXQ)(Kp~L8DHTf zDQko7)v#3gF17RJ1lQsbs3hsrQXer&`eqqsBe)iiiv{l>+s^^-INZ4UrN52fT0B~p zyXK+g)>PxA;#xc+n47>9C%6`mQ|2a`9_+e{6I_eOLUR*8+TdC|LYte|p-0$ka4jA; z&Lpruh83GsotKJh@tMzU9)dXQ`Jxzb$^OmQ1r>wnLp{7U853Z*GBH|B26qRA1cWsgUO`pFSo zi+i%Bz90sr^x-zR7R-;Lt?V;(3g7>BKn*pVad4gBexg0nf@|3$D90?^xCe=63!CBUENYIk zCD*dYLp~a`cn|jAf`z$l1lO`hH^v&Hjkk%dcXAtC%O2gh+m3R=>$|;W7_POhQgJQr z2SZHqf^AKYY+?rV$Xo>1qFLMC=U6tr%J4OcKNUeexF_rtrj9kE6v#M!amKNp`-wEp zMD$&mN#M!vbq|WT1}+IFFl{Gl!GL zvoq5U7cn4Q60Rj?R4ZbIX#>yaEMO5Bvmd|J=LDwdca!MRsJnX0{Qle};aX^ezOOb3 zJo%jnl5hgk^t(xh)fwEc3T8VIDu*U-L!EZPNU5^UwnD*l5j1w;r==knTtRawFr`M0@L)n zX=8S(G-}xd@rATY!nM$b`zupqB7mrD5hURRrs;Rn#+%P4lzykh7t$^X*FqcauVsKBVpwoVXVNV_Cl3vIZ+`bDNR5V00P5>8;6em8CC12QUWmx?c> zT@tQ^HsGsf@g=iKL<8}MMUaFOn5N%N0{_LCl;_2@tlz~K*~t<@!U-$Q2&jin^`Nh? zxt7&d;>&W=2Gm2RdO({92`4a3zncW~hfe)L60U_dpa;bl@+JZOp;Ld5gcF#i-%SF> zl}_V|BwPz^z(^Ed`kMrdE1kv_NjQON`rRa8v>R-+i@dlN+JGxcM8Yr$xS|YpMF|Nf zFl{HEz-hGE-B+!PAT6{3GlPh{VcIwgL@D>oAS66rOxub2a2jotd-ib=q=hzMh7<8p zOdExO(A_hfknnslZ6`j%X|%Q7v#5(8EwlkMwTOgb+PDQoKle;6Bs^bC+lhXSx*Pkg z^@Ai_3vE!;7}G{aAilU)91%~36PUIWunrou4w8gxp$%9$t!O=H1=c}>)Yn+VFI*&LS_ag*GUThDoSE+;n>YA_f&FFl{FwdXkaR?Pa(K(h_ZD-G!Srz%Ma& zyFD3kf6nv8H2T`+^W9m+*Z86*v+BTfaTb#BeJ-pnWxaiq(F+F~8hSFP6+BfpLR%>} z&k?2uhyUl`5>D)dH-8&KSIUDQuY{9Hn>D`{l;YNS_1Q;5*r2?)7N&PiSs_1OSOjd0 zNEq!1zaFYi9M?%f$uc8G&fa2$u!sK6TsT7*f4}f%nVf&|5FlDM&m>2OjaDo8H5CL& zu!KbL(n`|3bPE!;-5RSdoKq+X!As~a)i1d&Id(r7tbX3RSrDrxEs$TgeJ)Cc9@2C; zJsC??@8x3oX5e2?s&&2}91p#RsI|Io5(G)GBt-BM!s)=p9w&5sG+h1OFfs{2_24Zc zNp-Y>@`GYM)OrIR3S#$*nex;Y-lCEXjs-#8)#hWL z3W6k95+ZmBCFzX(DdAwgeropl$CD6L541ro0(-nVw2_zZYOW4ykX79UlC;?;%Efod zqEsnUj*)dZF&lr6I{dp_|3-NzRq6jGI#LvDruK@-AqbLSNr>Pjl%$^)980LMxP#i_ zZi*xX)dNdKEh0(X23`tEl_yC3C%&S}^Tm?H$A-#TPd64NObc;wmWp%3%Z!*I54xkO zrDv8F1W7o7>HT&4%L%zVLOuQ(;vMAM%2#a=TP+DeT1dn_=_v0E>jy;4Pb(9`!0YQa zuWk~8w6L_tAd1Irabo(bR)5N^zC(%9s)8U1&ll6hw>FV`d>#chmOswthz}~Dj!xMi z2|-#&3|^tg^PIl{aW87VWAW;g>Nf8VqIG*W&oA#JXfFh z30;ajR?mk_SnmH#IER$!}A)Hyf_LG{2=QHwwn!7)AL z-f|J8P_MCq`0HvhNA$QAqEvJOH4>A3hB@BeT?VC^Hm{%KYrl-j?FHimK@uzp5xj&D z%R6CjLh4;zl*s*|NeHS3+MpJJuWQal1%<2#^z8^ca(TX}HR;c_L3f6)6eV<@vEEUh zE3d7RM&96K5+vaSu0DOB~7y0+@x_#^~r*-JHi(ppD!>qvd<_2Ggz)%!2!qNj^Rsd9qn{WFYqBmk^$O{C7OTvr{Mi{N2zb1l5DLh$L;!BFT>~ z9@i^8?JI~TQ`2jELgt84EdXD=0L%Fi+6~_Q1DH9H z2;JbVgG7w6q^9~(OorWY~3MAa1p zNw6eD@DfT=uD{kMY2DJ!$4Y)E#&_{@+w=uz72Pt3F>eI2KHZyg9 zQNq`7H*p45YS;RL309O$R{tig3~-Od$3?O&?K#-3%wbcJi&AM2+j1p%efWFUeKWPF@7_=w0oGba=&?xL;0fCmWeC0Hf@TUK0MqN z;r$N8PYi|~37y9qgTwcUe#ZMHlyCymk4CN3Qg2!X_c-{s^mdqW{(zK(AT1nMm=o@Y zgwqOs_D`5KyMa1oYJRbDl820|8uvxX_k|dAYrn;Bt9?*zdTG3EJ?HBnwiT_^aH3AG ziShHxmoc^$tznyeuq6CCr|Tc$awbG2w7N3Z__J|gTMzP@^S&`_4sQWeOj$J)ca5v+ z?8e&4@4j7hB8_R=UQR)92`A7766Rg1X~nX^;%UP!3!#PQtHIlMk+$u0Qax6yK3u{H z*l{5UJkQNu4^D6`Yd@@Of4g|jC+fi^oPa$V!Ump8XWD=#gX*58Ep~8%YvE38thsGJ zgRsFRoPgaBg0Srh69kuV0``Fj0?*g8*PIhv3-*Bs0#E(>-vrl!eQQpvhi!M8C>57* z0(OoF8+dx5yR9(A39bb@M}!SLQ_)^3PH-*Qe~8dVeU_yf6ou!tEsDCe^439bb@ zj2&phwsTn!T*3+1(JTn_>}AtRxVi{-M{|N}!A@yG*mhtG8(hK(*qJQ|Jh|DlKsDzC z*MhgCg1|2q>;#u^0^X$x0#9!K-vrl!FBfENE8ABPYOX`QeYk`Z@E%v#z>}Lz8`K}1 z;9Br5UD&{LnBkpT@Ktf0XKdbN7rX(N?|^kY+1T3SCFXN@moCGp$}*m+4DX%)`4iUY zaJ5y`WPGCXc z>FI9bafM;FnsY5{2c2x&K_{*cZi8!4y8F#FrQ9|!l^lUu9uveqTjACGZ-Q$z+P6T| zqj~lhPLsf~`;X5rwt8@_NsYz+U3taE6q=jB6fYImQkIEtm*h-`JuCvpZqM$Ic5s4g zwYaxdlxjh(jEwlv2G;_QOb|&uGTw@$H9qZ{QdGh%>(*H{$5MGZtN3z)Yf&pKe4M}t zEEOlX7H?_P!#{KV07Aps``=t$iqbeTfDpfVtQgJQl8$nzcvWS(c*BfaUC%6{$jUYg75jd`<4p@q<>nau3>R)*4ax;aw58mz2O#O@cn>1lQ`6c9*bWZ(S@EC%6{BPe47l7tRT;#qUd!5HgMu z9ItRMBGM((uPFtzNGBa7V8calEhwS*-CYk>a~Hw2pcTaL$+oVG;9Af(;&=BbK^s^j zUMj9dSFn4O;AmerpaAxV%Ldn?S;B3Dt`AOdEq(=?t&2pWcUIc{Db^35HEd~|KX~7` ziN^WT?6&rcCefn)ch90|<6_ht+9@jtu0>~u>4X#C3u-!(Qbj4{mt|%4Pg8kc~-SEt6cU$GD>uoC)*Mj}qg1|GY-9+_$ zXKek!wczVRLEw4Gl2qUGxbXBZjn;g5e{e1M>OzClx@A1A8=m`ItA+de)B>e)+iK3W z;HwKfzgosK#3iZEvO&UUsK2_ptsYzpzPixRFTs<|;mJho{arZP+y1-IRu8Vl@9y0- zpSd)Zjo@0=SFP5!;U;6QAH3#Vi+;C#kt?o2ng^}D`L15$z3DC$rZ~a1Xk~DZU2NTL z1)J^U1lOX~$9{eMXoG9<6%O7zpFAY`{PfqVJ7LGCdx+M8&1p`=S&e2NK1_G)|m8g!yYXFGIhZ1W8bf6L?L!BDbi{3qCLdB_&7;X?&_j zPY2CfCr6ML5(gk|LmzR{29}CNLU2iVzLXTD%Ps=ll4Diuk1 zzL$>eF)fT&>Fq z(n4av$5oDPwVqiue{kZk%LYk!z9L<*m%|lxNX_|uv#aJd!qP$lVsbbzev#R__%Hr( z>s$-d`%1lbEcpY^$HD%%5dE{OR3!P4fLJE7E8>Z*bvZ#=NC$X%%dM8-`8a3;|HVHp z!89j6jSP|(O8MUo#0q|I~UJe_USYbynxbeAeTfhZDGj6Y;x_%i%SbYF(xv@uGQWb$6wYdf%=SG){1>Ah6N> z@*?f>u@gWf0+9&B=x!4lq+)APgYR&AF^`2`6@djU{syY1@O4s0YNBS18-xdYf6=$JLjBaIET}W_b8O?>cWl5`wh01M%H^ns$8CRUlp*X``+y z?xAL_Dm$%y7I#HBVh)vv7HO+*WV6rjK+Okd{;Vu`yxGYmoUq1%Y>um^K)@(b=0l%z zf@@iQBb$A0jVq-yj4LkTgf)6(b6ja)~m{eDfeJpaS11^(IcDVYBkt6AM;QdrO7seYgv6R zn|=Q4oo;Ho64#Ywc>@Ij{VXJ$u*Q{aj;mHMN)jGCP)frn;dyZ_Ym~_5C^-NlaonRg zWl8)DeHVP*xZBUmsf5A(X3%-b=93c%BhbVYy{WB(KBFsds!ZS2Z$rXI;d4A>{A|>*`{*| zC&bLxr@ee*dLj@fqPwbl-mg#&tlw!PxEA(*v{plIF$q_LrKP*7X{SUeefl5OaU}jc zuBM#W=pUVH{RzJ(z9}wy9l}+uXuVEqmrQe%Q>V}9T*3)oun{`3n7lq05;4`fsP$s| zD$!%F*$A$+0c_Ohn^tai0oU52(7Lt04OH^vyrFXmCn|})NiCP~Lt-qnZsn8?Wqj^O zHiBzy1RKRBopj_MhCah_n6IX%b|^dZKGL~_6PTWr=9uIBSv*s33E24dI-PRlzgI~J z(!%SeU&1uUn3Z_a->*PqdYevJExi_36iIl#c&$9?GS!j(6P79)5cP(wk>gT+un}Af zN8-BK85{>%qenKeQD^nt&^7YpZ|}vpA_*sO#I*47a8%ojrAiGpo|n4ec$*H^LY5cT z!tqw4{><`+=An&tK!ldO;W(1^vlv$-;RKGckaRJzBAK<31ivvmQCXhWGF_+8Sspo)_1`{^*e~&1v?>Drl<= zA#1e!&{kZ+32e7iU8g!dM1Pb5V$|z&`u=aPYy{WB(UW`9NoN5uuKGc#!rr9QJ3yav z2`8}s=cPI3G{;p85cyI#bQQ)fC%Be%6=>%55eP)i)DFFH9@l6W5>8;cX~EQ*d3~rr z{C9SM-mkOkigFR8WnImhd7W=6-$iZnx}V;xp6jX=5}vPhJ!Ih>Ygu!p zX3nCWA9heDrO@?1R=H+TA+hE}4QEaqJutUx=GN zwsr)qQG(!FcHifGwO;aPWwh#(qN$EgQt(R@JQ+Q4+hMu+vt{zB%qPX~_$`Qe()gW6 zPvm{Uqtv}A+u04c2@`g`Pe4m#NR-tC^|zf z?{y7qw7Oke(bu$4Umi(gV9hBnu5}xTHM=LtZ!_W9%X6E5ll!j^P;>UEAPD-p_a101 ziykGvyKqa`c7Kr@TYHaO!4afx%5D-Q;RL3)PU|B3<-&83cNMFvJcuc-2JeuC4Nj02 zwsg$?I`V_BczulUdnBJ#rYQ%W3=;%=)hN!8y#!jD)1GrA)_p2U<^C=;V)Z#WT#Zl) z<{d5wl5pY%&`%G|aNHe@b9=xbRY_5^itae>a#;#O!27ULactxbtaw095n@rCD_ zC6Q5bXv9%DPv_-w-Z@8Y*P|qr-;k&j%HKovxcFS-*BvMJ1D#>PQaSNE-a+;QV$t?4 zY6G7-w!F9&zaF7KfQSJi00=JOgbp^cu2>>Z>4evLrHzS7)+O!L7t%Bv!L{tydFRcE zO4#D|>SG|dgcAv1jt@hDJ70LqpHo2(HCv35di7HZlWodDMBGOE}>K8&%&$$c10xJ?9aq z`J!DvspG!Bvk_d&KKp!uQL+t)XFzZXC$Mi$Et)7t{f+C#XCPkp@l$79&R}qYYvFjK zxeJ~FK%aN->!)V9lEL5-PT&|TJ86WxAO`Poy3I~hGQKXY-YS#dMsO|6iRLc&5@}YV zk_w0sWle%4oWOLJb)DqPm+>B_A`pKb&8_})u!69`3DUC9iTR;a-GO*;pn}0AJYTHS z<~+6KntO2;9k?J-8F4D5da;IVBe)ih&>Ra&%b9+A2*k;#M5XxYl&Z&1vcV;sz%ll3 z*;4XXKO~mSOjO>7U00@#YG5O{);fC*0zBk; zFmFoIJE-{;=VoPpP)i%ZwfH;_Poto959phfr$BHCCw7C4QMJ!Fw!g#sk5qFKmAfZG zm4^L0+6b=2R|ZM)oR_E^I~J-u>DSTV5>9AfW8eJg4zH59;uHiMyYuEz>b~k`Be)ih zEBA_15p3+wmq*$2vYQwsB;mwCuyJc(Cdai~Xd@~zQSq$XKpwuQr;XrR|A38lL*|vA z9wMHegN^Xo4dkM`dm3EAiNj!H=c%ajTk<1O3T&LO-9VcKHaNkxupTK_WQIK}NX(d# zs0^#uKznPIiX@ysd#?v(a+>wn2sWnW%cJLhZPuI!u7$1s`p^ugxt`~RdUykI2-=EE zIDze^&!6t}7X8r$Y-BhUsuvw#_8{fOwQ%&TOnc6W9)~0q0UPO0gz9IZ&$)yX*#84+ zpK+SwDihcksBP9aI?Rzsd2uc4D$va9#7wJPFUBYW?ttR;EHN;I;An#Ju?V`Ygx0BX8LgI zqC}xX8pA8BA6{M^US z7z1k*&x>nWYnNtv;X$xQwd?C=6ofU3OE`gbf^|?c*FgR`QTOUBJXTIv>#k<5=V!qKcsjF@@zU)92!d;IzZC9k!ONH**~sYX_A-QD%L&VW z&`iIiKh)gkb_?TK50@t+2(D#$QI@}34eIgzRtuwLHohQ>Gt}BAI%BNpVLe~@eNw;Sy2(E==8ty+W zpZZ^@`7j_ly1iE+;RN;#_`90v?;Zf+qjwLZzS~0<1lPjx=JvwBLd~}VF~{wN3;&!G zIL5#u*U%$}Jw@?QDww5H?vlxG7X;S|Sbs#`^I?T}( z5ZQs?5>D`E{Sf^EY^+{iMcuurqmAHNR{vXmdpD?g)P^eROCY#}6a4LfB;5x>_A9TJ z$u-kPa4qg%L+e7RBC3~H-{+XAa|tK-vwlg+j`bK@LcLgLV-kYiA#nd1&QXN6sy3#C z8V>}Q@O4N3q}dU63(u5!dia4qa7x8J@SN)-h}2oPMt3H}BG?!3Up(5^Yvv#S$r z1lO|WN6T;j2sWMrQ56U-;e_?X%X*u!POGFg-|nH7+4I##a4pP&RXKHzaOE|&ba!Aru z?7{pEltra|Yy{Wh{xzJD8(&FnTC9Pxt(=d+C7i%(p5AguQZcCc?WynNNh|$q1lQvJ zwIo$BDyccc-^s_9`Walp2^?eemP3+4p&pet6_fMd3a}Aei~HBG`xDw~2oMoB0}L+V z1dcI!%K^l`O6r*n#k387+X=44{cCu_0yRIpxtNwO(JU2t^qfF@^p*qeyuilA3GcKo zF=ow);9A_jhOgqm#`B5qG%u@l$)o24wwwF?hd&UH3N_H*moAGixYqSfGo)h->AFIJe z#bbZ!OU}ElC_!*7>uR?A_6<;vRLB3+2VHPowL-!P`}>c1K=^FEp#NFaH8Ti;Ygx0B z<+taCQbljMpf>@6OE_W8E7tpuJy7%eDc|W^7rSOSkr&sp=1R+NZw_M@o&@Nd7rJIq zA>o8IKU(iU3PL?1cX$}b_qt|kL2xZ=m9YHw^H7iJ+dYhG*4$1WJtuICx!;&9gEgvA z*POsyOgh$T_`x}!kK%ALez({njoPyw5+`oqC z7f`APlL{E8E4x-_;n8!#{>EfA5XzVm#);Z44?qxHi~HB`gdV-Vu_cVc^;}+t@aQ>V z`483}mKi{7@GEaz$?5WB1i`f|FUs=U=Rv6s_?9>R1K)>BIDu*RUYsV-R?+LL7y~xD zJTj3N*W&)QB%Os)1#YNf?BD3}`h-W%3B2ardy3A0jqyi(Azp^dvlIl^!ajHV?Ioce zrGOaX_FjcY&j}pI?!8eRz{aQuf1`X)mxn9}u7zXQ?Y9pBq74wKd%L`F;n8yf$FX~l z*XawD)Q%?uj9W(wk>4%|uElqV!T$Evjg=moM;p1b|A)~Ca38z42jKS{_Ira3jlE?b z|1hJ@hUpq7`1=S>OOi#Xj1YU3EG_X4!J@@GJy)qzRw_YQB}qa{(gL{0>9?n+S_bZM zxR%wT;_ijpgJ>ksRs&83sDq%b_--nzt;9VJr(rk$F;CT})30i~(|_3ZUvVvN+eH{i z@V@1JU~k>eZ@a@i)N$qd-C)`kCUyexy*S*zmZYulF15_DzZC=CrE&=;xVJ1xZQ#9g zgXe!JnHdkQ4z z9jhcQt5{A6RO+kIE%VZIAMsum>qKub?8K9@Rpk%8il`@g)D<@9U8?oGOuRou!X4eX zz=)p8mus2T?s8*6kc1P~(?RPkz|PNa98KP(R(GswXCt^4+HglV?*6!ovZeBKrRRzE zwzmNM`M#YfHMOlAz5RqTDYUP!L2r1u7N=oV%jmD9&7~n#3k*1vBE9|kg z<$kp@Dvy61Cv4CgUTj@@l8%Hs^04oq?#i~1_VVn&P(hG{6a0y{BxUOR(t&$-Q~ncX zBe<4j!-_myer$K;`q1{;#eh)T({r>zPr2>HfC07TA+XW`ap zH)ym|UR(=vqA0|$pBk>HZ`U##UEzx2TGkaMo^sm>>#8-_RqKj8O!;ye-k%q$t9*?q zZY+g86I_D53GWKUGi$T~*S{4H*&}?vT==IzqupEAP7YV(VbbC>>~4D|De1=t8pFDm z7i~rHiMbZ0>4`U-ELWwRQb4J1%!2s}t#g93`15Os{Q>>JpBBcAmlK|3QP>GaEL%F2kr#tqoL z!?pNRU_0R#J4oGkBo>~KN)oPQu!mY3@UUDtv8q`+@Hf9cFE{d=rnS0PuAC$_0^%1& z&^~?A!ae(xHi`Ug8td)0j8=ck|HZ+-wywVZh_?5`3i+3p%Y85wt2-+2*`Mm`v+s{q z)q~GPEMJmv0@_epcyNWBrtlSrvDGFnmEL~;Sha3fT|~4cf@`4-cf{U8^Xlon3x}%8 z{?CFS2`6rWjhVTY%N@J4g4u9?Y$|>K;n8ZOQcy&?C4y_A4T>)eGeb~gy->txBgZ9w z8GIZKpDtsBFRK+q8tn~i3-Qm4%wWTNc%+{0@NlC^>kket;RN&`i!S!QSUNrHs}as{F$?>ep>d$vf<*ek|?zmK22 zSU$WO<2uj&*3D=Z{ZM)4WfCOe1g5X8i2Tf3H>WKeS%ir=i?uLSGr~CbY{pTF9P7`iPv`!f!P}CP|0JbTM{q z-=_3vyIBw<;RL4dl^-D2YSR>m!c{vN!C(GTUS?UEgdnY0ASV7Y0X!aGAV$~hZg|$3 zsV|OoQmHg5ReR6+TKX;_qEy)rl+xlRVT{JlFS;0myk_gi^h1Im36_Ki@cOi>g(_%1 z-zNf*=X^)wO4V?^MuD3)f@@)VaIUOckJuSN{1Q=5kIge&?Ny_l7>P9EejJGu8(Wgj zg?Q=l^GB-fS2q&`NjQP&yp3YyPuG@150+l+rT54iqUP8%BMCuTINB+0H9Sx3?$CFC z8m#uaA0-Hq@O&{{tp6hUdany$V@`Z3{n6)v>Z>;P7}#73ZMb7c@10*yU%#l2>Q#2H zut5?|z-*^Y89P`0qNjwm8Uk1CvQmB2#}AL%2(E=TDAKhgeVtZMZ~3ybI<3q-L6GD} z!W}!heYlrC48CjF7?3Ckl5hgk(v+EU_d8xts$KKE^x8SvsdIZuDq80RX<_U>igXQ6 z)usgNBkng>_s&lxBK(nr=L4}kT zM0Qksr0kxg^sZFFo7*Eb8(c&1?kM!ctK*ZAt1dI#{2#I-PpE zxk-?O6PW(qsIa^~1nsS8a01gm&6nh?@8?3Pep@2xEBYQ+R=(_=gdi;}l{=#KzVKlE z*18Q!i70#YZ=Np_6iplF-5PqK_^ryfef@+Dl5hgkflGDA;KECwRQ+MCeOWtFsk|U0 z2|-$D!yVE30j%eTF11!-?++3LNqD|UP&92xYTDCFzt?5BvdW4VP7+RFdO&!HW5EE7 z%q_tvX}zY9()NKp&NkOV8x-SPk`7M_)~|Y|Rd$peDN02WPGGwC`cpya&SFIC4~4+X zn6+R2cZoe-IM+fO6r~$>g+&GG&l;za@68({Y>79^fe#;b+-N6jI+%N(n1^VSl*jE1?z2=#A$x*M+qAw;rSv# z5xXHOFw7-~J8aSt!_88WgcF#q8CK0XKwA!_`U9@0HVFmv8{qTuyto$rPI1H`dTXyp z-FHz-{Yg4AqBTi=Bq(CHBsJ~@t8-{=eeX|ZJxIa{Oncm1?tIx0qklJ!^3qdlGxSoq zLqw@KL0VWUchu~)V}kX_PxJKw{|pcWNqD}P4xfI{IqN;f@?M`Wo&I_BCVkuGfk_C` zLK_sZ8@@MK5~yeU{V%8;+N6xNoKQ#+V zwFpMZv7iU~{%+lb4Nj02+MpQU@D0|;VEuLUH$CD+D?yNi=Zl0pYWBd3HS~;rU-kJD z+6sasoWS&ySCzGv52rw>cEDWHY)lrz^J}vt1ZklSit!De<%mdq^xWLW?jAo0f+Rd& zBq)wJ?0SI}XGZnh#)C}_1wj%{;Oa9Zys`E{!?PgXMtbSf9Hoo`FJ&9Swa^Ad2!=@M zlY{k!K4lD}mY*OEMFN+k?-7A|Vw}V1 z8C6mcB;olY;f@zR82pm`7afL=M{z-rgcF#Kx;9?xoLC1+H3e22uO&Ylkq5k!5Tu3o zQ4~iU2$)MsDNT$k4Kt}+!t=%7DONe0f&p_$mxE1=t?BJi%sGMn+^I>^v~$}_L#ZCa zT#~PIJEKmm6v77O#kJ4|MFp3nJG~?IM_Jk%S^D2rxa3EIVwFQ|_1<23fi0bk!N0u{ z1W7o7>8EdIYrR78l$aMVm*fcOZS*gBED1qcXq)1QLmYbWOWv05Wz^`KAPAE1e9?!m zymXPKRXhjx20Oje=@*;>jSd+$+X$|OHr%ni9g70>W;=%%A7{=G1WA$*t_b6W(zeqF z#0@rT+@ER^mV^_SPBUn!mh0{eD3uPQ>F`ZYtd)9 zyshb_Ak4}AETan$nSsa=cVFfbPGI_xzEoZ{rv=nJClKW_byaW8P(-OHFRq0-(Y+ze zC0i2pN4^z~v3<;g2>T-AkA-Ad6)4UStcY;c0Ka8$bQAUgx`7KjUb*DGAY^TqTHWscl+ zZ3?(PZUM0`u!(x+?1>}?x%t3Ghgpew zj-j>GvCcQb1`%8f=N0$;U``;40`WT#T*3)V-^esk_6_v|8_Of12VYiG!}DcPeYzn%dPONW$~Q^q!7`_Ds%nnn>L1=kgbhxR7TR#%t1SW> zkAjM;J1l}EJYU#ZqdkvnEx)bRA8h;uMDrP*YWs3kg$*LO7OsizJFj6_s+pc@W+1qP z6PR8&+94OKH34j-0isCt&q}!*HIopeg*mzJye2@Y_5m?HyGf9Q=Zk6Q+k&$9#R#yG z0f@*(rYfcQJkBuK&uOm9i4IYKWk0vox&MzCjR<(f}tVS^K-g*M#x zIPJhj8X%fj1W9T&B-jOG<++Ta9fp$+%_$95q8JsG2AvdtrkU zq=h!m<*ssC{CrArzkk=1)UO+tD z9H&pT2$Jx8@mdK;>8ZV27zs9}0pUCbF>BJ*6E=w8T4;lOc!+WX{c#kC6doo)5>8;c zUq~hG$f3z-1Bkz7dKfcG1qd6QAT68|-G2K)Xe+Ns594LY05QXngy)Oti-#L()z^&x z8=gQk%$DCMkiJY3g0#>EdE~H@1BgH%GFk*lc)pm_JoYhh00`@;9mK-?eDz&Nz~*FxXN?I9O{kvJEKem6D?PlhC%z;tMf zg<94AXTbNl3B={z9gS|^LX!}rg*M2Oh5mq2HSE*T@cU{KB;om@Klj`_Mq9IEI@rLP zPk?XL%KPOJHi+O_+z*CX6nZcWh|&IeY#uTvFzqQV*Y3~E1U8N@Pt<3`^fba2bhEwl z;#&ND8~CCpDj6qN`>SuR#L1{dUNL_Mg}=M~U5}HMj6FbXxoQ$5;e`F2*LkpUF>7^I zE#;-~yto#&o7>;51U7~OaTN$I;RL4XtsFc902``bRW)bRR!Iob!koyHh2834V|(?g zYSCsUK@y%XrX5A+%cZZLhSrsUC{(0^`uq6bg$+)S7TO?B7UnA;Mis80W)Cw7lJI=- zz1p3|QS#Dj|ACDUP>-RPOR7!ot`Rnf;97XCxc%Ki*j7MnzOzQ*5>8;c;iw4t(X>2p zMU~Jh8FPyjR4es9l!PEH%!xc%cz)%qWYj5MP~FnYBuK*Z#kBkV;2t0<24`0ryt^-K zaDueZ26?iQv=4}eK-_(65+vdI+TU6}1merx)av2(DOH{q*TVVH?eES6qQ|||>O~;9 zgcF#i_o}cC0`W`4Q{`ZpY)J^x!koyHg}DTX-=;lP=34|wc)pm<{W(C^@`OQuBmnX6 zu;a=>|NO!RCrArzkS7c8&!GpWh8$PcSp-RVzW8Qz?v?yrqnJ zAcAY*+V1vuZ$qhSKU=4S0Kp}kz;xDSUmV8|MS+ctKs@L;K^Zc$ViJP1Femb4C20i^ z37sY=EiHm1JYP(A3XgXbJcUnEYXLE7d^IKIl4`;RCrArzkS7a~xuNF0$5m5uE;b30 z@O&{nSRLpHPZPxIxLfj_SaC?g2~6K_8>$6I*903+!N#fF`Havr z7m^U9g*M#&t^vdH#f;C7{uDNd;9BT2xc%M# zqw74Nt*D(pzBFl4RfZZ2|}=h!iWm7ir!{6;KeQ_ui2rC{?=f1Kw@`>7Ymv z5vd{w7K&1oBLDB?CVOWe{5eO@o|pM#vPm|XoteA23gXiK0%|-6Ucw2w-g$7mm*tZu zpyMKlGeb(MXU~jzgs@UnleJ_Ki34#BM8>mG!j|xQ$wsOC#x(EE6$fFLtOK#XaCtSR zRvoRw5?qRGyO_O8V}1a{$(nVv)n`jMLD${V&h~!)VH9*!!w3$US4pkicvIV=oUl@) zBWCaJf{xoD`fQ34wuIM9cBy}1u2*eMI_S8vyRPP>akaHcE6Fhf})5w{q z)lNNM>{q{Jt&}b@3_Z#nB<;LahW4VFXPH$abtg|6wXyjZ@tojo=QQ3wymS8BTiVML zt*f{^Uyyp#TK)9?VSVKIw#fITRljel$lW8JcljOiwsRUIxIc?((&`O)ddjSLPH-u% z8!@lMEb5cj-cSecr3sA(zmM=6%lng>shvOnBWix}jG%G0mN#8nOP~76X74#pny&5D z)f30Wx?Q<-9+@p6sj+#-x%)0TF0To1^p{$xyJIehwjIiA!b;KeVQuv=u`go_HLSxg zqQchJf~2e+%?Yj#>u$OZs#wWgqTQSChIEkB24u_?+EK*iHQ`&u)0(JPJN_&h%p4oi zk(99Zwc{N6shw)QVv}e(aFix&2`A{FzF_M!oqK>m~bTf4%PbZPB&E-c3D@8R~yA;1mo!&-u8dF#dsD4%x zwuIM9*Ljc;`X@3&9jD;g)~ZFnBI5q-^ZL$h3Ds+D(XftwIh(8eFWq$~x4x@&SZk6K zVI4c0wpT}6YLxX0U`(>iRuBsII`_NBY9;_;ebi`HnWo_wKU{8QP&I+7CB%0wzo>UL_;w<*2U zxufG@OE_U#l}Pu5@560wsm?7Z=B>DW$F@qBP)n?3N!PX}cr|Le?I;?HTr8w<4 zKcw!UuBOlBKNx<*j-alWq%adbny*CLnsB~zuO@1Io~>twpYbw z&-Yi)ny>G}mXH+I507$>iMBQ2bjJcs)Gx2?_p@zT9nz7Mu(lSw=WE)lF8|?oWCKQM z!j^D?uCYFPv_9hdqH)bs%H_xXfrF+#LRcwUMPn9Oet6WT{&UEGGk06PCfX8SFI{8J z_h@HuoS)mbR-erH-v4V|2Yu(ZgzB~SRai%-p3T*W3|IZ5$*So+%Gyz!2W|t2`kcB!&ITvw7&YCdVn)sEH~w-%)ofXVE&Wg+%+3mEtr`1a>;8d@FwPXB1RA zH`~@rQpiKsmIcwaCdX-ue2Io%CRfditkOHAE#XAi${6}^xcI!`F43S>8^uopqVp5z zi~~Ap;kgMN-ScDdF3)MMcnK%!-5lo9f6=ob(pKFj`hT@dyfGzAa4EV6 zx|gVq#iRcx_8nOy9=zU4@e)qZJ&?|*jyiQui6{RzU9{_s6`R$?rKr#B`4$-SUv`M5 z)kcWxr`qTffNV)p!k$)v=lpy`{&At3=sjqd{dK1PBD($^i}{{9{VJtl<|6Kqx9QvJ z|9%#c1%`GLOFED6lS+M(p}O0-)oJ}ZmKgD1c|`8aF-&Z#*ds)kZ~W@-!jle5<2Ssw zBl5zDxruq6UFVaO{nj<_ZuZUtDcr4R`zl6k`XVBajEMLZyABT#{Fk$)uQZJ};V&cdTDLWR z+ty<}Drr7?sJHOpH~MZ5q#Nlyn7J=>)&+8LUQUotFI?#t8ahK0R*H1k6FlfE-LaE4 zKJ6WmFOOR97cLtYBB-zIxgwl~r)XtFKD~XtfAiD6iPS3k9Tfe-N%xiceH5o1XGiV? zxxK(zfBCk}A%aU$O}4cGAsC^5-EE{?x^qLD6DkB+b#2>vu_M+hO>ik{p*;};zKrOd zi{!X-F2!}2J2xj(Jo8+FtXCS@(KANd@o;H8xD==Hn}&4}d1cOOu{+=F5MjnZpGv`L z_}f2^$UPTUh^zgMhX{Ta1gG(v>U;?@L)xXHPVrwt1hwRUqX)Qc;Yi8-NS>njo2 z>%Ar7r*AXrxx}Ro-x;lcS&tQigZ{SfuFt+nW{hovG}Q}ny_mhKc|64Fm~R=d1Ng6 zduxhp$-)HHTfb6TH~F!jeNH>hgGLd#zELTW?6dh=hm|tlq1Wd>goz(8=I{RVyjWNy zOpuNN>5jx_`R*5=)A)K)gNQ6WER7Jumuekc%AV{HCdy*Wd;NUDee2kg5J5WHWgH*h zu-YZ9!_qkC{>_LS)^wMf>FTOb2`6ao#?FFBhbQWl8Kd19rB`VkSi|FK)#p;2cAOmD zBXaA_Zf=(~>mHG^G>xWR=MfqGGa}oa+!9~C#5%3RuKHYxbXXdhXVCHct!`cm=rARE zFQQi2a}$WRdl%lLqW9sk`_P1Gdm{A}r?L8=ui7=;t;MK2D)CNF`9{X%q@-I#9_?;8=A&1k1^-j2rf(dWZw&xc3$2bUrpmc|I;8B9^2fxiULU{WbOkD4~m zpgBX~(&>mSda;XtYrt^byLLzBQl!Ju!CK-M!&*WmcHcIukN!%9StZPg2xh(V*?OgI z1ER4edbB2T8XjS+iC^TO=l_T`kxTKfUxbM`jQNwd=J_Yhx@+qt8mqQv*LJMh`r8@! zMK0F%+V3s#cVKPj^(G}^=U|!r!)N=4wld5Ppij%3DK8ub@xYWJKaIfS>VqzOyMPUj|VNp;vUr@vb|+Nw1lHm_(2E;Zub0I$!bLt00eAZhwX zb#a2vF-w!&Ao1glfACXg^)u^>ITRm0P+TOJ(FKHbyBIzvQ_1g7= zYO*x7WsvN?J9?TRm2j!5uax(?@2RhK#0Z)t$Nsw(j36f(jVj<}YST;;mX7M6|I@#u zI_%0xf44Nr4U((ojkLuzC-xDoOa)adBO*Mjf#id?s zxH++B(ZO0rn8^KGs$e`g5%)vC#O9w4(}bm?I_UrOk6OhE`({diw=~HOk{OD<8|dIt z?+(4U)oCzN>j)DwH=lYeVXYd{VdmQVUEU^`<^pv|JbgL{K)$!JvR>6I69q4Io zi&CpB9VKSuZ5H$umwNursQ6BYhH4#Qf;jp|b#Vf7Oxx7-cT1DpAUWZ3%Al{f)Hj{? z#y9-%W33}h6dLhw&?-*gS<&wXq{GtD_3G!k%K{x-Du+#p$KUt-WIF4gdAF1LK7mA;QKK^*;~x;SCqsr26sO>%?e(05-6?t@F+ zUtGpLo9Yd%!|IC?bE@A8TE&TdPgZyHXRNLXOGgR%Km8-^oUm_n^mj{>+#uPxee~>Q zD&bO<-)-P#Sx`>v2oo*mI>AijMEm!ey8{d5*My~`I_UrOFR2dfiTd4{{%&cK8zcvG zSP?uQTxxE~PVUQ_GHV@Sf;jp|b#VfFyY>Ol-z^=TR|#ik2lv6H%1!R+<~(~}+YB*+ zTIGEEQ?PS#VoaYwZu(!gX~NRfmhepE1neN~JE2xtI@+o{BMSws;!+8(W6dq}iPjM# zNXNeErEw;G^v*c}3s8HCNQb4Pttxb{B)1a-satU)-DjUkp>>1_;^-gM#p|UN)PCQ` z($V|qU1oF8DlSFW85-X%PBq1dWUC{x%-8Gvz4fYT?U2%67a}QZu^RuC{u+_v3>zMi zwMK35+ivWq2`;q|Cjx(3_IO;FNbyZXrhIFif9I9x{ILY-uof#3mPWp4pNNbMU++JB zAx_UYF7-N21b(9Z+mwUAh`)|Rh6I^QFCk4Fk zei}j<9*mg11Ad>=75qP)IU#~{SbK*EOXCbTyg@#*xs+ev{(Mbvsrk85dY`o(t98VP z0~n7q4RiT_{k|YXkPd6_kPb^DUi%(A+rK{H&#J#v6IO}{Ywv`Kr#_Czd83?|%`Qcz2Z?s`iDjJ8WYRrtuCHnxoUpAT!qWI!&#{R7KFM~`WOOJN;!?J620<_?2bZTK3|?Aq){2&}cP-3=^_ z?-U^_lXd%g@xkYP_4-P)`_1O7icm|i%eb^hQ48&!=s25`C&(Z6uN8?smfM{rkg~gF zm}m>{;L85%MPmLqJqEU3(qUUggr(u-%#t_-h6vJO{THOe(vC9=p1UeJ=K0wg zRnP>N!uWeMufjx{>h(mJe{gX*qca`R6YDfhev1~T#D1N-MPV!Sg*FU^wVw{6VgHT+P$6h z#fbKuu{-B~-)(a=x+d~<5IaD;-Er)SiZjDfCdgcaN4ed$uF^UzK|1U^AnCBQts=X;=6Y4>OF%9yY3QU*JI?WAVE;HYG@>%j zT_b9IIZNjh+3#6$DU*eyzom(9x6O;F0UOu*83z17Z!FXj@ApbO%A@T;-m{^-sE$|B zs#DLc_ZvPqs0nD-C7j?HNkOZ8Y89`GOPN;b%qsk%>SRPU?YBx)uQT5g`VNWyGWQVo z)}DpBM{Mpeew*=kL?!0KioW?wmqU#r`ecB>+O*UWHaVoqMQ9t*aFWxKmg3cqe zC8WdZ<1KWY&!10FaYsjs@m-p09kyPQiZ5B)t-I_cts|Bre6V^%joC9vRIA=Z>#!xH z!|LNLM4Yo^g4&j?yO{smV6DT}OHvP>E#ba0;T^5R<_#!xH!|LNL#Claf zLG|qZhC6=_jtn_XYK=S z*Y%o~B-*~RdA)&-M61J=kPfSlw-8zP7>}amzVj-W@xU19dPxdno@mG1<_iaX<=MWn zCFVYKhB0rU<7~vd5-oD#>n+iFW$Ps=%w5mUU7IhAFFIh%cmMa$>tV*+mYDI-8OFSY z!SmtU=fl=ZQg~K8`wYf%gb!ivo^D>+-)-iuEg>CNA8#Ra;5q*~TX%nc_|FHFv6m}fX?l?BvIJ&m~)Nj7u*{tohgmhSayoERm8@pP? zeyjYNW>>TIl9b&=iME-*(1AUw$dP5fG<%dSAt|emw~(IjLHaqTD=M-3IoDzTz6lwE zQKCfLx7Md0w8Roq;`aNG68DCtv!2utk@TL3*1lJDtnzN_Lk@bB>LsFl+##)ldLc^C zeRR1SM6g0c(y<{rdLLtQR|<4+DY{OU?3mVJ^+gH#KmDVYa3bj(Bbwv}sqvqGW+NuS z3@4h1HQi5W9adkIp#Rf9D@D%)T_=53h$gu~s#}jQ107t7uFv#5rFB?+QDRDlOfS+^ z(t49V^F&9-W8mEHY}_DNafl{j&h@ieht(I=LI0%=&?phmyJLgh#{qLJPpIX-x zBZ#Aaq$3HTZ3g>yqDd~iGJxPxaaM=b7bUK2-VyXJCvZ>N_Axp%9VPlqxm=#E%$)~P zMA*KfnjYUOUN3r7+i|%^2EEG(%nWUdk`7BpiPC!> z26xV-=-STRFhLysqq;bO8Ln+=`}f$~oq3>Ypo2@%wS5MyKB_r9f}FsUs^1Mrhoz%L z=02AL9bAg8?OGBhE|n?D*OH)KtT_4|hjdsvs^fqCf{c{lO^Bq3uxnzBK(2vGJk==B z!Ry7!so&K&9o3Qc#FKn&52T2&YrEAKCFuY3kLu#}Vh7M~koNDG#fc5ObUf3RaKfI> zHucJnI5*?!n=R$~(*KBO+6)ePgt=7MUoz>fmaBK@{9A^#O8=$cNTzFRCM{JSF;HIq+XxFl9h?Dhy@rSLmQ_rK>x zxf9=e9)!QUk^H-08nvdZ8*j$hizFVhmk9E-q!p z#*2>mi!wEbm#s! z*c<;*dHp=v2!=gv^=y^em{*xF+Z!C+=RcHF1ur2TmY{1Jv%oi(Uu!8Fp55e&f0sQ% zSSgx4-PShsvTtYu9iR7VCbtgW=KoV{wcsVZUb?n13;6oxwwABmT;Tum#fC=+D@8;s zHgTm$YguQ+Xn)1~dj-wJR|iz{Dt7Ou@7zk+GkHf$qi?HMsog?$Nj=$bx$ltRCA?m` zj%5y{tJq2=uIcQL{qV;}2rFgJ7H)ooz61F@`pUcgzW-t7Q-YW9dg(fr2Qad3OL_WX zoc~YO%a0IN%ACEOIO%Qro@J`nTgtQl#rd_fTo$~9*Gt#2Jb(?*@zk}{ezyD9A0ez1 zJvTVhJ26Fi`YvY|5L>RN_RoRfCA?m`j^zRTfjj@b_hN7S!`qJ#R*L2u&h$)S}XZ=m^@n zxRg12JASgBSNlM$zLr|7xfh)!*@hm}C7ht^Sd^?hW@6|6;>6m_(V55zD`lPnH~M_^ zf{v>XKo|!1x_WRC0=K*1*%o^j;8sj*XZ?uvt$Bq>baBdhc;q}sWEUq>K zXUnF**|G(}4h9Uc0rEyt%a7wM(s{(;d_2qjMV8%^U3w z%H39VU2{bfwuBS-DzKX@|5$JAPkBJ(yHGJ6uwjBF5WoQJJOxL z#{RI$1GmxADk@pKQktMMC%0Fu>)Nv{PcM62w~9{1T=Wrr_xy``o7}N+ajMi)QNosR z!k&tGd3{F^d2`niPkmZY%~|Ja9h{)^IZ4W%+u8cYKoAS6Uv{^MQU09YdTD}AKdses zrfbfxO`N%4rfwCTw%YwY`r34gA&1@G5+|(Y=&cD`!U=p8*!_Ly*u(`1w6@>xD#g<{ z_w{Dhz9E83(S6|b+r(3i>Aa#EktuG^uiD7!H=-j*XBN{)ncj8BU<|0&F|sa=Eb=m1 zeC4K4ZRG8G(Gj#IoUmsk)A+*{9W2ELoTU8B=f0gKx-Kqd=9L?rR~0LsbW>FBC$kr+ zZ)c)Qv)ar=m*y+Aiq3bYrvN8HSIq3ryx32kYuHp1wuBRA=DYN)I8OB;wZ#gYAze%* z3lUt3`s(G)3tV^88N5N>S$_5DoS4;A9dt&82rdUShWa4Eh@ z;GGk_D?y|K!Am%SFGsrNZjScihUA8h-5_4vSY6e4a5F@3sqpHv3$42LRdwZp;3b@( zvH51^5O3opIy-X@h*F&^sm;gJNltJnz7jc3PK;n$5c@&!5>C(@D?YT3ckwEn0s8NR zbK>Xu}yoi^&J$)N@7KkT5KIvEKTPH+tDSMvu{C_5a z*bAcDz?1$vAb1HUzJiVtRnmBIK7AWE9fDe$XxWs z@+yepIkWqJUvCp4xD?H+*p3sym@mqa-CqlWmvG{1=s5HKlZhWXbh1NF5X)-T@&4P` zK16USI&Zzo;E5}1ytxoWIS`jYWZu+X@)Az$f{xQ!#;rVfhjgR|(WOQm_qiklm!j6< zg!cI8&RG}Zk@A%~?q1U>Tfzy_cjNshU67{tLG*+my~=a%47)ay5Pj*VZa_w#qr zs{7fqi$v4AwuBSZZ~n9~@uT#3G{ku9J=jlNHX~>WE=99v;S-1BXTjodoOeL{2;!od zCANeUH2&Rc9Ev}y=hfly=R_TUrKpX$%j@D&<|%Na&qq$^sOzm1ono_HmvF+&V>kMI zm}gMXGsx@WQs!xPqtCf{1_eEXyo3|xd32-CIX#2*zD+I@Vk?8Li%XeR$&Id8ILAa> z{wBFB8e4sI2`9|D;zrl25+Ek+%_h^wRya*?DYNdnQOj}$hzN+(Ab1HU%=+j?*WC|6 zh#N)ay<*X|9qX>Hi%U^WIHBDo+ZX2*ftYx`s9YY~4Ri@7=oWHr*D(t~6I_bhrN~P5 za>CdTZb5CAv_h-0oqbDIj#)CA;8HY0aW=iNcV9tY{e0#vnGFOl;RMYw*jH}UzIqYF zzFAG>UoneJ*Tto{?Td&BT9tQpQ~5&7>eF^KCyYJk`r1z14x;+nRu`p(ZYx|rN zG{>^HobQrFj+1-0oD==9u0QdWYwdPTa4CFK*2SswI?{ww+4q;0Ek;*XjXG{~jg&`q zkvC#cwNG_)!RYg%cKb&l-U89T!#089|6Chq#T2>WW(L6+ODKq}YZZ8btTM*Yl@Dfh&=m26~Anv|cQvLn( zxDdgm%se)BdkGLurIP9v2wuVo?(0W(8;IH;6;f`k<&O|HhQRG>e32By6Ce)MTrPMC zuQwbw7zkqduw3eV+1(+6OVK#R?DmQv?tr)nf|qcDM<8(a0Eo72o>tE-J{Kamlvy8* z-M#`u5fGynofEu-6UO7^MLk}rz0z{W+BE9+ru!j+OHobMB1eX4BIeb)G%BqjYzZff zAI?NGR)NTt;-=qr=97}w#igi6Vs?89wCYN-n|?nKyo3|RYp7!u`uq=B<;$b~_xW>% z2rfl4G-kKs>-ci+s-yla5WIvFJj$U@+K}7!t?|1ZEf6BO6t}PO)gkC8w116X9Rx4o z1dnncq6lK&t}*_&Q6)nJm*V!d{tmsY0pi@ql9HEjf=4+V=Nxn-&r`>LuNY2>MW5Jr z04~MtYkiV{+?KnJzXJp>;RHSNvG@ngt13fodI#rM3K3k2+t>P={j%xso8EUIcnK$H zj@c*&zFP|&JysO(I-aQ#BDfT{uN`L~?!57r1-#T}t4LnL37TUz%7I862=QeB_X2cq zf=hAx8ecX7(Qst}_p)h~wdgrP`fQZLab|$HGW4eV!h-0XTY^h*``U3XfY=1$lIdM* z(Q|_O&BiPorw53#dFqHmW&|z4rMP{KC>eTpLGC)DmYF5iqUS_7{^3DKgI!}pCd^%4 z7nkDpHQpdWECn$*HrusD&xvsSV-bik``3tuu_sCsT*^Gn#%{;SCo%=g};8JFnFn0TQAcldsv@zHXbO|SDj=e8> znuy7l*l`NAd0LK%?Kqm?Qf9X^c6+zz9wqC?b~RnX2_6^0uK__^7?w-^8{0WG!KJu; z?KmHTSP$Y*YC&=tz{609N~9^s&$@oD^~tk zj$Ae-8W}MJk4JDCza@(jiV@!AZhP|^DIG&Fw2tWotx~L2nlLT#5|H)8Y52(Sj?;5f zdzB0CI9$r~sD6716GhQisSj3B{m@rDo67W+e#hZ7e0}?}$c8Q6P!GRZ63V~gQe1aH zNFw;y@-Yba?y8$@WrKG6{a?;?uvuZj@2G7q4!5rz$3-l4?w+6grHG~S5)*ONzmVqE zGJZ3PxbstgF7eMI?rhdUZPyZE^JL5#Y;4g!$i=yJbAd>{WP@&%jZPC`>PbTuzne;_V!vXa?OAJW!sEzQzc*P&xPCj``HL?P_TqHkN99Z#q^$ zI=-I$l6St;Q24Jp^lLB9{g^?;yRU1)mT-dZFBSzTIrFdhCO1>6-JdlH5nPINEI#wJ zmvhMk=ooRSm3XD>pMIAEO|3ssM-;e!KTKTh*VtXW_JBXWUuUhuMtHdtr{Q&ern1=b zwCDf*UMK72^vGk%{rg1Qnh-@EQ^TE8E4_cWTA?%f!bcBm zD}L+I)LU1jpC)VxC%BIs-!;f{9T7aoIey{e5W%I4j<~3fX3*jHXzFf&4lYGHtd~1X zWExt-{j^qkaX5A#@f7vuQk=#rir99!5{1M)#I|_}_m~rn9?>-+*Wi_7?u2%u#5bj) z@pJTIJVo5O6sH|0SKHs*8kt9nCwB!gdQEUC?(xQ3YWB)v@Y9|+jS-}Jtqv~5{nyAt zj?NOnW{K9prKl#%L^nDUpZc|xkY)cA?JyI02`9`vHokB(+ohfDwk|G3HQ~8&qfgYS zzU{@OA2UdaCyGm%CrbOQ!-RQiC3|XJ%BJ8_oW@xx$eH+aZb7*bITO5uM$`JNiN^D< zYjT{gKi=-%srHf_`FD`X;Zi0Cm*TYJyl}%2O9s3o7q=~``wFX!Cb$$`$9&lM|@2`d%$Y+w6AuZhyGiI(6}RFlo6fbSJKEXNkVCA%Vrg-da7c9<}0yR>V& z&9b1ev3_GBkkz9zBOK>8vUfI&PLOwyy~Cxr7dTANGyYP?kL83NVN2$ZhX2!Na}0c9 zaSN=-U20N_42(R-PF5yWVSU36~-ru`wqm0%CF;?@=AM$LEu&rv>}DexA7$>4>d9#QX~)l_6{iC+OP#J*wlq6sctOt-*e- zS28X|I_%09CE9?fWe8is3A(m_j}mX)J0RZuHoBkN5-vqL?3y1Xs)A@@2wTDly0(9h z5_|HG7TX8+(c@uDxD@G#?P|nqXM`=`1YO&|M|I4Oq!-gZ4QvLzLvkt70n5Pb=frTr zmT-cu?cbw1qW>SH@57dGDWk*KB{3!-bO|TSH6zd}-`)pwa6(_3zDkT{(2)*KpiguO zua~av-=l5Xm4CEv$HSIzDbj&)(%E}a;%i3O5>C*y{d<(Cckh7TC^k!UU0jNEV7?h! zl$cr|8pmd$F5v`Shl%znQmLA;*&Yy9ige(KGB!2oAfiU>iP9y!Ub+qw560(H$zo4! zKv*f#ftA7JS(1*wKs*^+8FUG+m#)JERv%^8D_g>)NC#Fpo#ROw^m-K#wuBROZT}u6 zZWe5)>cv)3T^E-k9ayPN7ArCTfOsXgQtJ{<&~=#TQMax7JhmGIgq0#4*jLQE8tG^Y z;&g1s(IvcIx(*ZA2bJ9iZ3&km9X1n~G~hH$M%WTg(6#-0l#rkISAWNLXZ_B}rASBY zEtQz+AiS6bpuHTNpzAOJD?>3WBOt7lu{gXEhrImJR#gG90(J>6;q}rrygS~49~Tt~ z2uXw~aoe6=T*MICM&VXXlz_FQn6;#RGW>42ZhTkm;cy>kpZVtOGmo^>*n1&K@&-oPFk-v(JJOPT;&S59fP%(KEwv_L+~f&wO+CSwL_poN(sRf5F*j zKF&V#&Dm!`2`6wynMeNxXP@~v`^-0Ip9KV$qI zv(J2-ede39&jNx=QUBqDGou4%pZPfZ%r|GB1tm!d>O0d{KctkIE{^h-t*LKMOVf27 zPCe7DUbTuh@wMdo@4LD_@BRFIa(u;NPeNw7{?Z)(c<&mDOI19-z)jXG$76^lBZ|mt z2RHcBiX?#Nn#P2nK^*;l_rOy9vg6o$}^BBVG(n{Vh|Chh_ z(t3{*e|H(}_Ro>s``k&RIE~*&t!XNs%Xd=jUoqM5(r&z)ed=>=*PN+TfrRO9uqQBrxhpl3-3}fS+cMAdxm3H|liixPZ^qMogo&DOwwFJuMPfbf zgA?DCoa^p6xJB#WG`vwD+JNW`f=j*La;Dp|>PD?2OblJnRepY?y*QqP=v97!JK<)6 z*1>65F(6ihs0V^eovb_8oszAK))6LlkLfNa-n#9U`{&aTK_2c670<{0ks+1hwBvl> z^pJ(`CKK^TX8By|;gET5)^gv*QD21#)vlMEJE5}Me%bU8LG*J!yK#prrc#{7j&{0% z99wXjDCRv3^={ARbKM_4OzzV2!TZp0n*Z29wk$qPT;2W9=Tch7(OvN=MkXb`t@xrm zH*u(#SG0&qN*rFB!#z+g`kX&!XncS7^gWTj-y3QQ<`vB;%q@@R70n~e4v*&2XN{}4 zOL7j^&x+$*E}l%5?o?0Z&oa;FQq_-FaMkyp=-D17nzl|U=WlGR=HK4sapFOR>~8UP zqxEd(G`?E5^=WzJU{$poW4^syeYf}9-F3a=TfF5qZTf+3NthS};)!pnDwD7nR@D74#0%8UTE|qmjRkv)LF^?hcjJYg^Zbp_j zRya=lceSJ2JL?F&igFrz?YPUL3yANqigKybUF*0n^_u)RBEwgr#oFKeDTxh2ggIMO zuk)OScQb2InW0=6H5q-Cvrb2Mbdx5!caLW3=Fa)1rS4tc>yGnhmZDODcsCW+L?*@i zElezWDyMAQKd+ib>n81OM(|CJqmqJbjaR9x`rFc(=iErb-5y^}F;Kz4t5F*Uksk(PL?Krz8 zA%kOCF4YjdyY<9JZs~hfb?;`II@m3Eu%_-^-s|v@fk?SLm#T!`U*DH7ZECt`TXJPASyV344`pxvw@fPZsUe+(Jogy$n2?(ivO0T z@HxSy9(YsS;^R-nQ%(5ANZqtDam?Fl83=B@T*~OWReOB&7)z$r+yg>=c*(E1vaUUE zTi*w7dwBnNSg^3%uuQ6*@1+abK3vC`OfB8X|FqEhuz#rMr1+(_npJ$G$9G|F?{FGl zd~bMBw4b)$zg6{hd)~Hg72nmu>+ZqYRpqX+g;np)7d^gO@|J8K_K|z>X1r-t_d(TU zmiG#(-aV6ttPD=@nh;;PU0Ochx3U_(W{b!7JAO}`#+mme?~1FrR`?^|s26&#fhCckcG}5BJC&dJpGo7d=spb{t9E+&l$l;@guPng6Zz z{+$kWLIhvoIPExVueFe0AA8CFW8D?~#$xN@>j&xhclo%))IcK{)Zw)hdehS2myc7H(&fgy2aX7(i!gp&o zbdke;*zTY1zdc0op5`>(Sn_t2XRTp!96FJ|`t zdNplm-Q{in^|epkWCPc4jgH{i4gKZ3(v|#7A8z;fO3mBOY2>iX?J3K=b}oMC#<{vx zcID)2aQF>!$=3s9la>vtjK$pLQoJR8olo7$gEz!QTh*i1Ksou)Y;VoQ^&Tg93pwpL z8M=KaYkr$qbg%oL$KQB)y=R}9?Ov}i+^mWFihLvwM^cL_buM_ky`11RInJp?17-Ri zzr_z5ygx+n7IGTCjLD7VC9k?TF#le(ugv=^joOA6I>t{Qo-)b1bC+su<*S>TiCT5O z(}b1c9)$4Q_RMBIWxG@p#6GOM+@HYjHoO}&N&G;bnVTRQtli>qg5NEt9cOj^iZV@^ zC8Fm0c~$XmX1NX07j-{gkUaFRzQ5`e_p1weU2iWv=i^T0l?O_!7H^#_r=N5C7SG@A zc}@5&a)AVyy591$#@IH_tE{e*X6O>N{lOT)#uu|4~YAmVEgp1CG!;AExwr$ z_GNIIw-CGYAJ51kaiheW-@mNygLZz}^=Sm{J%#V%%RM*5?bT8(LaX?DIQ0$mc+@}K zV}b8}-1%9=%@*n=TEz+ehRtcmNjc=W*jcfty4(%#o$M{1#s#hMXl%m7$->)3&XNVy zvh*cF1h-x|jm)zP>%{dD=~TDFFDq{Ea4AkZ&ZckQk|lTa^FK~v?{aIBugCbE*TELD z?}7aO)#X?9Y`1GTmkL{b&$VnTuh+}&uit$pL~tn@8@pCI&Zz&|NO?J#7{2I2=!w$L zpz*5lr^|6VsYQN0cnEL7LWYkrk>(SB%J>Vd8^l zGWhBKz?l;`jfNBMmsu0(?lWFZsW|O8V~Zv8`}a?f*=fBRPBZx3kgZ&&cQ z`^MiMNa5M=XqJ->uFrAcZ&&cQd&b`$5TpZ^(^lhe4`}UgSMay{#@`DL2re}&!vt7?&wDgW!o-|UnyNzwj`*~;bAr!4PUBq- z#7GcVL2#*qlg4-x2IlZ+%)>;hAKR;Pn@{Nw&GG0Y;W$AtPFfdfUU3@Pp9ePh`LL3f#RzgKigD7)_9#*K^CLbYm#PlNgA)|v zq;-+TgVV4wK0D&4#7cS!1ec;1C#`Ic5}6R=%!_q#0mg$96yv1zi^hY~j`KQ*%phn@ zGW7_-iw@Qaks4PwQb&?=LwDdXrZS*CWVjd|wnEwVX>jsjs1fypMP% z)b)}N4)0R>nmm!Ph4ek)guLfQ`4vF?3xZ3L4-WQ^mI@O+v%cVWnif%ql81>YC-NuO z{rXeynYK?TPUF0yRb~7ii$&D3BlCSO^>VTzWC3_7PNYmid_N|g_f_s*a$@OOKHtO7 z^*y%*g!_41(*68IlXHm)>w3y7rRVxw3SPUH=*@_FH*5h6*wQvWSNc9OYn5>!;`YUP zairtlLa7v|@pYJkNBp6mG?mxUSMCyGlGmdA^rCAcTub#vcdlUrioLq|Ab75jK z){#+vz9Qo=6FEU^71j`!W;>@b=2)xBgNT6OQnX5A{dx?MV*g_Q;p`H!6rLzf(5i{G zP+KybM&xJYLtoaZFX!Su;1}}{snmCl_XH2IO?~IQNASC%5fA+dATq%g2f!bH8T zm;F))LdCpP4qR8;{BF{$nceq=&LZ%*MOjmAo4nLRU!H+P4qP&5PkCyebv3oX&rr4h`ve_ zeGR1ec!UW=UlpRS(nMba0)Ar;(O2EOoYv7-h3Km^(bqtVk4Kn5^wmf7RhZ~&K$yHP z-MgID(N~4&t2EJ957AfMyNJGdh`#FHg>O0Nbsc?Gh`ve_eGR1ec!UW=UlpRS(nMba z0?{`Q(O2EOoYv7-h3G5Jgw)a3K#Gq?m_YPZA^Ivz^fe$5uk#Rn)xFDU9eq`Zz6uk4 z4W#&Zgb74neMDb{iM|E|<}GER>E7kEj=m~HU!{q@2JblhT@8Nmpx1TuRU!H+P4qQ* z^Wx(XCJ=p9h`tIFeGLfy&dF&VeN~9Q3KM+|-XQsSgb74n6{4@gL|+4fzdLhUM_(19 zufjxMgEwJ59$^B}S0B+=VWO`A!F!j}I{K;*eHAA9>cRerr(K_H9au2&v^$62AQ634 zh`tIFeGR1eyKI<1^i?7HDope>AmGRM5PglO-I>!m`l=9p6(;%`Nbz^_FoEc+LiAOb z=xac5KLe+A^i?7HDope>xO1}jVADO)3p)C$5PcOU`Wi@)#RuC>_Z9Cq9eq`Zz6uk4 z4G8$cJw#u%4o>Unt3vcunCNRD1s|D*=&RNdCJ=p9h`zce`Wg_h-#oI!Xf!#kqp$e- z%y8F4Ujr$!DiM8+Gtt*TA6Dw*eH5avaVGj2BJ7(mr}3SljQLe%*bV()0q{3P{zgZ+ zMYK=R`wo7o_hf$cJnV)}u&=ljWjWFQN3$eMbUqlbhQt0zh82zz{Ed#&j&uG%yebC! zCpq%rxD;iY(LPSIJxoliQ(tw3RrUZj94GiYAg3KC0mMBJ--F;%l&41a2#rUWXyr9h zBd4cQnf858)^YG=`e4goFQI;U{l>y+oNSG(vwpCD$U>$(HQI@(UdmIW9h2@OOe7++ z?MD#*fZ$TRC1K)uWSu?pL27jiy~_#8Q==V|#)H%F4uY5m8>=4(F2#E^Oe9Cv*`2YM z{n8k7PEej2?Xfg7IPEy=L3{v0VP0`5J~P5ZmUX}R=b!w_?}%JAPM9^(BWsD%j&lTA zXKAt)RnyT|l&3~JG4(FxsnL!}y~}$Yu_6$2KuFl_T#ENwnAqMgugd;(PL&HYkrR}s zMmr|;E~jCOB2TR~Y^?8)hs>pTzlDkCk#)ALT?*x*cR4|MYP82v?{eC43aYfK8i+0E zT`tA@ElkuZ`h))mET;CzRpW%QmUQoO8oy3J*4bN=s;K7ZUCL9VotS!;^3-U@q~7Jd z4zC(A+kODi2ffRsc)x{-(a1WRm7H zjqfcX>+D|Y+Nv*lmwP|Bw}tmQK6H!Bw#8{`tJ5I36z{h%QK|M_{|{J9MKE_c!M#SD z#ycnS)HZ{V=v^+w`z=iLI(FR8T`ZS+8okR2?)~C4{0zsB`|Dt1{f6GwZX8M z?%_G-1m&rb#YA(L)A#~E^3-~R7=Yg8Qrue?CT1c}Emx*8y019FeTbZPoQ^O5;4iD+ zK{m{O!$TI5&UT`BKlj7D_{F8f$%v~(^8hY(IORV(w7tB7U5yjmf5B;dDFl1qTV5mi z?13=B-{LuqH?RNFsQHKAmLp~-qui*VRa2_PdqdL?&@JIKzIpcQU4L1NVg8*0Z);yT zqN5(gg!v9YmJE4vX=lJ!>mJ}Y3mw1k`~LfCh~QQYryb{s_%JF8ZG+YgD2!Dw2Bkl!@_C&x@N{0|Mzz@ z$|A{Xhlre`pV#^-;Ws#(M(_Sr$$z%+r{g@h{)(UT z-@aps=jVSnPa zsrdcS$pJD`1Kp~C;8JK|JiMwdc~$Xs%AM2Pk$ZZ`6=~-AT#EZF!^E97y}VkV3_#wt z<8%KfZ&j)T&n6Za9Br-R^d0|O;^dtJ<$-HT$AfIdmFwd)`l|k${zc@N%$EQ7m7n`m zM|G2@PpNpcmq(ZJHTEwG`Mol=m1_r_4iP6yb<=d*z%UJacTt@G;V1p%-hL^39{c5O zuPWyxwm&gb_cZ*Xero^MEg#9g4>su7nT<~KUf{IjBuBh!8-8cqvti@U2Vr}{>Pac%X!o9`JCYW#`WPozMSLV@w>~J z7(pIc=XV=kua>S%@ZUQ4fvkRigN|$3*gx+#PUEbUU%&L%p3E)R-l(AXQ^eaIexkDV z8SE!itR%OuEF2>EJ#iXm542z5Z%&gSzr3n+EDA9xm#igzPvQGO7ORgeR$;PO^|MWD z244-hr_gbbFX|&-RG55G`o*DMWw=z><8`-MA*DX7D&H-cmhwddzad|Db1!c09dF&r z%&Vf_bE@6>+Ojz!)tum~GpBXFsE>S6Ve&--?-2LHg*`?276_GhcM-W1y8-u}@s`xy z*x$?5M4DFhxL;b;__(r+N2@r&TgYjh{pln7Q<&_}AOnJXShzo!AMPrNy_r36X%buO=onL;@ zWY8h|Qz83PnC#CWV}tu-Xum?vWqgqRsgV6CO!j9$a1RTo9jAMn9%^OZ8R9U;gJNpd zx5Qg=@g|ou@R1O0eJ76d*06% zLh?_&3XOj^S(6WY^;hehN}>qHoDanVBqS0-2c# znVG)H%nYP>Mhee>fq!>(Z}n7UkY9u>8J6k7+x|`GY2NC!`^-2%z^jd=78}=?I zcuonY9j9Nu&T4PVul+U{51wnl>*aX|_oW}Q%`!-P(dL~mI zW+L}3@p`$R2^lFl{`1FU5BU(kf}kF?mN2(*x$nerCgQgS`LTzzjsD&s_{BPx3i|+V zzgbHapP5_jN2|DBgtsL9y^h|Qm2Z2|w~0~HYpWNAJf~j5^T7%3v*NVl9Gtq}Z~n$b z{d)ucM#nu9;dkejMP5)P`c+m_F&^BXz*|!B{wvUuS#HE@waMTFV9p!?qIe;>YsYmRaJ~RC%8UN!|R-Tg@3xlT|W`OP~aIU zychWUF201&_=oW@zE`Iq{?G>xdrrP7Apws}j!Zxhw8Zueit z9`YUfioc)pd*Za?OfOr}cXPK=PrQ7|=k4XW7zJB)*Z0w&Fa1KHMBEHN_oeEp?vAHI z`4^lH-^Zy*6Z}_~_EK%TZK4Q3kW<227`~6AALj8dcWtKjox0=md=K6d-a>pCuikjq z8{b2U!}E!V$CK+)h6sPJ;qNDJYQeD6X8>%TUt z>g8nqC(+F1V8@|)ZGIx(eUJmWJd-*D%Woj^miTkWy?Ffjcbpa5`}wE7eM?aclFvBq zH44v?9fLZGiA~>ElcrDhQ>WP&U%t#t{cHPwu5FHgvDX~^EBuS!bdDeK{9OHa^zO$U z#e5LkL2xPWhe&+3KJy<#G&%jYc(YtHRjBIK5b?{a+v2zGSfF$0ISt?I6OF`7oRGKW z)-|6?;q8v*u}5#kVWRY(?ZxK>URTBb&Y(Df_b5%!+a#xvzx&QHF)&wicxoqyz97J} z`Nu538J}|2WOL^`-##V|g7_GB&ZQ>)_HTTBf11AYFfpmbF0bwk%^Uia0MG2_G@_P^R*F&}eg?s%y8QEm zd(vB|e{T>bQskQ~nitQZntf0;MBp9QrSTw75vTE$smaMjif4POvFIy4Qj41(iQDwQ zg^!sfc|oKBF$V;fdh@Su;vT#)Pme)(CeAvZ+jX<{R>ziw3FNK4M6IIiHcsPhg2QLF4QFU{EjYVrFQLLNwX(l*08sHMW=v7pg7@1vUo z)Dju?S#qh6|I*npXn{9Y^-|-OP4u}GAM-F#c*CD=$~w(ejed9OcN2QWq2FWhdCZ>z zoJ8|dZ?{A9-YWC{@nPcq)s!{q(Jw7Hjb8~(?&UsMH$bf{a?9g$l;1i0aPja!n!c*M z^|$zXcLu85HCBZPeovgnuJ%D*(d6%T>Z@_b$)6akwXg>CHTe_6_c3QroH)9+pQ`ZW zJ&!+~ye06F#lxRyT2l}K49C~ST=xIE(2NG{7F1%?j#Zr+& zum2w8&#ZTDa7ksWH>#BKn}e?4!txv z^Z@}o(S?6edxtr#bLa(f=%vY_52Wx`9$c-Zm!o^%eqKn}e$IrM=PWm3U**HU2u zIrIWK^wQ+e2Lyk|;k3@77s#QPCWk(V3Gp|iFtNAq8*;#zd*VcrZ=UflIv|I|MYfQ+ zkJmcYli%X|ROj){GcEmWrBHu@6#KX7X z!auF+MZSlNd>`GCFoAp@iF_Yv@_hm+-jXnZd>@H?A8GP^0s{FSF7kc!Z0EGj_mRl= zktW|KkV5{Ai;S(u5XkqD$oCN@-zOm89dZ$2&`&L=b-s^8zK<~ZK7kaxQ7$4Hk0Frn zBarVSOukP*z#HYl1ESXzPV0OhiF_Yv@_k&q!|L8ezK4r^AKkmW*LA*+M81zS`96UZ zACEABd>@H?A8GP^0s{FSF7kbJUvXOJ`$**bNR#gqNb&Iq6Ug_G$oG*Z-zOm8<#G`z z(S5~fo$n)&?;}mVPaws|BTOLQM>qqQ!UXbt1oC~P$@d8ezH@R~ z=lclc`$&`T6YPV$r^5vDeFXA-q{;UQ2yOvzTIc%+8sC?~`yldt1oC~P$@dBNJH8`_3FP|-`yoy4N04Q~_gcQU<105K zYl@cT`pNgU-w$PSaH$k`7RC3eWpfSw7VpTkL(|By>VD|!Nonp4aIZgjNn07=Ju3ak zbTS{lZ7>?&H6R<2zHLC+JNzpS;k6z4J_7kZ!sPn|1ecmZj3uZb&mSCjvoE+AKJeuCm3!G6x~{HLjH+^+4K>R!Nj{8U>m z{oix4&gIQI+HNfX-anky@ehIchmN1~8O~Sg@LDn`TXET>PrRIPBL&4jf)$y!WXIDl zyY-HIU|Q8{SY`Qb@-nhy!wve^Eq3SR_rz%(n-GXi2oswKEPdWW{>)=M24<4?uQ!yp z|NA{;i}IFmyAHML86=HWBPH=14an{@~D0h~wE^lYu6(V>qaN2R^ zF1{cJ{N6_1yPkp~CV?HzTar`UjL+15lIbf%Oavk((nL&xcNzXXB8EV3-fj>v5r~-h zCSnp0{Hf)%<9M?ci;S5Pq=$J$(ROQv^Ol64!5?pK7Xwdpk(DumoZ$DwX&o^Uh?qzd zF$vns?P$a)^xuPsi9p0enutkY-SfK*-^VxOCWtl*d&!hnHtXL^*f$8?!ti|{Vj>VR zktSlIwbPq0ZwYT9-n>>z*%04*xsPwXaJ!a&PbT~Yn&h*Ey!g-0Vkf@!!U=A%avG;W zRm4|M@x7P4`1TH$;_FqIC|k0i>{VpDXqUc3h~TRar*#xSAPOK&6d>3Q_#PF$^GfR@ za@+3pg1)j&C#3BxG{=3j`Klr-Zya&!RvP7IXnec4{ri^OyL`Msf~aK(E@iJtDoj*c zA5jxygh%x**|d1QTlt{3ANuNFn_nKZ{`)4aqb`UBAgb)`x|Wx40y?~}K}U&O`y0t# zh11BS_rY7j&%T3Y38Gn%D8Wk}M?~*Dk_w-x*9b&UL-3Nv5m6l# zyT2|zKG0w5;Do&7y$N9VXl$K$8(vZ#aR&N;!Q_NCeHO<6F{=s;hoULd9% z&9|PHa0312O#l(qQFVVKH4P(J?&!jDoZwP?#^8%`AgY1*_DH_a?BhguUZpuVa14<_MTJd5^YE&1Aus0$g^`ya16p2$l$LDzq;8sSZeBjV)Hh`KmujlXZ@ zEH5cxrReX!oSNztd-6LF3Oep)STDvyN7A(fEpe$OMu!{HAxH-=G5R!NbhuF+@?=D{ z?6*qntuy}-0xi)}RMVHahq&eA4xv?s@EM`+&`5bC6~2#Ne@9fooL~5jTP4@+MO|8o zh!?7T;3Z3TOcTTMj`POGeGeUtyGB&^!^`|FO&{pKvL(D;t`GZp+647Qp4oouJ7u*F zTQ5naS8cpC-A`y8Uk?4myPfSMbiDFTMD^-7->+Bfg-{9Uu=;olkq7X6g4%j?v_Gj! zbFIVHOH%PAYkOyUp3*hd8{FA@cGwx{I9xrVy6&0ezf`?RsDyObmhcwh{K1k5>aSM;&+3{Am4D4U_x{h&k*Qon{he&E{{a6{y|#p||BtP+fUY80 z8t@Q2%i zxwoMv`S%>&nU|`stF^jjrh2Zb39TV~xy3U`&hFYs(E?%A9L$^2fH1 z&62vUscz3br-U{R4TJs!R;T#X>E3;hGg0ZowF^68TImW};S4{Plk~rI8)`ZsZ z$Gp_HqT-1WK!qggs zS;-vh!#Q_#HFuQ+Z76%RhMKk+)_Ifs!}TENI#=bQ7OZ)ud(=2+)NVGYK+bkU=o zYfwqhhO$R%=C78osDfs$A4k z`x4UNwV7l8K;Ir39Iq?it|X|X?9m!JcAS2H{h_NJN9}#ITx#z}%%GE)!Hn*Zpu02P zGdQBYyB%AIUR%b?mA`zpJEK=KvT#P3=JhU!WVZ#c;tkgyg>@d^u!-pLaJ<}e$`>A7$=xR$Ln0}?=yD)Lmgy-tC8*X;uyJJiO5Wl(j7yrwHWFJ)1j{<|6Q>eN z+y)!b`QmxPUnhZhu{*u^`|xSF){9$AMTiJVs1EJlYu0_k*2ED1q&}KW-Hp^#}IVr=pp~Z>vL$E43x3 z1l7V?Et;~DE&Ux^J~%u;c8a|#hSWb~Mj0yd+P&ulKmL3XFa7Y0>0N(DeOJHsmNl0= z7Gn!L2qmEeUSC_kl<(b)eYH4qH~FZnCi8unWQqEy7W~pUU)pRrU)>)^Fd?RoTy}k( z$O->&E~))|Cum*1*^XcKb?nY+Z`ZVPAwA`W?c2nRPMb|aNhpEW_bU(K_KJ7FMuwW* z<&po6irT*}PeUlJT|i9n3+K<|4Is8c?sRMs)g4<`Es!6W*9RB zhBOk}3yzlKz5UIZsAgR1nRrt!cL9iH^Baj7iw4L;l@bM&&~o8deEIZ{xqR*zjH$2f zNH20!7$8eMI%XlL7M9dyN*woXbQy^06B>zHuY1Ub74MsblB6cizl`Q}W?lutYf2%} zSDdUmI6<0{)$>T5G0yT-&DWSCR?~@Kk@VfgjZl5|nP~>~m zR%Tt0-XxTSmJ7eV%_mo!$~PG|fw)sBv-nW1jf}8mw-8ioJJ>jvYYHE92??J?UZQN3 zMzZM>H%TR_iK4rLdGu9`^lP~Ki2qQcqF|CE!=C`IkI8-?|40+uTB8;{5EgL7vtYf@)z& zJI+_(F}BA*d zt_VLKfyB#YUSgd7P~39sX%b38%SED#hbynO;|UN+8U00YvlKC7UJsK{5=!8;?|cpN zQ}K@F;(Sen4?ZFKyy~BZP+Dl?Vewb?RlAY+qg$ZZvFQ&nY|cQFP!d`$5{qvhv;Pu@ zcN3@1`-o5bwu%$`2bqMDPy(;LmJ9p2^+;sQm08#t#fXpvBhwH{3vJ9gy~-Zb_&E^& zj*bxrFLe|<9u6}JC86aaam0O;eaICgCIl7|@jXV1KcNfUJscx(q3>M5=X-e zi8||wi`S2W(-2AvZM3;k+Fn?H0mPsgfg&k)CNa6vSd&l^S}tDq-*`HCPa7mM|C(7G ziao&REe%OSC@r)R{KvZFsv$`Hx4}z5mK8rccY;YM2`v{1_w6#V?;IrZrt=p$KEQWx zvyV3kC7}dfFKk)F`{Yn0{^#mS zl!TUxMCN?UwOByM&sB;v-^*DKd^v_nZKf!A4X z#oM<3jzpozLZSkX(%a{E%w0+-Ews_F-%;Dj#W>p=^bZtyKF!ysJ{)4!N=azBcs(id zzOCa;T!Tw;WEP3zHtEBz3{68QEwr&<#|zsYj>Mp7FY#phQN2i^ekP$Lv|J<}PRq&? zlF^qmD&Q{~q#V~jT@Nq`C7}df*JQa_vD`?Uf?2Z0nU7gLmicwzy zx6I<@`0U32zBoKJC6pH0c;ce7-)`b=uyAOM*g7}AQ83Wgw4o%lT->8J6l}@Hx4=DW z`M5%&MD6@W=S|JbJxWO^fxFM}NiEp$+DPo1Q%D@Jl{b#QWEO&Ip^a1Bx-qYK+&Qm@ z28!UC6^+vM>zIU+Py(-S&F#msyWa(3Pk#7HLHnAABrG+*|U7O6V{*BSnu7QD~f!@*>)HIt(CRRHedm3neieJ86YmnRI#5?YhbcTCex> zve`mVExi92aC0$xz7p?0(#Lp-VY}g%TxUD(Sd=6Uv1=K-Qw{HNo@MbDm6L*uj}K>< z_a6hC5=!88#$n6Z<>#k?@L#Hl-B-sN3CFvoA(R%@>fy5$Y~k)xKs3MRBLcK>M!&jc z1-(C~_vBU^K7#_q)h=U<=Cz6lDxrkc#+$7v;=Xr)Y`yQH`3yik7ui4N7;iTqp8q@Y zm|4=#XBp8zWV8iH-^7O;Z72yP@cM7DoHss*cl4p#QpAN{dday_x}_|tg(azbL)g!^ zr--#cbc}WoNXhYo_YTBqRDG*t9m5)a` z2qmEeUSBW0klQ_QUKIu6QMwLtaMDK81|^gh&dQ&6kdvWSU4i(RxKU6EEf=qE>T$eh zTfFC-4K^-#wUqbHolHY0Ei6gh>A@X65chyM<0O=XmMg$U_4ZM`YHM8Qh2v60$Kmy4 z3;P?>h9amI`jwyegVSSDME()=WG((iPzfdQ`ewE%{Kl{7;W9_1h^?>Oi9=+)wk7`d*6X@e3<3vH-7BzRv7ef3-OGa`?ZP!d|M9c--7zS|>DVYKwu z+!V3sZoFuk)X}t|2&#oP)cua8eVLykI1oD%9fXol0FfLbjihb9Kw5pL(o^r z#~5alX(njTI`Xt{WO@o+OX;q85}QGQ;EXqlsku_a5zG=$PZ8!94) z^J*}6BXbrp`ebzwNwK&FvN<0xZr==jHE>%MquZVQrVUCcEwrKHYxvz)=&Rp> z_;A}nC82kK;kc&cJAu;IYW;2pe5=!88aJz+UOg@Z#o`H=V1G*Wj zzXqovlor}hku01O2BJO?*S|OjC86bFJolpTGIskKM#$(BXTIuf{9dPkX+sfIi^jol zQV(qS1JTQ)fF(kv1YYOT;#sLF$H7L|mEc8}^)>t#^tQb7qFVHQo2HdGRZXs1;~`_N zCUMkKQ89f7g@6AU@9sHSO=el^A>EyXl2C%a&4RBj0MQ_4ZMmX+AwkQcTG($t(r2)T6IW6C@m~WMY7PlU?Z`14e9A5l!TUx*S1pg zdF^cGofq0DSw)@>jWBIcLTRB570JShT(BWaRFO@?9E6h4a`C;|-4?TX^CB1_R{^5Y z<#Mw0y|tzdMNlnVD?j613BQZP!d|M^{wSNXve*K8Khem7fH*aTIe5t#=A?CtI5m{GRRR~T_lxI0YT@4g zGu}M|#3>;906`^`!0Q|;4He14S7^b;>`-@cd5MEi5?U@^2N^@{ z?e1Vi<_R|Ziyq^p$9R}FD512_hKgk2#Nj^pMtsR*{5$;SHkHtF@p`1k@#OWRFtRKP zM7BP2?Yjzjr6H6SmZTzC_>QosCOi7gwNK6OAe4lbi`U+-3VN5AjW!sJhv$KbEW>zD z(*`A!7TWk3@AiRO`SOYE_yh-`B(z+-ZnUJjZG!pqJQn)OWol0S#?soR4N532w4owd z$n1ylcr-1izF@h7P!d`$US}G(%yzRgjzHw+w9tl%WZ^j+^wsEV zJ@gL|4nj$2xp=){^=;eTUvOTHhIYKNEztjLUCFdT38jT=@MpaH3lLM-0{tTpR6@(e z>z~;P=b;_KzE3~zS~3lxw6G)<$-=kvz{Ut5syhiKq2=QB&zuQQuo3q8rhe~SKGOyz zlor}hk*ub@0~_Z)-qeH7ItV49<)U9vSsj|@3dD)%FS^I!ET#=bP%X5fB3Vcuhw(TO z`9=Txkb_VXO5inz(_t?cVT2q9?MRBqW`vf1Cumtz3w{32csCAe^>{`$V`8~?=8mHz zl)&qUor78NHW(ql0^+ZHZpQO77t#<)3vK+2cOOEn_U3mpPMmcRNLM6Hvhjb2Z-n>G|dwJ>J*8SmmuTy&zeG5_&)GXhW&O5pXOQ!(t_ON<$CKmRbf zvT^NJWEw(gp$!$uf=`56m7ZGJ@VMh3l!TUxF^Wf<`E0-we1?1(y=eKG#-K(`O&f}! zS{U2?jCXM#>|U;>(W60AGwM?kO5pX7tV>u;J4VP=fLOeuj*)TiJ2MuggwjGAKjYoO z&&Uc%@YHZh85K?K$fZaSby0tgCZE_ z2+~^7JVMBzlbz)I;#rK{-PWsGnFOsnrQtWEd5ZAe*H@P5?a67rAoi$=`tkllJtK#R z>{2y(|FoyvJ_9lw94B1N7Sg&?8s4Rz$R$VjY$LnPTWqHU)uOf`_Oa)ZtD3bjQa)#~ zj0bIp^^T?SoUXF%{r|+F2vx>a&T1EQUS1NlC+A+AV47qwy6gg7N%p+40)KZ!K zv?RzjeAH7`jl3_O2G%qQrG@K5#p+gKaQ5!(sK=zw|_e< znzid_v4L9ZEC4M@(>xaV%eR5|#PtPH78|Jv6<=%G>l*>G)TRV+YT`_jP!dYuwaO5L z%>Hd%b73DPPSr6s`| zMYnFUkk=<3*z=QVLq(I6u-YiuwXdw*{Q$4+dD~(GwNz$5(yAnwyLJ8L@{6(j{oD)^ zB`TVvT9k(8q96Lo*8v*u*$3VqkaF=_W%kpO;P=()caaa>TH6a3u-ZsXs3;Sj4rU6F z+0JKR)k-?XLrEy%wCy}^@F1y&%(J*6EA{S!s+B3hnyAPUuT@E!cKcp;S$*a~#&do! zdsoGVl(5>^3K_p|>mOnbV;mz$&orpB2S}@u;H&bt{pFc0#q|nJznV5wY)G}xhN2;d zB}nk@biPuXki8tG! zB&enG^pRF2!5jC|{!(jkLKpkCS!|>xRICNRJ+Qs6tp9ztzHuVFcZRZ*gc5kIa`xeV z(AHIU*?3v+6E-gmp|sG8{*1`#z3MIh{cu(vS*(xg6P1LPi`VLm0LFSz$l!~J$VYQL9R$n<|<0ZX7ui_RPsHM&x;Etn8 zf?w6`LZVufhVz43p!{Rg4L!1qRQc`Zc|O!qClruYB|#=f_Ac_w zW*6f`xviW^C}E8<{&}2ZuV=q7x%z*R{CVp{JcVnX!ldUL@b8}*ujD&co`8s~=)qO2 zL7p(_Iq|!lN+>~3E@;}hUe~;Txg9FMzmuj7RTkC4Jb<5P8Wy}6Z`*%8SRNkN-ONr< zS>9;x(ut+KPnL7$-&MXiWZgH+##V%lmxJrHvPdXFYYTbE!3&a~-42oAQN_~`s)p8D z9W8XpmgRAfESuoSz{@G>4f} zq;j*d-0$fo@ZsxjnR zYn98bY4s|(d4FwROHSM6o`z6bNT|$g$k?j9I=O93NjYU+!!(4_!de|%;>BxJ!uM*$ z+HYs$zEzMHGZ`kKB(z+-R=M1e0TJwG`_H?m^mA#NhEQ6VrS~(-dq~y!w!CXyHW;CmCDT4v}w(s*+x7(DVFbX5K2M`yjE?} zw5mZLk^{>;5nfOFn6;vW(!yG)9)UBwyDGAo{bNOGXRfo#j>dB5Z<=Di0&l00P?_1V zq7En6dKQ``P7NPp+E5Zo&>F%!$ig3z^OoEy#w0s(YbilnuJXk-ZDr#C=B<|$4fjoXtO1ivtAr82YOONDO-+VTwiMSNV~$U{~VO3)gDzZ#d6TyJ+zG5>%yXPata z%T-R8oCeoUy+-j#iZ>%Bws#X5E%%fCB{)_t$!jxdSiok1?XRT=s zTMhJ%|MtNac{eSgw2)9))0*}%u%@kT;o`bmileVo=CZRLHZ_7OYZ~sO;7xkBj=$({ zMmhRQNho1$$F5oM6V8+Sj{9CJ!QFZ^iJ&suHzeVr{|#~6M2bw>`p%3Q{BVa#o6 zwyPXy_*LDM4D8RGv-EL29rH>_C_!ro^J?g++9}0MvxLPcYm~8^$0wZanab{ z=TGQso;lZ`Gp8BLh4sOdXHYrNnl^9IJ=>Q@C-p%I4nj#NL2C%JoWO5nB1XoeGql~#IBd}SEZ`c^d8 zIVF@95-Ot^&Y$;bY1^`)t+D+-YgRGV1R@!RkqikWRo*dq+s}a`M#f*I@p<0eMRGu}A;Q!zp!R{a<+t@8; zoTzeyv0R9d8AixRsQhGj+n4W}t$V5A#uoT3H!7h7ts(p#Oa5=k#@_>tx4|dV5VYm0 zN8mKaGlSia3N{k_dYH9R*~3^a#MBJ$ATWAW`N?n!;%vMv>*Ddo#paHrvk+8^o_&U=A8oyo-R3lvg(Dm@QANl& z!)YuEv(k)~HO;+gWT_uWB*X6ozQ=%eGuEBc2sy{@@D!zd*zBoR4E^e_dy$U zovZb)Y2zQvPOg3>#OT|)gk=P2%jwwQP7cojre#QitOH}|jaA-0SEJeJ@D}o~L#vak zUV&_WxW2MzxGmHBS!^s^L-x)#?}Vh*J|;mWl&Il4!hZJ6EEZxCFfa)z-k%fE1|_Ig z)6GY0i;Zb)f=Qgecs!xsl^sdnzK0o9LWxo-N9=jwi?Op!BC^Dlgs;zEnKmdvwOaXP zVH4K{voMn=-1kjF?fliuc2Ef=8g$OW*Uk@SD^0>)?nc7J5|>OHl%QH|11hm2d;74d zCb78DwuCXaT|BVmR6>dW##iF@HGP~mj#P|KIN2}3v_T1~<(0Du>r%D}i!^O`de%?4 zaA-^&v_U15@F~-TN91VYv{ClRfQ0=?%S;=Tpjy?|_F?-bRAO^Y8&ewI-OHApsEszL zgc8m6^x@O{RC3zL?)H4|AHBj&8pA!^NXM7%yPB7CCn=-p+w^j)A$+RBes`e zINLXLZRJ_{$tVw;iIkvP3IEJuTeFUE+VK9AJPB=7 z{3p@lbej(52vUM-J--yq#vWSj?P$lOPyh3HRd}1ncd$Vvl*n;An%C{K%KM0EaO&T{ztC9FN7{Jg#nUkc91^5=y*#KZ_R%A7PI&ZG27n;^FU}&m40~ zP_1eDG^TAj;xZZS|7((Vpu}jmQx8O zu+_Nktpv855>yL%mSIn%C8&fFIC>kvpI8ZOIVGqT`VsH}{|`YWlt>4&5N42*n3)i` zSM?Pos22JW@Byi8V9Tk561bXRB{+%aiOJxl@xMtHf@+~30Uwac1`nVK8_vLoa?JeYxHIe+ULc{IRfz2^yII@aI zbPBaM`z_2uP_1CU82-=XzmhKnAQ8WJ7jIr}Q1T%cD?zn_?!@o~f4=e>ZxZv)+c~!T z=HH#+MqOiKQY@8c3@o%BW!CeiPp1&_36(WN^Qqo6L0VQVHSdF-8vG(7rXrJb;2Y9#9p)Ib3cVz2&$#V z$+WF458lRO-EGPHvO8?x2%>}%r)$RWBlj*QpEYe1zO;&`jB8+TR@F*St(z+&`RITk z`%RNb`11x^Q`=omw%0UkrEE~GhMA`F*gDJYb`5&OoU{19_#f>nT6erwy^ea54E$gG zFSVAMl~&@4=LF-_;CkYNVYiJs5yM^IcV@L0d=pbw#_+86E-XIun|OXXj_=*olHJaR zC&Lo%jyG&?8|tk#Rbx~uV&Po=Ca@j5|LImLqIk~VT#gC)t>7_?YQ+tl$8TNf#Ady?nTmK3+|_8E&PDE99dDzAhn&T)RtjQw zk9`)DhBKqT4>IQWJ1)k~&d#XTsjqYRvFm+V^Qh~o2$w)Nqx0M5^6HttyeM(y<4pc0 zY&e^{=CzGfi^FwwV@``${z`hX&ABxh(;||4x9QA!*ZC$q|BK~? zPB8ZG-tRDivls4T54T?x^$rCZRIB8MNFLC<3maS@HLjdEBDNLoWg%+h_u@@^ z$FkqDX_C_Lv^K*l{otI}V*E+Npjri=FkbL$EIYsJyRZ^9=6V@!VO5RT{L|RI4dHyu z?r`2F_Ooa-HJn$84CjM-d=U-n%;I@nhVxR}KErtQ)M^-s#cCNnho-Y=6+bnL*UB2i z|2+LU6;a}|yHTyBo3Ui$ew~(Eam^%N0sf6I`&CdH-rY%eW6FRMM&Fkkb*iNeiRIJt z_T;0BrY1(8%WHV{N^i_wSJI$Fsor6{H2mum^Hoq<)4CkUZxrDfjU~5>8dPgU-56dl zu{*yxGd0m^!7csjiGzCl*H#t+W(dcz##v&awFYhO=v}KF(Zk>S8B`0#n-_+0$1%4O zjZ0^dA8U1zwYP`yPB#O%=k;hlpzBvrvv5yt436c8ihLCXiv;n*hiCElQ#c+gMwBp~ za(5%_uZ=p@qP<`x9%sm8@cjjhyPJv_lyHC5otN>B;YriK3Q9xn`Kk2AfkAnV!GD%C zs21%vE785g5xrV?iXO7j&qBb8<+%26)lwSXjQSkXFV(uGkN@1tpjx!wti<&l{zmU# z2kPgtzS3!}Xq$Fs@#iZ~#_$hwzd>J}xV2hL_ZlFhnoqa%=RnDvhbDV7J`lqrQvDqZ!h$>&-UvFI=8U2gVqqd8%Hna@NmhMY}4l-b4dP`qz zvNz|Mp2zaMnZFAwk;PtI3||`}pZ#8m(Q;|sDGk3f`d4?^b?|GEX06&F3YRH^e-s*94Uf{Ryg02;KsumEU^C<<5 zD%!^C_Rg}w12j& zJL)UpJx-(QMyq=s#^&wQ7+q`B+gXV=<=l)J>1r7*avabpL01u_;a8N}b&{9<%`DxF zP;T*-#3x#MTASG<_nydMVaCbFGZ;KKWF@;q@tdy>i4SnyB5Nf7-^1e~0Uqy_fWJS0 zzr#0cMt1UO48-wF5sYfJ=d0MRERp=dqtrzGkl~4q*Nr!f4y|-b{L&_ott~x+XIOAX zP#W^#GEel3T{+(Pbw?|mYIRz?ie)c4gV$P?npom#Pb%#(+*mSdlZ7Y&HlmUy@zQP= z1f}5=U7piPuYhn1+N4vh95Yt2Lx(2uH@Q<2^S@8>9M!y!u{8Rbg>VNOzg-x{7k0iP zC=GexnWK{qb?;+bZ}?27T2aeZv40;A;{)5LCf=6!^UPniwNZFg9)l81z{b4f&b(N? z8-mi1U()Ni=Z+$+jjx;Y7*y-rfmN(!RA)ZDX=-BbwM_ep=k+$y@2_ehes7e>d?O9s z_|R=ZX-%6i4KZTW8c{@AkO`S#!C&iOSh#HQPEtZmbl ztY^VHg3^#9oK#WN3i6P9`&70N>0mrUwsmHo>)#NRhWz#y*}b>;2gx=1cAaXSKC_CQ znAn+}ZJwG)=W)ujXo=Rc^u{~}C1PNm=f5zFErYpBX~=KiaHmemoUP>vk;kA~LGi2D z(5u7Pl1{0KPWuuPVSUIIus$fU7HmvSn#9V(8l*J58Qrziqi&l%(tYeRooX%Gw2H;q zC$SL)QWN7+ZY5^-7%q#9-ee(?z(#!O87wRK5=v`Y-6vZ;j@gFG@&221s&#MIDwbGw z2CFqMHR0oOE>T}MUS{jq%0iq58%?uDvZLS=DGho0UGLX^xPH9!tenHxPBHQm?g5V>FoBbRUZjT!|CNW<%H|v)q1*8!wjm`4s4{fT4W!x z@b6Sa*Dtk2nWr=KS2IUgh%ew7^brB}i{l;(O2hfVq;jHrU<18%!dQc9O#mC!R=e5r zL_A4F%&S;OEUA)JUo<_~LL`BWfXT1taq37 zwHIA|l8Vr))Ddrz&97`z-cG8f^x?frMs6#1XMyTf( zdu;if$>Tq+W~+M5{!1fMwmXy{{j%GYv8nDP7T2=1MI z#y+YwZ}e(bJUEUI{xB`cN@Rw2=MnIHxaZ`qHcISozM6Ho7scy8TyCSZrlpGvGh(L> z<7e|XvQaI(9`t55Z`iANDxzpgsQDbO@_xxAXwBOn@BQD0ISdK7PR47rUC@2u7HAiP z6Vf@ujEkF&CU2g$)uM&HfIR>`k&0*sHX5C7WuNwtTL`p~zRXbj9V3=e8umf3(fIB> z`^N&COoD1P9I(uuzVftG#J^x;`sy?GW!)1k1lq{<<)D52&6y^lXvl-h5oWw```4ba z=~|PZTF+KKvLBlil8VT9FVtw(xFC;cw#`DI4SReh{`GOVNhlhg`(zI@Y7VKuzj`h) z398j5Pkz2;+JIC<=>1S5xCG!_@-PWSYuc|_!;J60$MD_{+L;8^f_~!A;#5SV zr=dp7?Zv#PS7!@>HnL_M&)c~cGzmq+m$@^A8UNe9j9)GKn@LbD7;g?EXTzEJlW6`T z)cCdadcM1BWeb68Wk8MT{85D`CZTA^xl0dyRd*xr=JMG_wQv=|yyY+hQxWT5hZ+Tj zY~vLJK3WKDhg#>9hWkNyi;=QoJ3qH$v1OeTPh@%wWe=XVFP&&)ZVefxeT!QN>Q^WY z;}IQdjLeW^`@G_!*^98YZE9^}8*mL$j{#2yZDGcHqq42Q`emjEP+HgySiv@2=T_oD zNT|`NQ(?BP?l}vAHNmmKHArdrKAdlu@vPiNn~`~eSu3gqE7*qX+)Dg4Fx05|rZcM% zcho|l4V+WB29Z!SoJ(yKW~7__&UWHJlu1x6Siua}xs}-7A=GHIC=$L0u+KuE4O|(+0Cg+LoP-Z-L2C>p-L*DcJDwFfb;EagmsYQYL- zxX!Ia;inUg`orF_f$eHr2)3z&dBR&aK3( z!xN2k_VoJVdJolFGYM=5t`l4@l!m_QA7)%FGljW~*k^hGrG@3fI%l|_TM6f?)o;M6 zrR6$TExTb`ScTH?`vwqY9DOs54cpRPt#h;7)C5EW45I<~?jW?h`L$W>#HcnZ$}r1a z2yscN;5ZfuaS7V^NnF?)Vw~FMWoui!wC?k0BfEQk5(`O6wzOV|$KUiC5Gyt(r z?iry*Sf5YH_9NFBC7fF5S1h!q9mySLyhuOKzNXlp76NTJ{fe?-(wa7=S(uTd+eLfn z_AwR$Z8*JzX+zPF#o9Z}82?vh9%3JthH$QV(}tooty#Y?(babjBVkufdO5YF{z5{lNesM=x1;gOU0(AGX_2wYulA#T7nDH@(^&u?yw=uyD< zXZ|eM(-!E==P8*b_}H919#dYb<*1 zd9YD@dnY|}l#NjW$HN77wFVHCVXYJm-y{1t(U^4iHLJX%riDN)=Wc1IG!S=TH@Lll zjcQvb4FPq>2*9kNqG7f}U)3Bsi4AGulZJr)!MH@V+@zteU_Abw-hyqK)*=mo+DJKj z*QDVWj$q8=hm~g|Hup$FV2!Y5NGKY9LjmSh|5KUSs_o;_5HOc8vNQ=r!x?v&yRTYa zv@K~7VySmfk10 zo0#6*mXx!Gg}`<|EzGu18oqk^Fw6)z@x-=!b4Ck+T6l+oK9SP!>nh+A^L~zCE(QGd z(RNS|M`_rd;r>J0ebjsN^sVM@pzeO0y=%rn=&9A+lBVUnzDA6kIYMUc+S23Dg8kfg zL=-Qr!LO>;6MUF=H1Cz|uoyddKhHBJidXY*2^nhL=WZ5S#^G{N+n#%=Rv-|0ZP7fi zSFa>1@vV3+`SN}nslRM(A!4HT@m0rTdHXzv1*J8u=JT8~GILuwFMr|MRBKi2KK|}V zEFamuNRpK}3BSei?m}t#{$r=Tl&JqHk#E{Ohll4nEGP}@qfmWWFt&^gjrz3?)jIw) zkzZUlhc7GVl4K>W_HL)UXB#i$yu0(Nt!D9*cTxP*$crNWK?E1Gqj(hq)A?*IiZ{r5(emcUH(?6*z7fe|v*S0(%LN_L zD?J}1&kWvUqwjH|gNO5_UuN>LkY!;d%2aA#{L-YfaU(g07bWPMCQ8Gz@D}UzqD@B_ zL3PU}(>Hwdz2lct0o<=s6t9u{Fw|<{+5GzPniGxl!|x_jE!v}2;(9_!ogE7?Dz-kG zOy6x%f|dl|v)o>dSC(Oht*Vcm5_B{v4c}J3y-x3Nez?qZy#u4fhpiEOP=_eKpz1|I zX?RyOy@cK^Aw)*s`Cy|29UDr+`KYCtj62Oc8>9d0X|X|jn$mC<`DF#;^4MC&g+gJ% z2#(RViZ-`+Ry9F9taiR^o48H`ys;Eu+Z#{W>l8w>9vr z9daguA!mZpuzv)Vkn4}Q8=rP<)TvfP-k$6mWDbmhoCzxt-#xv|a3QbJ2684S0r?UP z-?U@S1f}7(Get&uk>@w2rW7@(mRn+XhVM`@XTnN+KYdUXUU*C2@}-r9fP4vtZ}u@~ zg3>T|D;^Q`JKWLFLe2!$f_w>vZ+0lbn|N>LO!zh*U=&@rTKrRP zx}`@K?TKL?k^a0hXjzGMg*qEyJ8p{5)9?#;_-wS{tm9UckC-F z!rvQhT+Hv+3ItzLrI4@KyS~3ZVdf}FwOs4O^7^1P&oeL;kw4s3Zl2d)Ki|yHLLA`H zrakwCeFdfAH<6~f$|kG&>(3kcNvai9AeJ`-8-?lzrXs4g@RKDM^w*z;x>|@tJ(|CT zb~Je3S5O+B_0{#0Q=lE4V_hZHn&J}68-R@~Z39yg@1TzwFYB+ro9`4w9f5&? zg3|Dft!blV!1Vrlr3ha^wMu-BF>UluL)4o(O8&m6zdmiAuTF`5&<-4r$jgC(((u*n z$)n_K7{R_feRZle)!B}Z<5Ckr&{vn2_Sc_HbTud;VLV=gjpeoa2};B754Q7@Ib-|l z}t+yqzo6xvbS&(A_UfO+*EY!n;a&+J`A!*~R{N;jA#w$^?I z)yf3(svg+zn(G*kpTv_jzQP|`-fPMz3xV_XAFvS=*-ua!e%WEBulNolIA!W6gKFW- z#~J>70sP_)u?N36HOE(1YRzhm|-7 znnQ6s!dxxHvfw%9`oMWbX=q0yKjUG1f4$0dSA%Mu+v8XtIIpb4bLgWEV58&=U!4+l z);nzAY^OAw$OYmb7>^|}zB<*a$sIP*5((2r8QWl%ET7;jD6s<|z8J=yYQef=xXy8XSP5f-tI-775edG85`srF<*z6W=eEbX8V|v@=L26t zwZLC7BOs_2cut1a>(Lw!T<4UAr-So+MI5ZbnT}QaLkrfOIUd*!D^VuQRo;Pi>}+m&h93m@6?2ZE zzoIlmuWMZ8S{RS$TBi5;p#}cKw1NK0O3Z5FC!aw(8iG%x<$`}?%I{JdzOq@*Pd0%7cw;)6L!BhZgwr zAM1nKgNO`>ykMg=>`}B_*ssiah5I0-;VU;lgo59l0ltxHVY#>lah+R<81U&2A-=Lt zGI!1&<-$&Fu5;YaDGgts@q@@XroS%0mryP2AM~8KpIeCmA+EAKv||s%43vQQfvLEJ z((v^pm?h&jK?DG+muf+rV6G4JyH?`*PG2z`eB!CeW+d~YTs4m|zM{0Iz0K__`ogMR zIm@~mAfa{uEAeZjH$3Hp=SyCb6X}VnFgTZUbwfC73(uM8=_>fv%S$gK%imSy_MJ2K zQLX#y!+FrUa5fB{Kw1gcu8obhjv(ruEV^ILfxwx#Xe555cIqfrQw+2V=tr0>#D}*ET0pp*2jNl^6GKJc_i4d z65H3V;=YdqrBByu`m&NU*opL^%wNAG5}!sgo7*V1aKn{UIjO?u5r1;Emke-ws#7hR z9c#^EtvvVEmdx9bfqbL1AL2Y`LCOFS{BV*^}IWo z`KO=4N_@cIW69OejbGe1O8%FAzD~6^mYc->%Q>ALjyxxEkyi@ zaco)`WLO+MB`6J9lc$#_wcZ^jCmpZPPMru~?K(xVNARv-T$v#DaX}=T|K*sV8Lg0? zc5Q?C`5$hH_OT1b%Zyc9S;n09DD7!D>0K?%C@`ZI^j!zPC)M z7@lk)s8(~AbsFsm=9=qMEC@c2tGZ6M;-HgjMk`iJQz6&a$#O_S<*qY8odE=)@{C2mI@#5Db z32omNmz1DdKHVeOl9L(PJUt_LhQ!B>jKliiy=9*jmsCQDnLx0U8M&WHbSYKcsL`44 z-E_p$LQt(OTgJ1huO8bn1iONbbtS4BE1FhKXm-p~QVAtufCzr}*nVjo61N%_Fk*Lk zC#;;-(n3(J;>UWiZg&sc%4f*|M6hoG!=?G*gsTxPC6!Pj=0q+<k!W9G8Zll z#BYC%G~5pN5{+hd6jVY9>M=B})!PBaovQI7-;QY(f@&4Y8pWFLfVgp3O|ap$ub&Zd zW21QDJ5x{zCFuHxjFi{@#^iVB#pzcoEd z0c>O&Qq!o}H?ORF`l6r`N>CpIAAB!Y*ofaSHv`xSGkBH?)SVUF@TUpjx@tmSFF$N3-3f`+|*4rPCXErn}3d z-#!T{p#=3Y;6?X5)(5xpmLEb~BqgZU<|7apNW880cJwBqI^tqH-QVI1E zJ+qv(tq6wiQ@tGqM8M#sdfd*&a_mZ1NhOq^9s|Cybv9C;JiDo!mLr>mpju5vF0j4q z9?kOh9|<6mSAF5?R`QXaQ&I^f zHl91{U3Dk--t!)7)vnArThi_}(q`nc5LD~b((rvc*vM0HED+O+gxaoLX(Kn5&LydY z5;<)XlK-5S;JxBMw6Xe|FYny9jojJJN>Hu(6;qPaH;raFwqiS$1YP6DH@B8a9db%4 zp~Skz73^F6qS@svNbnDj_=~x%WpcTkl1eDit3`nQ#@YwogWh1R4%De3y!-jdz0Gr2 z2&z>*GTMHyb2Q6%3CDa;$0?%TyJqrSfozgWD3Na9A$z7#(Jb4JARzY57$RIAHJ96` z{3@x060sluXRmRwxUI_ttkvx;o5kpM4Q175Su6zA%Czc({n(;tR{MX0(Z;tWBID4; z(yi1ll1eDCuK#m;x%S?+qXW^#Cik;qe1wnOUn!%7pjuzvXXnS@`QqTx1Aw>|bVj_` z;3Jzh$tbCW5;sN{;r2_xw%<192V(e$7h+9$FS&7cItxLy9&9VYm)?tJaaGZm%zon{ z_pEc5EnPngDxt*5r#{@{O1v#_C`L=IgEGniJ~idW6CW)E)jI84lehjQhVk}2ff$^a zN0uu7n+&M`T2KikwuaQ_r@Ug=tKYf+kus>LeD7CQP85#?l~AJf`CdH9e%Kb49;3dn z@G`Q0?h-P4(me}7wMs4V=Pky?uo11>0ugk}UG@mcBmWtGUQh`o7StWe4;+MCki5-+ zXgR2+Y&}1(+|m4^pb|V;-5w7rD^!UEbLQt)i@2B%GL9y&e zeJ>z>9okWfnYYCDCF=y0P~z`Q^LXVRMOjVrj-~LLUh-lqE{aZFU?Hg1(Yv#Gw|lXy z>XzTY#_D|&<;8me?C!hwyw;K7J*YF%BpoHuow!zQ}n zEZMYVg7IeFU%a$eQOi9ijp1lC2;aKja7NFy+DFc|Wwb=$bXTMMqoze~?kAT{`9nND z8zE@_#HL@)v$v_mHne`ut$mea^Duc}_%yMu=Wuax=^}n1bT*s0sfeIjl-9Hwr$@?b zzw{Bl!5svZ+z462OJ8fjX5PBNX-V*mEGSrNNjbz^S9gmIN?7}<*Rl!nL7@vgEV788 z5=vM{Fg9bj?SFaW*z;Cl60>eo<l!wVm~L#l}lY;5Fp`o97294ZmuYIoy^Xhz?GIYW==?seSU~sTO;1 z@0=;zR^#zby~D*}rVT})4QHOVNhlhgOn{BLK(uobRIB@hhxR_kgj9qC8-AVs)rW8F zY1&W(+Hhu%n}nia?t+a*K#X(}RI5e1e7s-R{;7z)U}HdEH$yyWZrV@;+HmHyn}nj_ zGzZui2!wPJRBKO)J0CAvr6Tr&jhf%x4fto;Pz2g==INV+qBSia*r*PKr<0&sP(I(C z;+~3V4aA`*&5eM*Zl(=Ipbh8g0h3TP{LT;5DhY_;PJ(JdKXGVrDnbA;bYoAWd#8T| zEf=qyrxI*9uM`b;EI`0m7)_i6)e0~sa2UB%#1J5QUmRw9dbHEDp$J?ncn$#1ub>S@ z!`VI{+5@3K-YHUR!Mx?wS1(OP3lwgYqj@$3@XP&Dk$(7RoMIJ>5^ zSu3TL1GEnAjNq^iQxScEfHiI$${S~%T~GwpP@RybG@LhpS|KqX2&#qN06YOd)ObY| zD=`{~S3oSw6KCe>t8z&@?39MD6hN*1214YEV^oWjn~LZHL~CgI6z~p|z#6KPFO-Ha zo`Co92jcRY&N|gnJ&GQ|O6&%rCyby5-hmQm&pG~fO2ZwCbIc7Os1}wBeuQ@ee_|!F zLOYyu*FqreocWy6j=4Jm=5BNFCsYf|?eAD0sfg`REAS)6VDJui*wAmUzvoW9lpd92=pgZ3s;eICrd>{!Q8Fw*f}i(+EXWy zC=Ho4u%Ew%wb2RI2-U*bhxyLE4gDd+C1yL6Jx!YheN`8HZu_4tH_LVQ zG@hw8dsoq#wguXe2MFw|)LJkeHuTWc9^7-nEU5)MLC2pXXqJmLgc*Zps!c-CKjIPr zafzBGKeTXvLVtobeiF{OL_l0(AhGs&VLflxI|)XLd(T#@IB#VNQg^RB$N7FqK(o&;t~mQiHer6RyI;@ zDxy2g61-cnfp;MNV>ydXX-yjeBZx%#pHUy~0yfn@xW27Kqn~3g$T*v4(Va8KLjQZk1L6|XBUlM%Tp}SZ zk+fXAcCKIx{Ua`s5SN$))q*&|^a#`*{3;^!6~rYH;t~siHk_Www4vx9aS8eolb~97 ze}f(YZTuvhaS8fF3xPJA9@Qii{Ua`s5SN$))pGj5RD?4wLEmm6(1vsWFbPHfh)dA7 zn*`Nz?f|I>XIvs6F0l|~hcgL9|ACDu5w|N@A3Y_kHr1jha;?Nzm)1tq z)I3JHE(KWkB6E1hH~smp+tPvM`M&*05IUQCsLwdP$vqw%&Y`l>vo7}bi|GMO)dFPZ25 zKeo;Syoy|lLIFF4tPqvh9x1DPu`Z8p8Y)ru z8Jw}6@29@B!UhW_aC8->Vcd;q$}i@uK+hh#k%(30jzy8-BXUHF*wz_h02iAgq7B~Et0Djb8O5*~$nnyGRmV5O{?DzTCr(-1#6d7YiWDiNoF z*4COacw#LtoGlx)E>WDtB5Ys+$J${UmWy7xohVLFikwi=6{~PeluDdSj5Jf#JHbsM zV5PlTH)16@rZp{MNp`GQnsib)jpA@YF<9BYSZ*aPCX0!bnt zg1{;q)us|cDQ#c^A|K3_VT-gtt;BWtEHmeiKfH1kEm5{O97}{-C_Ljt+%?&ohU7Y1LeVdCYE4xbkmSv?9t_^#eWhL4!CU8^&reRl=lcnrs zg;h8{MkNY*tZ@_V>T0CfO6<`UI4S|t(E8@wGzn40ScTVxt3;DMY58y@a8v@OVGYan z4ffWKRd~I*N?a;6&OF6Tv|UU__$|j0m6*UTn&+O0 zd|(1vhFP033PRGFRwm<1dp@vA{FZGD+tV~?iDsSKTB7~FI4S|tDuLS%j`P7S6o@0> z#XM}nJ2x6&IaoQAoyr?VvPYjc@QV22CnvEQuu^*b@zXH+xW5RY4|0~aZfIp#u&Pit zKUV9^ERq+_d{K!GC7Mxxukw7&hjJd6z$@@Et!d@v6w{;f2J_s350do*gV7gt#}>c}>`gz98<(?svxH+Y#0SpJf$ty1rs{4<6M5@7iAh*>_F*s9H!_C&75T$~ zIP^A?e&R+jKm7A!GA24}gW0Pm(WDKWkArDV`)k^FJ!H5KKQd#t2Tm_0)SOr8byGi7 za40`t%<8VFP(DzNAt-mNBlZ@>TxUX_klEA!I+#2KO$zO8)&Ilpl#gx}wqnOs_8 zSg@*TDL-=e@GRng?5m*?r{8=xa<%s16QcHdV4{mQn7o9Xw}qTzTGNVtZ)j9a4dmfP zPABJsvx?x%BH{w&J|(#q8M`uu7;s(@UMUZetVN3%WeWxKMv-@uu?nwsSBWY&3maBT zFn`zji9+C1VH#%612>JHUx)A`QHR{|6-?m#!T!__oADMy%JHp(i+YGNejqZ1)PQq- zaQUb?pEAQ!@33T;aUY_Ex;|LPAV!TCmrhxi99l2pQc2Z_(^m2C(1XeOfD|jlM?nPA z@R`GmTw&ulR!zvho9sJ$fk>I*MBBv=GcrOf7ABIXZeS3jNczq=YsIvtm7MNG zi!2{zTmS;A-c?>N`~))XMT!G)r)3A~vv`>C9OAq%aYEZDVv))9pbJ(^L;QL34)phV z!;A+JP8_SgTGk7{gp3}Z>OdTY7~VmUj~(MY4NUZ{v5`THB6lY3) zN=JJdSmo0+Eg%2=LR<$MeSugt-c!efuqW!HK*&`qrZw#+*mw(NwI$e7$10H$Q6C|3 zmmG*eP*$msk8LxZC?;gN#ZJ6o=0no3ZV4ibcPtpELEZ<(blX?QaMk&{2>4l}F}=Y>@hZS5*%&}9eWaG0lF1j;HClo=*uJFZsg zwiVN`2i+V`{nfHzMky#WtdcFf__WIogcn5U)rPWq=0N1ll-5^7J}?b_Ta2f19Bg<1 zfmQX4b!L6ULOxVt_jD&-0BjtAvckmcrfbdqA?gFunl=$y`SU-A8Owpds)XffJyq0) zO1y8`fp>-aI0=0b6Zej+G5d#TSD4ncmavD#6e!(=;Z78*{*Fw`hiF$SF%se+i$Oj- zf;@Fhw2EJ2=0mi0Ov4*tAPxgDG|*GWsiSY{4;#`>yTm#}-m=nh;Q9g3K zQi=Ic=T1P}gb@xC`Ji3NaTn8Ynt8YrcbPxTmi&Mv;is+GiuHsU{A!s%K1ZhfVTMqZ0OPk zR>6IR2S`Ld#GTTK4=|P-hB{vcWrYbSHzMZ`Ov66(FtV+Kd~}AI#40Es;q{yIhe|wx zG4UGI$1CVrn1K2hv9IR*foXOAz$&O`;ZvLQhf27^IQ1TEl!Ug6324V=K5VVsPHWmZ zAYy{0gnN_(Q8V;c6F1mXdB0NY2Kz1GaFP>FoV z89*iGL0OH4RQW?G>u}YMWoB>n<&mWk8@zHEo2VmUA zG_2W%d+&{dw%ghqMeQmW2hDtlaaSb>@5b< zun#1RQ;T8735NLttH3X@w=0zx4kNV%Y`DYxfr+e_)j;A30vBL|&-#%TQK9X&$m!KH|Qz{)OL;X-#Vl^G9E3y9L1(R)ObjmQQaO zcU5BgG*6=s*eC)efC<^V#Iv|_n;DSTR?cX{Zn1*=HSu;HH zbeZn)#(`+@W4h(V$$yh)Ja;xQ4QC=%>1DZDjwY7>qT0Z5aG2J#;Cz2see_^UuIC}V z#Eiq%4i`#W%bjpGaNLB?m2j(HmygNQpNi;#tI@rZhXlS$zVclqa7+WH;VqwEJ8SmR zACjz)Dr^HsC}0|*=sL~xs5HEEa+9AS9G3}>F;PqR{4DCepkRfhPYwi538uxK1KX1I zA>ZBd1A%jhi4d>ftcCL(Pu^fgjNIP3J}LV8&ZPT5;47HGsTJ>_LTR0>$INrR#TPf* zDn_}!fWcQqyh;ytN*6?#0w>H)!E*$BajKdF-U6{~9SDm_69T`2AT zu;SjRlQFx*y|7BI_>^}_Cj__P{}6JOo**QhW~1XHH}mv&aRsa7%GF;9!HGXd0=`b$ zSLsPw=-?gom}BNC_JY7Fu?|Okp%(wH66dm?x2Fmda@Cw5Bn?lg@ZR-BQc1fFtdc8< zeSuQ)9f}dAy(Ch8WlDqon~Wo%7WeE zm$-sew%?`=l@Mz2hY8!)X|Y<}v>|Ds3#CJnSJs=~>SJ9;m1vP-Jr24PthzUA5dJ&Q zfv|m@HdpBhLegpVF{ky)J=gcV-sz|k>-xkxeU%V4I#oF2a?61bDU_?`1R?3PRE6zW zX4VH*iQn@3`LD#~$_LE)z=Ta@U!^DMG#f<=2JeAX)x|1Xp6u%Y(h1QLhu1yk0y$R* zK|}eNtMo9PW@CbT((c8rKJLUSkwP0`u6mK{4$=tmU#LNa5H!@Yxk?YyX~dmbn|6s` zScQH&tY?sQ{{IMQeU7X2Y^@~M;Ci@!*i|+{wkwfB8_~@v7WWT3A=lZ76iPa+T^)Mm zZMT6{a;3|!gvf*V6IU=H*V&1Gm$cA@(%w04*;9p8a{bM(#DIza*;9oH7)Q+hEeJ`c z+1RkDke$FPxo+uK!uwI8Jyn=US-}tN(<`ah0B+(`>-(Y|gbA%BNH`v zuJOEmf<-F1nx8nV(zDqB0=|3M2`2iR=tci0-oOgJ=)9-y-)3$m>x#meTWH-1UIDXe zL@fKUES~w#7kk8auaSk0zT?BP*7l}Y)pm3&>$57Jy_=V6sKmJ(*=e5?f0ojNynviN>;?$_QEI5BSJ91s@Q`9bRcKW^7CjIfM796W?#l|rgr!eOG=Axkz zExrZO4^{7z@TXS^CUBlG4ehnjem%qO-umVJL-_MHvCMaQJR8w3)u=NvmfhGD&;A>f zYW&kGmOW35WM@XDK&rYn9l#G}PGv8mpXpdN`&A4()-94U4B*{6mez;0 zx^G~j&;i)DI52`edvwvjw5IiWJB1#2nMig%ZJmTmu^Q|zI%-Kgn+d7H^#pGR^Aml~ ziB0?%0&X+x?$=+_Wc2EgzVI}vk@a*w&Uu8FV>%`h!cpSeHou(cuMqg{DW)~;Vv&p{Ax1c? zg7-=0eQocr?DpX6(z=^sT?Tg~;Az`biKlH$!>-wz(h01RziscY?Dk++l|?rbqz$RE zJ;j?U{IxIb{Z+x`=>-0&hrh(gJEakui%v63SL6c|@HWC;ADGs(-Cff1;gsN?fK}qR ztPhn~^*C!1tVl7-3KQ^F#a{oIhFv4N+_mQ%tHf{FGE|~``>pP8!NyfsS%V4uy$;hb ziVobGBnVdEwJUCM_3_{|Nb zHO<92z3pNZeut$R>|L@EvdwajW-kiAA#Te zV;atC+>lOS6@I6y61eSR0{XVSJ}?dMmO7>7+<&(@GT2pukoBPwxb5QmLd&q%Kc?ZV zl*Z|87puf?SnBLP~U=8*n3fl*F{`(@3(<;mTw9zHYm3htN!>cmQDXNo_&dPB*s3fMEkbZ zY4uS>bxbrU5zAh00}pUSs)1=u+xYunKCkQpeNn&K1gl0Aiere);G@Do{dzttuw}ZQymbP{szzZIC#jPlAQzCnG7p+OmyNg)XDchd}Wg4Jk)%k<5WFgcC zpAI=!h_@Mo_%>rX>9?$`LM+V}NA9(s!6GA53`|3P_zmEd=GU<_JMv1$st0~^$(Ul( zS^g_2M#{Qal3%1M)_l7ASf01t--so;H>FrrI6Rg(L0K(^XF!$Mk>bRM?w-N6`gd0d z&-Rhzwh_w4m$+nL8g{et%TC^U=^-^wFV0sJ^4@HBgsjw*(t6mTsLazKJD0*-_zdd zSqio3&i3%j>M^IztiqHD9!L!eujy&gBW zOR`49vjz(tiO`ER^vMqb>F06-6ax2cOl#VO=JoUsTOc3vya`s}`d0}Ww8NP9Y&7lk zYQI9@zKv-ptC4fb>TV&l@t2lXtitU|B{sg=DlzY67GuDPV7flA zh7}XIy<%F^3O39_w>I#i$32e_+~Ufn#*qBM@oZ8^s)1W5Jf+Lh5nl>aMY@A!L(9$wtyh%tJzCqsj!bSqYZ3I@$w=S^E?mo_e*nj&A ztFSK7=rwJWX+sjiMzsoeEJwEvH3><>*naH`n-7GKjlinc_itGm^&8?qh_YH#;D<3H zdvDW*B!rFR>-k8(30+M>(onjPk0>C<+6b(w=ai4kY}&bG>hB}`HL@65~Rib5VdDenl9#z_b*bMoIeA$WLDV^7}Aqin4aEA}^jnm9jNg85h zpsY3kVYLxbB~tRpuMgR=^QQ&d1HS}_HqQp}-2pcZd|&Z`EO5FEk7IL$l03mcM#XB;T2>4^A0DhHw~5V;{$WhNET@qNW_Tb``Q zMl!rrgH&Y%VuX#rs+nnJ(}pC34KXJ!Z#KmwBn_*h zAs<81W=@m9s&Q#^tpni(HCPyC=k>jV6++nfBUh1{Ft?k8q%|!W#`f$$EU^(-wP>}| zHkkDt2r&)29uDq-Dl9jXON|9SHY}r1)srzu=xx+_zVgmY(V{6!DlcDN!xt}9ef6p zz$$1NR`3}d2%FEKgU_H4!UnWs20nvHNZRf*=-@M$1Xe){XW%n95H_EIg3q83!Upt5 z20nvHNZRf**a@k!^>YS3g9Bmn87TM+rVU958!)#s@EK&UHEFxgK*47)38@l&5N3S_ zK7#{c^BE}k3<@D^z=+DgXE0MGX}ixr!DlcDsj`in415N2+)XEJJ_7}x!5rHqA#A|h z&cJ7|V%qLAQ1BT{LaJ;t00W=Ffw1`u6nqAS5H?`GV&F5#*}$ajJ_D6=6js5k&%kGJ zAZ$JZ1)ssRAqimvya5J2gE>1(+U_$@@EJ@3t6{6EpGFDY^m}26nqAgz$!7S zfzRMT*n9>ZdyIhVBE zXVAfCFbS-JS>Fmig9Bmn8FcU&6hhblZ$QkoCLw9N&!D5HZMzC)eKFTM5H_EIfX`ss zkoOff4LbfLUm$pCYulemIa;zVt;0>3erM5JDyU9j4Q4Y=5Vl>z1%e{FZayuf*JJ-_2EFn85uG z(`h!UH|Sxm7sV>{oBc`zxTmdRMJlBip?_y-HpWfa?oy!Gl3n78?49Di(tG)pnE0V^ zgTnuZko^wR=DI%qd2ca$onw{lx0w%VFD+H#zv55a3lp;6p?|mKW5UVb>}?mTq&N91 zq4jxePZcI)zY~O{MOs4nfbf@QeTXYqCB5QbiOFlP+3Oq=xYtTL&Blp?t?a47D(R~W z8!90<@h7fe0#x?5gOV1yP<~J!YPW$^kU~M2^`R1i6Mr`A_WMHl*xwFHTIfP~siWoX z^?_AT()MRHm3Y(Stvywkfcm$;9h7vMjXDp0n(JOgs<6uT+ssEgA;0Jg){%hL=lFKe z)~*VVOWp&my`CVX%GOuRXJ>RL8?mXx`aRI2ej()BK}@IR9l?x9c0+^ zAytx)?_|=6w2^wEX+x^yTSu4;l(&O|7Wob3XRig@^C49tAL6%oJ0$OvP6$r?NfnIx zrl$w81b9Aiq)(G z^bXNRB&$T_@OHF7_iS{0$!KHx^VRIyz9f%v52MNIKbNwMQBytYO^qk>r^d6BJqB&B z{34FPJ`-7or9DaXxT@nTm=M1+M@>x@w5F8@8zsAE;$F-sO z3MRyFuxI88_F(}V?epZO>%fL1Ayqcp9>TULUHKPE@x8DOTnbVx{y&Y7X~*TG5_dDz z+UuX<%Y%yT((!$9DPS7D*M=3*FOMEcD>Oq$m94$D4Losk9PYJ}R*@{1$1|FPgaA52pCbA^yUb>(eyyH1{l40oDt{sU-d1 z>!a&g^=Vz(D&L*)S8J8XeJl$PYE{yhx1&2RG9`@sH$95Ixs+mLz8pdPdqpwb#qrB% zrXDS5(T_{?jH7Ze)UU5yLl3f-JvtF%>J*NNmS19s)3rHl&Tz*syxp%3pn;x; z^a5AIly7wS+g;`J5u_QU_Qy?;^F@aW@H6-883pdPrC9ZK-Yk+(C7OMLRo*JGDu=r< zVOasTAudoMlvE*F)3O$NN-Ql#>ra|bKULOUqb(e(LcL?j zqkWO=vR{gU*PTFY_}7;7;nk9Ko4+4P`fUbjxPCVC|1H(P^{>|8KVErg{Yro7HM2IM zn80;_Y3N6}KjxII^R?waIeKQtY{?ueD#X8y6@Ax3V~Y& zrp0W~mUl@k$~Vl*&v2@6{bO3wD#8AV4ST!OIbJIj8+bQFOv736BRliH)AG~AMTH1X zFWxy)&H3cptC(-IRY|YvhHxD3isNAMDO%uDjor(fGYwDHzE0uz3MRUh&cG6)+gcwL z77@8l+Z!0WGF|bg_8?FpunM1|1-sDh>TXoIx<094hshjY!Nl^OrP=XJA=X?I#CcwW z{QffP?tScDddL`sz$$zu7VH&PVv|wow=y0VR*m8K3MLL`wXiSe7hAvoC(iR4^5~s0 ze>q7W*{i=oU==>$3QnEg`M}sl{_@z~YB0xFFmWip2Rl_K(b_LIAJ|y>wg}JII4Su; z*7gd4RrrJ}INOQl=6z}}^@tAb#_<(QI34t3%O_p479N!gY_ywLn`gMPG5O>;H-*3| ze8Lrcef6!xwaJkl>!*2gd<7GwPE2QSu6?y$pOa10N5)3{_akn}_c~Tp2&~%KeJ(rE zrwFUK=O@#&7i~xL_#;b_Ugb|#PHMV-X9@dus}5_w<`u&yDrwsCw=QwzH~?rp*IKX~H)wsIMzK5!l2Gq^OZ z?^Z9~<|3#;%MTyWG@kSotWunwQK*lNLN zcjI&8al8qvxqIZ!^IWaTTV`Yytiq8fDv^6#JwCKc177WYoI)%`r`cl~#@(;Kb1his zsq=#^ScT6DSBWkSYVrAt-T9vIU<+2^7#x+@f1m;XSf?J}T5P34;Jy1Wt!dkC595QD zrW$*VN|w#H<4Bj*?MXl9JIYDyuVG)q$ZX!Ewz;=q%DRdC+`_3wcV`z1KCgYntQfNM zZZFan_BK?BdvK=22>9k+rfB$BjJTt=stNNXqMT+F~Bhz5#NR>EWq`to4 zb0A$dVWtHWxQ$^NRxbC;$*U!I=dT72_P{FKmQ> zmpEINVxruD5K(lEIk+Nws1>3{1nm&h76QAyr`}_|$=7)#wwmNpZJcBx4~*B3F(q^p9|F zx)oMU;=LbV!H(7Y}-$nShGbJb{ z>c93O6+B`{V%T>B(-4odFB2c$xe&j5u`Io+Y`D;gtRk++#qW1wWeyiLhX8|KM1KBZgEWb!xb=#pt8w zoa?6$G$4YV9~Qy#K~y}ZHEmaFExzK?4!z`<@*Jyrv=3vCpU-CFUZgq@2ZB>aje2o zNh)#vS|hq)Qj9Towll><&5pC!-S<)K^w?Ab)0(zqMmPTFqNRG3LN5%g!m&##@x7Zf z4e{|d{_O*&Tci7a+!nz`c8_8UYNi^PhBfp`IUH3SBNT$*( zrqph=HXMX?IoP>F8$+-a_xHDSFdw>(%smHDlkN_-(oJ>v6h zHn8wGGIGro;|iRa@-Acy`4j$K(}umNOaIN>kUJ;MRfsy3!`Z!W!K5d>q|lny_E|N0 zXdU6s?WQV(%YV~Y{vXrG+J7$^n1($X;~UWO{p<03-BkkbnvQAs(%@2yc8+)FpPix< z8+Z?NOv6dz3mekl4t4p{a@>-VbuOFq+i$4$ok5-+~dN zxf|P3K;tp(W)qLjUTi?aABLDUVJ>88Gv}OzN$k<~t9p~eLnu}W4+DG%CcF%l*xYoV zQKH#u{mIpS3eo;u06F&}fZeJ8!@xAG1l*Qje2iG5|JJo1#VX_IoakV;VewjIWJ-v)<@E&r*t2V$OxRmx*~-B?^_Cs(bYq$md)* zY%CbRnw1NPBhx?5OzfPnoVCd@n*`i*w!G|=z{>WDBHbn=!;S_wicN8?=NrO%=8s@l z)jKqSb;&-P?5kMRfhb!0OG4vyllkfH9Sux~-z&<8lTYIoS}+Yeg)DYW_-D;z-p4PE zkg8hK5?F-_;bgm?BXRxmx_z4K7~X&UX48fwgpFy5q2%fMI~Gi9+KN$A6I#2C;iX2W z5mI$wN&@?l6iV_haU`67-f1wT?LdAt`h{sj62eCI6kk&LN`8WAP0JX2GGR`~ft&@W z5mNPKQUdI|;!D1sbR?FS@^Q^ru@iS&RgmNRir+(%y-45kbqJ>6yFp;-#QwE9@tJXH zgj8+vO@j$m5TGOQh&*tmuVFSag? zkSdS<32f(XN-kw_B&xskar+cgmS>sY+_WJHVdK`VvZPSQ!35I~NB?xXYw7s1{9sfX zAyp?r64>N(Wl4g!BQYvYOB|6Y3-?U+Hf=~k*zhTrf$VP>KrpRo-TF04*zr9xPd3sB zsp>y9fw@=AKv)Au;@>Y(`?`KTWpqC~!n7d?VWaGiWJ?g4K`^apm2=Ndn4Iaf5qCO` zkgC1#W-Ui~C zu#0sUdsNO8MO5NZ$Yb)k`zpgtAEOZXt2L(K&0Wb*eQd};`q?;aqzp}9@!nBv@Xk$g z^kI`=^qB{vQt5y=)(=J{SpDhUiw?17;@$qsKt%b#7-g#Vw_VLfzMI3E^)Kx}#Psh) zKh?;<3+}(H5Q2tLf{D=w)3D1M5HEqqZX>X&`~4`^^wBa0VkHnRYd;x}lWXhvzT!8G z5=@Lf!iJ<_XFnh&1L1EYq>6)Tc-=7eq{=e~VgV32+B`SH&-j}*Bq40%NbzN2^uaXj zTn~g75MynGREd=2$TFFAb#itfwgS;^-W9_YykvaePGAE@2_{A#OvB6x#1|k&0^z9o z{A~cMvf0&vhyo(d_5H^961x>b*n?4miP1;ckhG@70g)SsZa_Gy{F7R+9yhu<5Nm*l z3SVyw*l}7R1P!AED+r^HupwzpTL#2*AVO^fR*mCT*tWdB4#aXGNbyLc!-RXL4M_+a zeamHFV)PL2j7nAxuvO?{Z#$Wr5nX+sji#>P+mtzz^MHYBZSMZS5{ z=W}x#x#E7BgjBiutY#hKMp^Inigh4XeDS6pi}UDh{L=_I`Uo3xv}>3~TLi6XlYF3m z+{vYn>6w-)sj{WSBJ!aUbD^wmd3M%i&Ltsi$Wa^9_Oh}QSOq0YWPL!+O?zpr#8Ny` z?`Eq(NeCNI|K_Y_s}Ga5*SRk19IK#Z5ZSJzJy_2G`8W{1ULTU)63zPx8*&yEHY5#i zSb+EmL_m6LH|KDnf)-9>|41jqSW@Kre!Wq8k1`2iLwW<4w)a6@_Cc(Io=Rjtm-aMm z6WHiD?~2~qHkL?2*pPmZupw#KHxY*x9?+XyEKVMBUn zf{-*kr2eH1l)L)*wn9^1yFV}q1Pp6O6CLwG{FB8*nwk!}w)_&4s z(q{wH#}z4o8GwlSLnTD2Uf0M#Go{ZsCLwG{FC5dF77N6GKom)z)l6Sqs9+u>&0!u? z2|t)QU9Fkug!GxyB(T?yX-zwtu~5>=^^tmUn_nXPxk!~9B|`lYSkj$=))u28q1XN~ zvvtCnYvK=3hxd*pQsq^j2X#JJlVepF zl+U1}UM%#tIz%N>j(<$ZRIw8k&mWi&`H=ntreT#uqpAsys&t|WOVXY{r0M`XtF5@` z%Qj!lPgEk%`@+7VZ3og6+jEp8gbnG{U>Z)gzTGRKRhxmdOq~76%k-%#K|YQrgtDl= z?^smg?2ChYv$&3-Ep5+(^1i}`^ye_GY0WBbNOsE!L`Y{$<%6lu9bwaA^lQJ!?Qu2%!#8{Pp0Lf?N7p{_nL8B0{fb6HjAiV)S?pW ztcP94jt-%DM%tgYO#*w%nAWuKEgq8z{a5K7NSYTe*M%+`mB4PCj!#|J6y$qG8dw!KZC}JU7T;88zBE0NM=Kp+o@|lWr2&UoN z_RQMGAD?sb{`)&A1YXgKX_#xnY8%5o=cL~0gt@*oEX{_8uz_hf`5jVKE@B~>o1Q9@ zz}^d{VXXn={7jYZdX@B?n}o=%^qepad*eds>LXSdSD|$As#5&ihH2Py_dqp1;aocx z*Gq(B>o~V+KJrZLt52ymIcY>{0LM>pxGkxzq#CR*8M6D8rPSZWUCA3wO|6PY$-IK zCgBas><~V0hA&I`t%aPo%`1+Ce8z=SFxG|eR)2J5O$%s>4g3r!Y};aDA=a|o?GS$a z%ron&w*Dp|uV6x?NXgO>2H8g!e0xh0UM2$0Xzxd|yGxI8TU*hdN*R z*Hi1@_SZ~8UcrR;o&G#n8i=Kho?Gwq_?3_h;!ZNo6V6ya4LhEG47HXSSI8vf6?|XuJNXz3+c}wvD@(kSbwA?)79J+bwczmsjw8#qacI z=btctG%MMh{NtN8e_%qYgbkR9%sr$uEs+i3ZWV4B@8U8Oye1XTwStiQHb8X$&j3E- zjh8-ja3+PoDw_>+&k0x+R%;5MGw~_$9Fg}I0`DLp_qc%XI8IQyi7UwKOGSSnq)OPZ z%|zf^1osHxOCtP9^pUrhXMEX+?8;E@7ecB8VVhULhU-jNJKv}T zaeCe47ecB8VVggIaG4Rp`>y(GaeC?X3n5j4u#NdZ`c)ygkS0~(|Rat+%JSw*-|LR zUC8+i$AVl_0<;B4Ym?59(L^g^(&i*hUN> zYC-=9`D+C`dZOqrgj5Lvyg{)a9mI?t4D{wbYG$VSD$f0dkgCp>)hw}59C>p-)v6U!$h;}=d3FNqS@|$ zeZfXj)=kFItIg@{_Bj*+t8k1Fj3t$ZIt|cdSwftZJGwiY4xhWq#C2IGx(dqMvJIQ3$O1@*xj7&Z61K^1}rYdseTpvJsuuG7HC7FcCDS z1lheYz}jMih|a7v{vW-6MR&R`E`vf~)&0NAkj3|-SzJvq!Zj?Ci7tt&PmjI-V&E&7 zX#AiNsefmMwV|Jg&dlwbg?f9|qo}!9>i-{v__!5o?cZd4aeURDq5!T81v# zd0!#0s={J#(tc75^Y7FJh@)5Q(^@kM(n6yy8u$t(7Bn7B4jhVM^$WEDqSLT?^w^R@ zG@)s#fv;d9X6s}U@ZyQ}(j+G!_SJ7j>8DKeLWTV*fmDT(L&aTzPtq@q%;X@et1}o%`HgyN$(;q!( z|A<@qv!&|{d<7G`v(6)Hyh^f`&%c5%dTC96`n)aEcg|R#5Lk8m-W=j{KbFQasxf zJ}#z%WyaudibsaMu(05z;4jW$uHFTJDBEf>cW#hbzmZ(kz$zS2KgGIGz*V38DdWkKk<5a{Z6&aT&?g)rF1h`jV-wWY=b28Z&ODp16v)+20ud34jjG|W+nRY>*bA#^0fQezuo&E}Ad`@PutsM`jnHLb^`%)Htd zjlQW_N3l`kNE~S$-kw>C-Z3z(X)i-c>LaEG(t93PiMQ({Qhr?|>$CW@f%nV6dv$19 zo%Z9{%~m1w%iRVH6L<#_OhW|dq%~}zbqXCmdW=H!j9*3alniGsOV2v&Uvg*LK5K)R z$+W@Qjykr1>lxFU)~FayDs2Q)udUe>0=F1U!@H$Q{S5c)Bl(`1n{<3He7X+Klco)5 zxQn$O9l$SpcU1^{x(=pc4NK{%Mz82W{75OT5cotDOoNSNZp1|OrKxLIC`8`yRpjvD zQ1%W^*TFQbJ8^DDzd02G@92SP=(TGy89g9QrflpFB_FsCVp=@0 zEHa8Z6Z&m$F^Y4DPoh!F>eJ2@`p5ju_|Vuq6ss_;=Df+(B1US}U|R3$<77OR;C8jN ziZ`izEQa0v^9PI!v$DY3g7;l%fvcewteSSwn-qLtF79Q=NE1r9}oNa9_cD7Qyr2(KSZKF8=(RM`fiC;(cmV zV&B=`Mwu@GeCw8X?)biV&l*g_s`~~_`N}^k(AY9=?!Ra8BVW(VVx`V}HSk_9vonk# z;SFc8d~jALoTHeSY>X&6nrnBGEttSN!eAQS0W92M_~rEDee3_N5O~)iOoO*{d<6Ld zU&Q_MO|xPfcn>K|L&V|c!hDlk2X1-MhhPHl2!v@kCvIOwI&7FHEwyAO!vro-OvCEW zw@!R-iSG2jHp>(nxXv-HX?gB-C46-V{l2`371uddVH$SByX3;17F49|YsMIO497Ky zYZhv7c_1zKv7x@~c_rd)#J zkv6OnVl-J{Tt|KX8Bls-L+x#aL;e?dFOG(4+KEl-DhX-YF!-|K;GG>6t*DB~Db4q7;- zp$6+Z({WeZ(b1m|xMSk;+elVBZVa0Z@qCzu=krY+>48jz=-tTQ2qt_=%w;{^4P(1* zUo$Wbt5AY#($9le=ErKCnMLx#&J-#!@wzkh>gU2YE!nT*`$8--6YV z-gck4KZ9MhIBP#9;*o!c{TWnZe~V1?eqte>`JA~wgPnlA8JLLb7yC0{8pgyeS!n6a zzwzh{r6^Xx-V98{Ym5CERO0*TLwd0Vw~U(KJ1PW3&M~ozfQZz?G>j#ckLv$*xMTba z`!irw3AbKMM3IZQJC*nX-zK(~%tC7)&&!HFi)O384k8h-pU5}gSoR9`Xb}4|xbj)- z>hFH!9+WgZpTDk8H^!IY*M@A+u?m;2O3eMc2z7m%g?EMh8888RGcXbDZ`+^2UWO1^ z+_?~~osfz9!u||ch06`wgVk*zclC#*j~d#h4hjL0j7;plAR;F*4e!ETZs{FhkB05A zKLb|ba#M-&ZjrU# z)?Q@Alplsl)S1?U?|c79pWqp<5V&qIt!es;{rX4Pqv0Iv&w%rRQwTAmOzgOj7G=76 zTz4J`do;{lpGhgJEH7i3*kwWN&!7@F<_7VPyUOWRV1EXDUz~PKLrg=+bYoM`iS+H* zeb&oay;%b6n&Sgya`s^_);BVS`~~~ss4cPhQ$Ok)UzxmmwOPk1+$U6GjL&1^Zd4EY zWym7szMZwf>=o>d(+1ixrZvsuaT~qckKA5+A_nqd6Js<4%#if90@Dq;}rPDiS1e$+4=ON&;J$`OJC)el!iD~u>dfEeIG|$!_aaPdTEEko z`IN2RG;&8?hQ~f!qPV2tjn~XhZi)Ls=(tXe$hXsjSO<9ety|!TvG9>E%LPxxdmkP* zhO~u1^C6)qfJv?E>Z(!*Nf>kH{6If<=UT*XBgadJ8Tod<*eZh3W*z7tc zat)cpvaO0_{o+p>nAWt;i7mg z_uuA2{yjOE_j-Fr$0{7%t;U}>*yKZo#`or#DrTUVz;WW3hNsjDFDyq&jNv{0*sNFn z1EN05g_F_?&l)&|YW(@hL}&PJFpi(txj@MWj%!zmTNm<>k2yy1yhD#D1Wr4q;SK$d zm2SU{4&m1qM39SVF^Z)1`@_b-kqNAJw%O$1vlE7XU=SPJGm2D$_ZskB?T=#~`(c&P z&3`=zRuwPh#}+J@O*Z{J?m)a<-_PAQKA87-l2ccRlapADkVrEA_-O;vns#U64*g5* zVZ6tyaR%P^1J^m;-2+yCzVsm7=7!Ls@A5NDe1o;;iz|e)rt{AlnAWsv(V6v8e-Go2 zU!Bx3G5b{vJJv0dU3Z6lKM<{HtW-AgCULu7uaqAh2W_cLawu!zoMN0B1#cYlheOQs zMdMa%9CL9BW4>=LLRs~F+=os3VKM5s1}a3M1F`H~U<7*xr_o{>;wILXHOic7!n-^! ztq{e7qnQ=H@J*PVYG4{pOkY<}zqQ^1@5!oioGP3TOlw+;SuOQ>5u@nOh8uNE;M`&w zb|gK$nLPIGNNN6pbTC9kXT9Xh+`Qne6Y^wV^h#i7QoPu3dINHv`(SsnVo)D?bJI^9 z6WCA0w5DxeG@g{2>qXaQ&#Kti+z!qwJ`l?86u)FBwD!7g6xnO^p;!FAD>iNi&SgbD zOk=ZP=N3$BT70vO?uW{@qCR~~DK`2>#<5G8XRtA0DF&uB?YFnvt<7#VrX7n`RtQ|r zn1;6oNB$w}ll#+L1)eLZ!X=Gq*b%6;i=Nk`G;P?V3H=*(Blx(TvitnDai&Kc+h4pM z^Re7F4nlmx9~a898z=5T>HaKGMnC0Tjkd1tt`PY71Jjyzpuda$_n z-a}xXIOs)wG`?ZrQ527^ns)5xMKao@ANL;lR>#EY?{nGl>w`(#sOt(1>wT^!lCSl; z@rx%Qt^wJI8!?aFy3&)(`sb#BX-(TXbvYSTvLFBA`ChRRvG7m!Zb(=1;L9xo)9{8R z{swVb)`>Unmrt?r@^T#8yQ@99o$HQ)X;|0yZ&khA5LbSCM0JI@-7|sR4xwb(k=q8Q zVXv13K9;h}CsU{49d$h4;ZY6uV0iKxo=DoR>rThU<)FB);X1%|qiLfvSJsOL=c4x> zcB12Z#<8y@3$oeI9xAO*ZC7=JT=bMj8L3zE9u&7xOb>(EE>GnQY(%q%(01p~uB3-0 z+|eIS8bDuzjTiOrS+nPSVqg`fp(Q?b(Vy);u752!lwuX8^9)a5+4EVgduu!f8>~?! zea+(4dSF#w+QKW2_2{(7I%(lk1FJ9%F<7*Le*ST|-sDe+u0i+0be{nU%yZ`;>+nfW zz(%W5mGplGHq+m;i8KIg%v)X5S~%jFfmN8+w6`%0^sD7^=(%D7C{|%QE7ZSp)y2s( zN-Gw#y)n^7)VOrCsEpMO~9MQ>rz@tElRhS+HbNh=! z@g8eT8^^Cy)X#d)VE+|VZP@N>5qVOH|C% z>38?tG1{fKU6Zi2S0effreS5~Y8So4i;TQX;~ug{nW|IJmL8oiOCG{_t`gg7Rn|)c z<>G@L*!!SK*!mq2vjL`I&$CW0`q50Kd5UinidA?lQHf!(W%T|Bf9H3`xl=sKU;^I> zeCm=-El-R9K4n!u9s8Wckq?KxT3EyK`(R7mC6jrN#T^xY7ZcbUgh5qaR>g>5)#JoURJ@GeAjykFyvRoad)cDuH(rM^>Is?v#(jf)!vvjx*a zmhx8JD?3>>KY*>A+K!)%GAx(dgs_}9TJgIJGLl*rU-tG!Hn1^a?Ny`v`=Rv2rUPzR zwYA+b%js>w?99z<4n(t8OO0(?$I?5`8zo|*Pqi@1&cZWT6cCt((I>kTy*;l7ueqa! zwaWaA>^JI5zF*76o9r&f_HFehr>&AhU+wetgrNG&`Mw)UiYFm%; zY;g(r+5q`biAM)3(Gwn?{DrlDLrm<6q^$MJ#^gNMz%;CZtT~8Y4nL=Vd)dLr!$a6! zVzm~4`~EEF%c`u+$lhLW#b5Q9$r=P5wH6K$sS4r)Y0v%_^>^9Z8dxPt8A{tMX_ZLM z+=af}oQ=ADX`>J=N_ewUJd763%2E!k*SAh621W+3}C`FGQXO7K`hw{@;S zb2$)?*EV7o5*o3WU<1?OAp>y)h{K=T7+4jNw-swtp_OSvB|1^~_OX)Cp$^2Kjmxtt zHN4q#uz_jVn+k|iKr{dXtHK8U&f4r5XxdN-wjdiFRiF#~_DLni%+AQB)b?dh!3L&b zH+CSxfJg)at0HK2wqZ?L%U6l>-Oua2T?f&{4#YPv!`iW12zxB@foNEr0K{-0N&|sa z88#oa&eUh75H0sO zzh3p|Jo5g-ELLo)zcnhf9dC0dnx*Vrojd}5|FLE^yHIS5HF}7cab9f>q>)of>VHl< zMX)NMLkxR6?LzXUL2Vs~E`vg7$M)HYbFPUB;ddv7E%@uT`(z+6t!cHd45Xh%T`=yp zX>YXbK9imGJZgCbW8X&TO_4M^5u@|+86oU+KV}hQFvPfb7(`dTK4-lD*2ci9nb2bg z&CW=~jH41&p~sF{kc|)3+A4$?6`;48HZToe$$*Fl;tdd3RR>0%@W$myKCqz@Q84oC z*DLUs4ulxpVAL^fU>e@m0+EeY;8`-ZHL&UijG#BxHX?<=hDumq1dWS@t)UzUF-pVe zY1+Uv>_XeA0(}9*)=X`U|B-dpVOca^A72FQLhKG~0YOFJ-r2zxm9Vh`#BM>!TfhJb z5xcv)cz}Cn2kgecz(BFPJKwWB^8C*5{>OFk{oFIVGdpu;=FB-*h36%a7zi`LXY-!i z1IoYzp8GHj_Ep<)v}?oTO6@*HOiOD=Fw%36nhSH^xHVJRli-i)BlsKJE0Et{!*J?f z<+ak$#mazHcuo|FGDSzz%3rQ17e`fa#RQ%cF)c~PirwhzqE+b!*ipq667Kn8Z;x=@ zsx9tyl1<+=iDLrKub75>6JKZ0{@ym)*5%DKOyHVeT9Pam52M}7zE>_;FG;&J3WB+M%=B{O0jX~}v zOsF@*n9Ix)@-t`;Ov7Evm*eS+uc}5y7j?k|{)#XyNnO*%)4>yU5r*z+rs2|UAL8g6I0%qI2$MrzviG!+v8-&&_`>KM%m-6_H`4eRq^ z;k5c_r&LqX$HFLDCI`F-eAgRJz?0(<74`tMaC-9c4t8)@KY~^G$wgw|+z>huRS4`kG zz%+b=^%Irin*-?K>=v%rBEvmHZ1bhtw<|6&lWDK`!f9BA>1U;HsPRfLGt28&O_ygW zbsmhOZ#LVzV#^Y%Fb(%{+PqMT4)vuSjuuM8Dop!dEXA508^u=UmC}f~?SL!kObt+b2x@u5owsNO4`;k{hgGp`Zi#-kLarauTc*TNMn1=nUx1H#+ zyS3=g3-?p83e%%qhqC6MtFlFT?@I37mnKXpPQ!{-cEz&{R$&@OIKx019a)G@`Eex` zt1yk{F1Sa(qXUiDU6&p-hPmPy;5M8;2KY@|Zy?r|UGCo3SH?5zF|AUG7 za7$?SWOsFG-gEpk3!`5bR#T=-_E68aNMI-KXPGkLcd-i7lGM0OICXCDifmjuP{k@t z_pS%yR!4VJ(Y!L+Uo}$q2gS*lwq4abClc85LQh@KKp9wtX-VQwjC7xShU%0uNX05l z$M2iVoV%Vi6w524WLYEat?XvgDv4#_xlbgPCWX=+;~QvuUJq2U3eSBavEutE+QBhP zD|oHt`x>xff$y*5q&9qK0CB~(_ z?>d_#f~Al5YGCx)azlCbW+Xqov5|^Z^F2{Xoi@as$8pR`r+KGmKP^~ehFpo@T3!)q!@nl-67Z{DLXZ4qLt zV%4|cCPd%E&{r%XQEX>JzH34o+BQHW{-n4OU(Jm^uQ!r6{}#K zK=eHfy$q4Cjcmi`ENVy#FA<4mo%)j|ay@np%D^;u8-};xYnL^oRvTD(7t?m|Khag43U`9W+KU4Scr{;cZF#uS^5P{QeRjh(_8_{O}VnuDKO^)O9s2+x6Oh>HV6*(F&@#XwsXt6;B$NU&$3mmw12>jSvCO`=k0 zzDPW_olPnZ7@1cFreUN8;#$2#r6Lem1$!k#-^0+$5Q+M}VLX1em0}6C!o={mbIJ7j zD^2>l!n7pW0`Yp5m9ht(9IIfjgy?%1dKn_o^QV!&x15sN0p2bqy1to98fC6DREKwk zX;`ZPu`i)#>Tc+}SOt3}MBl^E%MghZL&CVn11qglv`92*Je#OxN69KY2d1ITfw=k7 zN}C^Pt6~-Gl@NUoLoY)lYOV<2K7A53CwOv9)ER6fUQ0At{{}G)RyYu=fhY$AR>58g z(RV%cGDIT#%qV{IU6y7ZED}!|PbBYC3z6cmH;rjHkGeXFH#wT6`5&@Xv1&K$87IR| z_ev;3B;p?S<(FcMado{&^a>q7hOVkZ+Ch6@8g2>o?90E7FV16zG*z+6ev>ar3u!_Y zLKz}aVtPAXxodr1>4?2RWL#`VzAq=l3d+DVIuZkTk8#OH{wYE5SWIu?E|w} zgGol-;(IHB@Ob9rlG!PmctLrXmZYkFiOR@j(2A`Z2qU#)@hNKN`*|c3%D|&Gc%;}9 z<@CZ3KDkFr6{{K^u~e71%_SG1?jlk2la(?HdgH^+HUe?!*anl`^>`8pWnda&8`caY z^B|JPhm);TtisPB5`l$$TvYg~f@10k1b$jfOH#`QiP{1fPl5t%)GoVD$jj+$5>lWI z#J6ivWQ#Vo!4%$cUn>>26sF&myCPe8hL9$CE!cK>mKFfxVoA^Xs<&HF61F*r7@-WT z!Zh@f_($5|Oh0b9silflm`?6goFwIrAw{7z;T|MdG5d$~<@b#Z)SiA#$cbcMG7HMU zDojIfpIny5^y$gp4r`%e6{df$X++N2^dVAS8B@TD84%Wnm&$6Wx|Ve(1M0hzSSSOl zFb#JUXExy@SY{sc{0KXA6O>A$b`? zFbyl=qeklLdDpdn1ADR)qG-hSNmD1CEyNcWhI{kQK2Wwf7fS!$HEi$FxLj$;#6PB54qwcwbB+vGqz+S1na zYPvJQD(pER5=knoKkjsqv-dj+#CXUyrR=I9C%F9g9C`i$5Ge%SZjy_cI(CpF!K(V@ z;@Rlmv*l5X%=6#XUt$9gWu}x?YkzSdScQEJa19~u;1Q@*soRE~EA0g$Yfe1t`|O0A zv!GCZo9B5HK+H4fCHva?sV9FlAXtTc4RCpoM{%!_wjCpp1sAFdM9B*Y%!^bYWj;t8 z(~{Kgrjh2Xo31{{{VHP>_B9X*?`$Le=Vq8Zz1a_efJ{UTG7%9y6A`B2JHKzF&CKVi z;jZUotiosiBC+WAG#b5lq0)AU1;GUN9>+A~X?SI%Gb{(ICoz9$UG@b076352Z zNleZE`@r{O8suFfkavl#$jiHw&OfjkcHy*D(}QVP)q2YU@^S3~Hp<_>05PzLEbo11 zq+P4emobt5ySL#^HKyTKyqO>Sm0+Z`w=YxU$6rvjmGP{>VZbbC=FPjnuEdor+ZliuPyg&L*%ga5GFKh9n%)yw}%LUKAZC{O+prF6^G?d{z#= zK}LM z)aW4gH(q;d(<%H?sa%tZ^1 zY49~j3P}A3#H`q*0)gWcVHz?CbRC`c3W#b^%UrR_BkiK=^`&ua?iC9z62U857!CvR zB5t`r;CM@zh8@U+()8n+UUW=MH5IF#7G7ou*_Oxx=9qJlcz->~P#1bhu|p?Jn85Kl zFb!T|&2MSG{YTPjJ%$>vD)mJwp^;TpMH`0=Ay9-3>lL};6DHW^mO@EQFTw%|zCcE(XBBO-ZhB#{BI60Ahf{|z+ zjHr?n(Q1AQ_>#U9Rg-~mE9LJPEE4z1OMLjyL3Gb;2O*LUj&g%(h!u9Pqt?(m zgvR$;uVNLBStAlfnv^uX1)JgJbw?Geo`fVY-2%|-E)tcet$>^e5M61Cf~3SH^m;YRMhWv(~j zi#p};(iP&{6Fs}zILPjn_&qVtl4%8Hz}wB68UAgLkEa?M_5tB(^;jU*1T7$Xt@JW5 z4QImp3(41h8ENQ_GXjC_9ZW;KzNax-@7aO0yPKkCko&Jz`PPzdg<%?Q9EK$mt9Riv zBs@{AS}s0scGj&hJP+a-4x;>DJwfj9aH_0H5(pf13e#|}$Si}zT?(fS-4_W2j)jG3 zNgB6hEos}tNR1zM2n3GMg=tBeoHm~Xb~Vxr?U+E|C}5a|*`Q4%IWX8rSDk(*5I8m& zrok($RwyYs#7J8|Da!D>!tu{A4PRgOG;*t_k)DigC=fU*8>S%!#N4Umg90O5U`K(# zvEncdGft`LEX+CfYWd<_w&ou;MXuM@{3!`}^z?K!1sg-X5ni?IsB z1dd0BX}A+-UXy^SL|TIWngO=(~`8?oXIgT!j(C# zxZ;%wj(RHEi50XCYW45nahRzYFo9#3Vj6CG&onZ>P#CF)x0Eqa4fbU8@yZ`Y2~0yY z-ECu;?R=PPueu6E8jPa)*dBY$U&A!)m&EQ>8$AbG^x;^6;4o6Z1!8rpks78YY3Iqt z>Ty`(#JYqC#6y@rbSu1Oz(@_#kcnnN7n9EyBVCymDG=~>nZ6d86gyJGG!V~w7*akP zX?E|q0x{|D{8|gjz%)dMS)<6uz>|_~V~Yc=97fX9)yet6^G_zP#GsG8~B9 zKT$G{T88J0{JBJ5d4p%>+*!{|3&F-j%i8q_wY7k zLz|x*F-Ir^dPd$HuJClDH}IrIB2rX}fUOtu`7W2A@7k^};J zc%IFmzbj0`*zWtDG^`U&uN%_^0*`i>hI51Bot(qq$xW8C1OktVn1)_5BS!hPD3H2x zB4nM#Jp=D1fX`j1nR*ZGlFWW*b-RS+XSM}fByVKUEg4Kp64*W_Wc&O_fW4D9GU(P4 zrX^`tkCkaRU`#yhoo8SDN5J^_pN)%Y*nxC^CXae#l)eRK}Px@(NZ9A1Z7M^RL940?1`6=_O-vD;xceNWK6>x)oV2i zw1-_tw><)ZqZ?xyJo}p^v&C=2Y2^>g1p-Gm#x!_~I9yFU zKqNpJ6(NuND!8|gX^2J=`omDk%a@l9d7)rc>mTW4+4qU0=l>%XcYJ8*SgSiWjg6_of6;wM`WFRZrB)Khre6cQ6RW` z3ORJO4hewUnV5!^*BDuT_qq;m(WWECs-s)e$-XjmN%+}fjC2; zJtS2w4Yy@64YsKLdBdPzXSBEGV<}eMGtVHmm`UE#q99Qr@w>s#W}X&f3>1j&&>jya z`^i_~)-R^PzhteY{HX0b?PoBoJCW+b*K~4w&%MgjtFP-E!<4Y*BmWK(%Pbfo~;-_Z8yV8k# z8fKhVS%$HZrIgH=Fp5>K-_l8h{|I#oyepA-w6?Ik+h(3(5AA`8AZYV}W~y2Y+8oo6 z162KPxY2f=(k>*BV$~Rn4DvI@q@IK}7m3K3XAIH5&MGs{jS-0YN(%9}F=LCM?_ye# zrpm44(GXF^(PAvcs=vLD>3vru+@@8R%Uf8|0sr(D2y>c33g4^45>Dmj_uV{NlAdj8 zB8R=Upcjw!r&#s(D`NULh|7cBs2#24UNI22ZBa*oaDefuZ7gM-kLBclgLyP~t9#ut zym(WGR&C#rV%3UQ>15I^%5u{S5^)~o|V7O(~ zovui=rdSmLWBY+06IrGIM@;Vg)9_ChUwSY0g@TFNP)1zpOjZx(C``k5@#>wSiI*?+ zhxr4mJPKzJJ#tIangxlKQCAFSoF>y!Fb`s)1eCF<-dtt@b1kMJ2Hk{{hHb8sX{#YS z6|8DrF@vPEn9Ck7DoD)PeZ%l@V=%qd%UdA6z&z+tES4Psn*q}h|B6cT#g)PI*h6mx ztIWV=$fy#_9KdD}iN3?X88(lH)%KIQ1QU2AglX{WOYbI^A7-Rc&T#~*@Cl|!JZ;uX zZ9dw_D|$pTAQ+sPlHRaeHxRM|_beJq{;6L@{(G)QoEJ=kv%9NSiELyY$bUA-o?+F2 z{u!)Q#W+%8M3O-yDpp;jeuh1hY@cL-SisZSt{$;uZ9+*I({RWA_CfVVMi95#Fhtv1 zB7?pAJ(rwb9xE4lmd-MM#gL|_ykvXGk!)i#m+YIg6voeO<6AP{5y3pDjkktXxP~HO z?6=MocrBEF9a38$aIG*6>+|vzSlzdic#XolwAJ_1S?JP8k~aK;Y&6ecgO|)Ej`w!S zm%<^=OxjFhwel|1YVW0*Y(k02{Equh4XbcXM52A>Y?mF61NZ^o1cAVB0n?InXKVwO zu+o=@On9cHDjBSyO&~c{xd{1sJDs&!7*0MmekFgOkpl6fCXyd#tcWDl$SlIRgD)@Z z^FqTaToaMlA8o(Pw3|VhOoaUvo z!1(cG_oE7A`@|I1;#@ycw2TAPs^*7JYTqi|c~rPH$0}SCk!YG4ZE^`5#0QL)1OmSW zOv6aMX_@NV(7^v$VaM@r86fJ^fkTvBwe%ocHm9=*st;+t*%4|L;joCce5UZTv5h%a zo&T85`d9TJ=Q3#lB6eR>_4SNaJSn!NK=7P&W)bN|O3dg+Fby%Ve=ao1OY887@f`)? zv=QRCW!51nkTD(8;1S>CJ^OX7G5=PNaI9)KKb=Y8Ey#+}J_QJ+aFl9vuFg9h>mm@l zKc}-o&FT}mnlHgL+zp?5Rqb=Zj3>kmOMtnmIEt8fiPBJ8_jvVByRTbAr85V%&DhTYm2nVoriPP6tH z!xto_Gx<%XoIO2~d_I)UMxA~mTm1|p$zdt1SSeNZk!L}z+TUo(+GL;At}GeDu?p8j zB+ef7O0%!70y$RUnux^mdZ}rv7VXlKEhY;DehZkEq-#m> ztZRE4Z9>^le)}4QN9B!qFS!Zi_z z+a(8^mM-t3b@L7u2>cc>4fl#H9MzL+Mx@jQk6ip)IRCZxyL9#>V3DCzwK#ZJo)uTI z3uf=tgEmHvRTpbzF!zT$Q@Z%a5s`TFWrwy;s9Fnk{)PnA^rdBhSiEBnN)PHewJ3FQe8ScPjS5|w(_ zR2Sx+A&F_>0)cCVY1qHwHQ9lF^OUC@1Gy5F&T4Git=3DLO>%2zu;Z;`)kWsfBok)p zVP8yYS4Hpb^*7dIKi9=zX$0}SC zk(gCjHZ?WuRX)c|5(xYjFbz=(LR?w!3Um6r!vJ2V9Q5!z71^>~ z$<=@qcKbpd_8mr4h!yswB&&1Zf|lOUpJNrSiAb#Pw9_=>%45YW!cQRZTfj8z!>zDm z-4E5Ki@tT_6GmjP%CrS5Q^kjrc+c6J;Wq5-TVHZ$ObUAzMp+3L52)3usIp8QQioof z(~)Bpu8BzWe-o@awkb)k*Xkn>_$^=>_GH!vs;OlR^meKp$G)W_jz5B5z^$94$z0RkzVLsy_-)BX#XGJ>8xjvjlZ>mo+!0KCjc_Q0+ zL$_oq%3?1%M})a2i?3#cDZGyygDR> z^{G3T9g5K{z-~t> zToaKfy!=&~JU@U&rX~smehZj}*?Ha$)oQ4bt_g)3v8Z%>x^Vq&I;-U!%Z5jkgjyZ= ze1~OQgwgiwCc~;@Ug_+CeH<$nkYEsrOg2Wfzhk5~GT#V3kl2e6(~@LW^tI{dk ztCCw)V2M)`$d(dj1&Fi7nQ8=IgV&w5r(qTNdoakONAx^;Vi^H#mZ+~k8o9aWa)Efb zw>DdOKc48>{V)x&EE?FepGS?{$0=1Hu2j0Cx@?Rmf0RNT(~`8T_*}Kh7qG^jEK0?y zpPx%J$WlngL6$<1@EaPe`amyvS1C#$z(YiZ+=;{qawlRMvhWqYp|*Nva`D*PLTolIG8OY3lsj$ZgM+cg3pavGMBBe(}T-@=uCHmyfs9K~Len zTJ8oHOuXM$RQ2BzN5VoZIHuvA*WDVX<9{IAIGOK?Rhv6EQulbplWRo-HIZ0w#7-sf zw2 zsfz`|@#`YP`E_x`GsS{q8g9|GsFR}Cs#D?uSF9>Ca)Y50l;H`vMMc7{td%?ha#fGN zK3^baPpKwHrNoh-p%xGm{eQG1HHxlmI16PoJR9MPRqpX_vQyW1@?&j)CK7UFb5aAo zs4XR$2?TgV%iw`cbPsGy!@72Gvf(@Qs}gsPxCpALOXSys<4JkQ&@2+soA%1!<;{H# zyl}<@oQBG9TY>1e72FXGcP+bpGBklQp4SXc#j2r2GvzfwaOW8^G>e35vO->_7W$Da4RPo{C(Dsu+ zRFN^^^K~{E;ya(Lfvm%r2H&WfSLGT{jC^dd3Ib8JSRCoLe?I91S%)zV-XcDGHAzD-n8G8SH}G5w^U3^(&3bqhJ`Tt zoGAq`v_X!FX-TR#`hIH;^ehi>l0H?Q2|x&%Cg^mdMdb_PQC_aUFa z{_G)dV5x3N&m^6Sgs#=eiF#*4;d(aWRR+xryH!xj34$rZ*W`sb%ljoJ8 z*B#T6RHm_`JnMszFFiL)Aj+C=*8P@9|AMfW11hj$f7f!UR zXH`r?-z_!BR27KMJ7NW5<lS`Uhr%M#~lmgehX{e>K50WCt!ZPZ<~) z$cJ^Z)7$pHvm#93cL?{R&R-@qiiYzV8F9kt(rIbie{UDl;DwalQQ7(?m~Wd|Qy}nq z0MpF#iT`q(a^R?r4{-?`pPFbz3b*R4@6s^Pqh;iN$1f2n#e!8DZN^^aW6JDfjpc`Ojn zm;NgQ(~z+cf<+b?7s{vIEtP*mGVfjC?;O*RmrPxk;ss;LN!u3&oZAJr0bc2WAM%`$ zr07B;cdF$gV?u9d{rk{IQB1=rK-o@m;crH6a<>qO{Jx}*qL_vquhyFk9x#dyfA~eH zReldohfx&M@I~ECceR7(C^7bpK;(Z#`Y4KNh{jG*({xM!(5aLbTEj%1?eNX9hW&1gG^ZJc7{g%%AHYIQO(pXgb+F%7$% zZ?e^eU}Z#|I3*CCpXV^h6;AYA;h2`BfrV{Y;29(Ddgp*Zl!L4{ud9RY0~yRQElGtM zpU7Knv-slzfmiXEhA18uFO|2AeEIkHV!y&W2$+Vu=lz> z)szKK-nGWBG)(BZ=in}KUj8{u!^&&z7Nu_SDLksw5ET>HR>w3DD=f*U+eSWhS0xiB z@Hzq0kb~!on&t+zvRM7xfGwo_u~xUp@<&m9lz^DBY0FI;VD#xy^r=APkLP-uV;aur zuQXLJft~ni+XI2fpEL9}$FwB%E^5IR!E@|gb44KVyo716sr&WQqMHQs2Yags1fKga z4RbBry#D}eHQiqgKY2c(d&lPg{qM|aeizmSqe`1DY&0V{EBA%IN#rPG9~uDpCg83+ zNrpS`pY!qwpBx&>TdZ%Ycv}=TU=_q_Ao{&?{l>aTM7}cexn_gq!WY-dn9zHOersL7 zv5sljDFUL;H6JZG%8e4yMQCz%F;a7nu+%Jg)KpvZq#h+-H2H&W? zU?Yx_*r-d@306VW5CXA9R6VwcNHl^yhUst$UFdfMf#?Ng-1A3xUWjsvfyTBtkM^JdA8-xHwfLYV}Vd!v}0}S_XM+Fby#Qla0K?UZN%zkqK5o zY#9O(XiRzp8j&z#MqVubnTuC_7l8;^6-VYJwKV8)aWD;MkU%s$>two?;4Ba^P^*BN z738qEXBwvAHaQR{npZSA_ID;&1#x%?MC&o=(RxIpahj1c8!I&_+C?A=K^a9}ER?Tp zf2v^`Zf8Q9SKd=zo>ICQ!77L+L=HOp$a>Tvk=O!6&Fn{MZ5OR(zX@C0%_%8HmZ z$cuP_h~!H~zHY^AHDOnAf!GaSZQSvaWd49h8m8ft3@i+%kb`PM^Wp@n!g?o>S?*29 z-BJ$<5bfZ}gEm``f7(Blu__DpuIjC7OmgAIp;$(#ZO}_LI*_H$p9loRMIrjV!6tBS zfN8MdU|;F5!%B6@@Z$pUyjK!QET)hbb#paL!;Qn50er)Vg-Ywni)E~WNGe3XX{hHM z6^Yt2U?$iV!rs1IB@l2&T+bq!mzfmPl62%p7+<;TH~aWtx{Ou0yf=__HKs^^(mXF4 zZ6fUR6&YYoD!wjGuxe*c66x8+lMJnVR}+c0tJ={6*7f;;gGerGjIgN1y>o0hy$jz{cX#<0r&YAR_qErH$WU6A;B*qdHH zU6zlC{4Eg8PNa|!r+8LB^n!+I*u{zQrr(QN@r)MG2?CM(c-VvCvj=S`}BM=qTF$aCzEo@nRLLl24|PH!%yy_YMV#s&U?Qw!xZqwp-3H z@we4THncgWC8?*cH~l=tn#QIqXIQlh%5Zr$pG1u)NUZJeO@rL6sB5u50`a%ih~DOy zhPwdWylL}+R3+9C-;1( zoPD%UP~AI|LPnPvMjnqSNYtq2O{<#UQeyg@5s1gSHm>ia5MCxbp~Hi z(&}VrSamfkg*@x+N$lR{6d=0K>`a%I%Tgwfc_k3m=TgYVzO9I-maAbJcDBcKr4HHq zlxv&+XfrcY$?x$FBzbqPwk0c-ENWVbynFjV!!+zOM0cl8r0vSj^tXcQCzK&wu0k3$ zdRTyXu-b#FIf=^HmW4U~UDNecGEDg_x6XP5v8nz?OH#*kUbIO-SoMY7~c)Mp0 zew7^?KQ2K0yzNCV`3+Sz7>f&p59HMB?_-kpc7LK_8vILcdeLwGLzRh<#W_|jfilif zCdch4Nc6ttMaQ+Pt3+KXBM_6J4AwhTHjQ|yVH)m=X;Wx{3teOgC^cXIw^~M$?yjyzH zqMMGg@Ym%8Vic6|uy?4cL3?0Yl1Aou(d;wF*o9%%9IFOEdsKWMt_DMUh(tAL!8a}H zYK4!N5eX>6;A2wteuZh+Z--vu-=(e=0KH@YQZ0fqvME#Jp?`@TYj~UbwkH z{JfS*E;g;iO2c=KX~;KW;Yq!ICTeC0mK>`hp^T`zRoFK8&PBp?Rd;G`*s8Tkd#7O{ z8b;9tgB{oc7*{Y2Q3M}#r6bJ`Xg$0A(y(eYj0O{WwPOA-UWr7aRZse{n5GpwcvB!E zE~JtxW8GOx7)3D+anId)(I@towGlmzXjt_U-frhdgIUW4x3yWBDdgfPPj>EI4vg*l zFM89A#W%HWcTZ|qSf2|FgxmX~u?SpB^yA=FTsXk*Uo!G9m za32`o+nrn_os3yLk3?2G3s3&TCrLTAd?GEisfTd8w{bWp!;43gRQn5>NUWaOS*dA1 zkv5K4CJ+_6rju0gBK}?El7?wXsy6eWa{g>D>hb8daJv`Z!o7cllUf&zB=OW0sMW{q zmzDm9y{K_XmT*_M_A5>bc|zBj(>Mghjem!@JO|}h~vAu_)hKe$((c>*pDopspk#X!Vf7gsx+t7$JXUoRc<#YHv-xb zheC@I0kFuhg9f*UT2~*Wr6`GjchZRc9JAuDAxZit4vVDN(Nv|9M_ zZ!Qp<_d}x9uf%rZDShx)xa#J`ux81^^$$U2yhL`C`2MihIy7I z65Y+NE7Pxg(k*MQ2m~GtFbyZ}pROn+oxx&qx+;trXQ2#gm`+^yHBBVGjlHByY}b*V ztN2AA@aThSJsa&gW$(U@H0$>_4Xdt08BR81NQr*gnn-l`d`@vQxzK7}WjH4Ah=Xa! zOZM=lvSz+BjaplRW0iMTl|)Y%K)#;1rHMrD$J@$~UybPy@9F}9$0$rg{=qXhlz)7h zP^V!vI9C1BO(i?ZbR=(fmQ^spBQJSJiq?)DA1s61<1g*vWj&ar9_ zlu==l9eM7WtBJ&=;0wxXUrSnKp_@Rsxu%o2kL8F*g$Ej@VRpWMP6_g}r0xH>aje<_ zWmG;~o=DRQ5>uL$Oa!twWB|;jstDs;y8) zvw`pBE?$oc5JkIRR-%{fR(kC45ePhHZw6wm})AvcDNBhdk9pqGi2IWwu#QQbijr5Oodd zq+iqV`+v84s$p7^9R8eB`pBN7kYNnRs+~}V@nz5bl@1gn#(g@cl(Xx}n6pT%ftj<_ z!w)8X=EO8a=B}2hyw37q5ywVztlA7^gk^s->CYh&-MU>;nw_t%wd>(85MSar8FgZ+ znga7Vrs1ysGZ^6lDr;rF`Ejf|1Z7m}J40pA9wHG@`j&F_S%?<9Ww1cpp25i!=YP~S zU|C=qb`64VD#WDYWwfQQ&4JsWj&;Cp;Nc_${2a%>M`O`c9jtu!kCfIN$RO;^Sz^6aI1IShX9Y!yJJxVwj)rN7 znmzTJ(riFw{yE8>V^u1Y0pl)v4dbpzJWa_~hKD!d#U57|h>X#k)b8Dn&5yjLVH&*j z0`Dllq8syD>#B3C`a7O8ef|)Mb5^&NjWJF<^L#0R*b7$pnZYBOZiQnSZf$)zrt)4yQ3w8J=~uz#)aO^( zFrDSk=lSJH(&OV<%DRqT{8h6ofxz}Brs4MTf$NI*G*50EpCwqSdQB`y1WO0IL?kkU zuPXnn>BA#W9~1~|?_wHG_3NBd3~l=H-QV|XSak`?0Q-vR_LWHN8+=aLzkVqH&?s6U zu#Jmph97_ApWu4Ji!va3T13eh+(>&C=wPuq{K@0bhe`l-FhmWVf!50 z(fD)#Zf#w(qoI>s==q!shE@1PKqP`P?P$~8PBgn$ZNWarmN%v)DI19FT~4$y5Lksz z1VkbMYLy!8NFN>-YQJ)q+Xw`10wC{fGhiz z(>HB6R^gKkkw}ZSqg~d-DVG-63Iw*JF)c~Sp>{NQZJe@goh`>Ie6k@Dkq~=sh+kJ_ zLD!Z7f$eBaLtJMlW7>$WO7AW$IacA54Ut$2@uD7<{Y-36Itv80yfF=~U_lTO&-yb7 zJ?qS|3ZHC97qsTin303ZHC}S^Uw6j29I~voFK{DKq9xL{loj>8su?nAT zh(t4Z^8O>bYPX;TF@f!9OhewKU>Ms+b=AgpYss++pKOT44|tC9TjR9swYCC*EpJRq z(g&zjxh-*8c_6R~pMQwNW_Y`$9`Dyo@I_$)+tHYYaTog4gXjA--#a#WEtqfJ<8um; z=(x#_j?d20%KfM!5ZI2!G~5hZXGhoF&C&}0s=~1fpKOT4-G_FxM9ELuXNOV(f$eBa z!)oHT9c@zilXk|b6vrxjvLO;v?d@r1onpMH=P$uN$96QPArit0I~uU17-whxn+@`; zdwdom67!&!TpwG3yMNEkpFi>leLl~(qcIKf^kF{Vdd!*+DxI4*JLjwLS%^rqp4OZi ze^uupbB+rHwxcl(zELor@1Ibe@91+}u(t7uiAd~$`TXHD8=lj8yFg$&8q<>G*WH22 zb!~XrrvF+Q`PM!5LJ^7I&zjSUu1)!-_HlX7kxyVd8q+YAe7B?Xoou0^8A;hKP$`k+~&0@|+Qa1#A1S-InK5BofX*%-H3`=YVC2e;3=) zn1)y{U?;ZN?ZhAU{MUNTx9=q7Kyb@ds6o+Ot}?yQ}C?8wxQ@J^Jttq?dEn_ zd-C{&a3YOIPVwA%{!>D8YgOQ-EA7zmNiH5gu%8@Q;d3q$vN@D)v6VF3YPgr+GbD&7 z^Q}1jHns~rbU#rzuf=he@o5dLYd6~{BYelu;1pFjmB9o)p@GJX(bwUS)$Eq)e+88aeQKYIv`0mrVn8k zmY1c6Pxs(hh4=SGVyTaTo_~2*S$em;K;Zbqn1%>{kiE5;;ghmw&rsnM026qxA5P*j zENH^&{fbn!vv9(TRhWj^pjLO~MkP&Ik~>m31;FRSc&{H$k)2D^^xfH{VvU}{2``QW zjCa)`>s!J)^~8QJQgN-3V-?;P7l|YyQ~f4KfYDYUa3o+%gB3o1o!TzhiA*KH{UXFY#_@?U4Y8x=6<0QY>&;CqiVAz-n83T-(0BWlp!J-( z@Cj=Y1)m8V2^jAb!@g+!j*6@IL>?Om-aE*%0uy+57@oYw1pdK7RhlHnBwPJSAzL>r zV7DeNPRY8#NKn7oENo!m6zq);K6i~L@KYyD%D_QOo$!A!aWb2cMZIRT*h;!x64ZK= z)-iAjO+8abh!>3G`nGPTu?b+wQhvt(tgI+)XjbPO^Z_X+{m`B{54YEjlPhX~m#ZRUt zgSCPQ98(z6;KTBMr}p~zBpx-f2l0m|EHB41|6#*Y&D}WbZyv|e6TcX66flT#W4Tea zxn|_u>U@x~3daW%i66t(YEz@8@MRW z37h00r&E~QqC|2vu7Ui1T`HT}D~>GuF&|={P21UlA8t~MUK?6i!K#!)scaV9`xq2P z3lPS>eYpCzI4uueW|(l8m&zK1CX%>_3{j2=if zpGskkw1K4XFiJv_Q(1C}cI3sE-Vouh>H-gbgJlFDvO7*B?Ot4}ZuQGw0d@`N3yv|6(*sqNJi7Fv$7Q>KAr#F-S< z{7((G`EUUFk($b?E^uaUg@-_`zBcN{gD3o>eUJI7U{#Mxsmu)`7tHuPxd3sca!;=9 zPSku}eHVy>8&jE2Lvz-zNd&<(tPLW%XyeKT&~lbO3hsS4613P8+u6_5S_e&`#d>%s zSe4b0vklXt3FEP{NX#A;raiNtKwFNUClEMRHKrxW=SR!tqQZr z?inevNc`HrP`fbMpVqV5DiAn!G^Sy#7T;cTS4Yz;9a0pmx&mMA9LP$tqQ^s7BzC(m z)rM>yO5KKJ2n3F9jcGWkHt(%H{56FBzIj){s#Fv~TO_8~PSK)D51|w5-&U}yJ>hJ* z{dDj$EkZ=1^Ssg8=i0sLNn%DZfumbv8t%9ssIR@-(1+eJSW>Lw&YUHm_9qip*C8Tt zy=9y>&f1gSQws|Oj=7C#utg)OHtJ>v+CZ*Gu?oi;6bZk(&RVU{9q8oc)hJetX~&t% z&YtA^GZ!Kf9uwASH;OycYu9QD1de-+X-RtCtE^UJbPJkj-hyHkj(aT3&CA z$0HTKAaLAkOhfwf9feu?(&{wMrwhd@9G_Yw znlGEBc@3>jzr;|ARUH)0241L75>EOOk&s$PX>O;BLF;)41dgDMX-TTot-e;PS25bW zOfQO6$Do&-eN%!=n>US!#H{Vhw6phrDjzF%7YH2D8q<=*S`N_m4Z5#5{~S!Q3P;cu z38(X|w8WHLr4t!Ov1%0bl0J*>$?nY~h)CoP+NF&crzu~i4H5_((Hhf`53-z{R;}7@ zrP1ec6svFqZIQSb+FR?^Xpb^o8$+=Q92Qu}ye)E>MRSNqbR4)&>svBRSyzC-5v?%| zo*c<@lz~lJD5LIAp;(0@Xp2Mzr(o@m?S zN})&71OmtP#x$(9t5?(J94(^w9|@*dl>)uwee;8cjPY?qBr=yR(8jjPAS1~%fxt0E zF%3QO#&B)dhEgOlB#2@aj;$>c6^qu@PP!eFJr0J#{?Gs7caMW!GRUr|sqDEpA`&0n z*J_(AyRh^xQv?D>&BnAO`8agaDn#sNkDCTltin;cMdD^!4=ttK4)$tw5XGw6&`WNP zsi7_jizOn#$F9}tJap7jYEKjh95ox$aJTQsUS)9~TV-{`I3dC~j?yg>z5fJg+YN0r zhoe&|R<(g%lKwkZ4VoHFMB<8Buoin}zSeg2c!9uCvoQ^EKMpq0PCQwvDJhdER-J-g za_Yy2qi%Bj;=>)Gg(<}zvo#VQ;%TO@qnI%!RV z&T4nY`cteL3BBZF-#@BZ-4G%Y_qT4>65Q`-frt7C1di*CX|P52xoVSV{?d}B_oG;a zqh^alL&;MsKkA28>!%OJD*a0>GQBGETQ`=7#8217+K9$w__^I31p>$Q#x!`hRoJOq zeP4nujc+f+^2V{lMZ)JWF0ZGf~-I%gs@^@qrD+DjbV zCL$5XHfbL_^yJf4y;3lNBY|TYTCiSqS}sH8MGh}gunI@!7KzNwGqovYATP&&7YbJC zcEawj;cV-nH?l}f9~`Q=ZuR3ImZl2?jvbC^*vnYZK-*J&46n13DOhzJdP!8r*{oes zvMds0^g^xt))BngnwX2&(zL(4R#9=gkDOE6mS9F+${ay2Wn%Z(0b=jvVST!BWXnrq- zTrCtYi-g_0yPE%!f%NT!SptDqbeM(+O|Nsbgo6X=ii5KhtO|xQ8U)NC_F-wVNVI8j zS3BRo4~=-SO(5|44AYQX_GgZE*tZY8S9rUERRK^&P}N9MeAi=HB-+8dnjGax2dq6O z5O{rtX-V4n>Yg^Gl_&kM_N;D`wr~NA2ir$7O0+_&SCrrbRaN=Fde@~m*?7JeBXhX3|uSo^}QsmI@Kq3--2E%hi zUQqUK@(>7pl*nI4VOo+Z{vTUs9T!#e{qZYyVxgkgm?))y$j%IQB6b&w?XDfz0SW?w z-PoO|#LC_oYksleDkM`bkgM>466=< zjW*SH=^lTAo7j*&MHw^a0jJ;l(+b`LBm&PlFby%U6A$>JyaVX&S_2qX9faTgd9J(8 zLxdBVNNRJRKkfOIxOWJY2t0$pw4!u}_p!6}H}d%XV3t!=XLy{??u2} zO(-~2BJg}bBdj!>6&7`$lMeB^LAs%E_Q2nH4eZ`hV;&StI;C4|w(*x(4)0^fpbhG0 z!w`wU-aV#a^&H-Z?%sNJZRa5@rz*~~vT5w|2qF`6;C(zdx$}O910(`__ZnfPp}&In z@pXwi&%Z5zVU_ltJLQfvJ-HiZw(*y+Yj>a5xVnf3?CB#B*jL9itgsw?z;|?5#H$SM z!>}qAY#fPCF$LENG1n`rJveiq?*l$2!pLtf?<^76^Tsqp`=GyyeqiMD6FW1k(w-#g zkD^A#&LlGN2i`{o`{#VIODl=Mo;Rl9^b2?&(;hwJ?JKr2*LJJ74ZCL54y7E_Du49m zd|2%%N-gNGJXaPFhiZ6B1oopb4J-8UK0+515aTL(GpvdO8@4SxRR0luh)gVk{_1_8 zgV5kin0{mNBO~R#p~6#C{}4t zqEqLnr5AqG$;4xLALkc$6SM!>ClT2H#B^5sm{Gr*Sa^LO#VV~IY#*~gZ6BPdlZhYD zK9UUmMAEQn5`n!;Ov7FrcpnY7_Y;k z?~7?g8Ncj4KVE;ZDD7QV@{qNU|B_)ox`eR^jNIO!PbECUo#6M0>Zc5`q0sOhfO})LjhE=gK_dJ5#JOEjOy2 zzJ`*L+teJfyAcK5MZW4zEa=SwiNO9RrlFSTT*UNx^_gweaEeu1QjKaMuV7Lj{*_K9 z28?nMQ4MRsdi!>X!2Tzu6{SZdcTs9U4d!!Z6U8dWB}TPIz$~)gwlI;2KJDE_y9y30 z&z|EFf&EWR!*{}dZo*DDFb8^)Vik@L%0$X*SCKHk1lt__L?W>NiD|gw@S3wwca~)N z3csLOh2xGgQD~X7Xuc;e+gCX^!-V#?)&Ima?7zzED%Stb!`|M_WhSgD96yzb$S_wC zx%?F^w9Hl_u>Xl^@DmTXiM+`#Y5c5W46DLd8`aDE>ym%z$Q;qv>bKlP@1`jKgI&_-md zzl&-3M)8-6=yPj3jT};wVO8_vMzu)A=emCTf{9Grp5`LThRvmG&pJzl)<;?WT}(so zQ_)3aESXEIRd-=n6`NvILqqrI%Ckj8CZ;WM5f8UDq@KqcN(A;lF|8=Gn!AZyWjttz zZ3Bi?BR4`cyi9N1zik&2nGh@8M0Kw-Bq82YBCyAbY502JiJK@NdxlgTkwsX&)M~4Y z>X3RypY%!5L?*8P<0fujTB564t&!P=mC(i|tG|nBMR|A0Rk$|`)hVUD8CD%TWK`XD z7DzgLESktfxn8cK&(|61&!>$fLZhwzC#K;mp&8Dib-Q4-`s&7J!m7G_!>AtpSk-jg zDT>I%&M0T`a9|0(E7nUQv>IdeKQRsW0&H^?M<*5K%N}`{Yl&4AyT_=`d=+Kt);fa7 zL_j$=(XL&8Ucuj0CcuW(-^DbXPI=o+EDh?*(+;>W?4^3HG^)QQrkciXSV&|d;DwuT zT(X?+9bH=@w0v0oPfSA_9PTFWH(9}*Q)`=_%BsS<6J#Q@sGB%F-N;*isVouL|HL$` zw-&s7kFQ--Mk28PiD~V$P#00Y+Z{gsogKp}yn90? zUiEbq6~#|Jw|fDJ(CU@d|HL%x3t#UhI!FHCZH@WOwZy90xyGpOF5OXmZEBNa??>Pz zH_@dtgtx4m+G12M6oqjC|0dhjjH{I$*Ns=St1j&_qvGSjOt>~w?h)4 z<-_XlVj9lneC8~suXYq4Xsr3Etg4S0Jk`eit4=1yv~dxeU(^$D%c4YRJ*w5; z#WZ|nTFXr&6?GC9o`zGbnzGrbz9hEG2;?B?A z#L3ET!ag*Mu&P!=8~i#tQtj7brcNeSq`QedJ3WNm^$+GX3oC&=R!qZeq7KxOE}o*r zhxg_gmengB0)0tuIJZ`pp6MeKw`RDCLM^?;;NYJ+{JWc@j;Wu|M5z<{I~Xwy=a;N% zF3Mc1&ME}m);0exQ9ZD432|ZS(`%bPZn)$b6!_MglCa?fYv|;sO0jP)c6M+Sqq~)q z2&}?+g57P??(w~ohqCq~@9FR!LA)-GX8>^L%P4nICDey%#N#M!5GW#Pq=4eS-m zM8U!yqDub~EPnS5idA@5piDF`+5_gB2kF%XHz@WX@y454n< zgNaOd4(TSYJ)A{L%=$$!fxSsg!`J)4OgZs`)DBN*w%l3E1d; zsfQ?fe6()!_JWcP>>J8N+*F-Nbqb z+j@$~PmX-IV#Ba^hgFz{v!e~wM4iY*JglcT!zxVw_aIRvAs zt^AE*754OGVpzDlXff~rZ#k+e!z#SbRwjxp>@MEq;oRj?D#czA-pecdaD8^y5@~J) zMQUIHX~!?7OF%n!oZMI4U64UO99s4k2j8FL#;FG-8`wjViI2nUh^o|H)NpuCvFgy3 zMD^q0Nvh|GibN(B7w;}+EqKN+cH1No*h9iJj8Q+EiB%Jd3ttvPv8w#}M0NbNV0Fc_ zk2;x{bi1u+99U4a8@rrh6{clxsqC#Tf_2F&7HsZLv5$jknb=X^O}GrJFBbQjE!n_y zSEwb0zlN)g7j1(v>iUabVs4LI;?lSh6#F<>g=v@xFLxA+7cuedel3bsn8qFltdSk+ zDRz&}ClU(95v;;qhD zjuS%}Rt2{2L#pnCJ!EBb65)-u@I^fmc$XUkCF0`iAkyJu5V_y*563jjaU!bmLUM>|!LvXQ*RhHqgc?I>Pqd zf$vyGD+Y03RXE?bcBVvNm3-p+@Sz5gx8gS4-B!maK8LzH{O)X4*z~%_vmB>puYRu= zB{NRx+RQdle4aKY&H;UC=uXeU2JM8{#b5No^Za&G`CysAD*5zpHO?R|eG8>OH%*0; z%>SN&%;0xBPwb*z7?P3W1m)Ua_2Tj4NP50_5XIlPV&WOl#YXGYPv)|!1*O~M#56kn zU4%qnm3*!<{ZB6nl{C_T*~^IbyZPhis3pY(>3)locT{qqO0eoQoYZGtvy*a@t_>KwLhH;5OY_A;8`R`~l2duw5HV4M) z3mmI3ttdy~4U$fY+%I9XL|~PC-$W<4t+3+kqr8OQLy5pD`Syt3>kVS|=7W6FvUd`J zRfpkeU(w0r;JwRGRxJbcV%yL|JWug56sKT9zCEIUyg_Vzw4MK1TU{csYA@K>esw7E zJ9`amlp3TL8|Lodu`db5D*Vm4Ow2!M5PzPm;g1ga(F^cfr6+cQHl4w-3e)f{@_4=Q ztF@MoKQ)Nr6x`$BUxNK55e6}MTR6W{eiFrf6josxcD)?Yi{kTp^NUgIDDDSwk1F5n z;5^$PZr_Hzulv?Y1XewQ{FQH(mwfyF5X#DSwq6V;p1e!uPKr}7A>Zt9bdy1N6m{ge zn(dGXtXc^+LNm|n)Mt;uh8V3EEmT`xDkzrX6p4Uy@2&Sjz=^#F3?e=At?JnJphV#N zA2xxF20y}dZT+5tjh*B4qW#5->QC21idFbF2bp-Z(jbQIk5<osWcfUhkAG9S`putMHu$GNFTdHPF_P)^3qquT-s$ zVil(0eaz5{wf#KlI-6Y-r{FscEOpxaONz2#hC$T5-+_u_YiTnW)t2k3skgxw!75C{ zw;8c|!KU}7UDmIoI0cWE_?MvWHZzE~`KHiHJc8o!6{|1}aRcZ}s+V6&w>%w0@feQ1 z0eoTw?7%)`5RY%Kp{=-|L|~QHcWt{mRL$xWOG2NRF>41kd?FO5U_w6qVlni)X%Dy4 zduyso1XgK1_-i^@&Fb44+u`dUIzA8;0^woEj(IQ()IndA|Cq;_zP+54Zyl6+yFjm{U+UrM;=}{ z1ryP?VEe93h}y+33ij{*%A74){q{O`GnOP^0;>iB;Z!kL4S!J#=25?aSpLJNab`X$ z5m+VXBMFFHb~>L>$H#Fv1rsxGtK{42dFuRL-N43AAmZ}%ZCrKOrFcwW)mtE%&Yh#) z4~hih4-i8f6=?*vd}o3f{AfZOUS{=s`~mI*wBda&sQgW zbXX}7ScPk-cJ9R-K{GlhZ1-3Zhf^>y0&KY69j*o+&IM}#8eu3u!TZkJff9jLT8UWw z>#V1moOUYy)EI*~=hhTV3%N#5={1O7Z_uXnQ5m<%Wf7VkKURlFPY0(6n zf{BmtKBfdUQ$OfDEH*av>tK8|&sHL^3im5nHg>aLPwM1YQ?oqRzs_c+P#!~+##N!l9 z?1QIzv#*$X#yP-}bN||Xjd7kPiNLBxK#W=O)3l}NC=2o9pN)x4N~B5zR^hQE>#1tI z$m=~bZBjf=!Nh#9QDXc})0<5bEH>iTHu9Q2VWC7|6&@e6N;jb73Gcwq%oC?zVi1&W zdAp;gTo0#NY_#vKc)JgXZ-@!3$^hch_VFg4Q*$ju=X>?Nn-^&*5m<$NiL9J|`_Q0K zNaL}Yf&=?UvCspAVDIq3VS$NId7A?!nkY0%XplEiRVzd zJBGx19d8{1Hnf^JA=3VTjj{nhl=4~%S0;{=?7i8s*i+O>)Dd8lYMw0yM6 zv)KDc@x*vcU{yFgRnWX*y0zu3Ip62BH*rkQBNBmC+I#xzi)uEiULNedt)@d9PQk=T zAf9E0=w|V4z+UWvde zJd??KAGJ&cjA;`e#p4uAe1Z329A{7LfAj(yTF!4N@8auLzbp}0H5=;g-<2XQ9}(&r z?|?3bIGlost&oogAx3(q?TDi;akz@m}w)MN0%$ zX`aE~H2}>o37kY4i^yJ{I0X}tKV)09gw2$=u^{$@>Ca@|Kh_N9-#J6h_ z5L!MKWt1?kx|%K#STzR->pDu-`{>=W$g%VbgOB1AO!NlA7&MpUPM%@0@$^M^qqGU@kh(REG%)68Xd9+^fmPV|g{K;-7f$Vu(ORE6n92ro(lTg7smf(h&gDN6H0ux6Q1j0QA2#BmBHoM5fS zzo}~a<+2E#YN(q*gtSa2{PPisz$)wq!PyCC^dd7?8hN=cp5qiu+=rUD{mm?sXT)N# z;ZPao&L`)P5)F+KfmPTKQWU@2deLvsR5D5&<2VHq3&BPgrkGM)v}m}#ph0y0aX{Cn ztVtrU3j0BD8Y0Y{pN`$3`x0m3I0X}_P*x}V9`yXL*ix|Z=!0I|y5HP%<+My-751DU zQXQxlJA8JTu5}X}r(mKS)RF?Oif(3IEgv7Dta>_^Q+H$@lL)NBo)esH*i|q39GuI$ z&Wq%DL@p0CJfH*2n|=fmJc=qx-_LsS&}KS+QYw<;6imFioJb;vcOb16b%3Yp@?9_L z^jgIC1kRBNtit0i+zYTzFK(WX;Eva3bDV;SM=6QqV7UMi?b8@+bS!TWXND}}1GkKj z2&}^6F5Eb^9pVQ4xAW;6bo~4!cvI)*5t~c72p$J(UV&S#GbWPOWh;Y?(#!N>{k`q{ zi=U3;6inc87tTGeXMj6v*6|A8I!Odp$xr3r4mFV;;c3BlRXkdbhTQI*6h=lQoz~$I z4pu)}8N|ZFhxxGBdn!)B#31Ms70*c0K2GaJ8^r6y%Z)~U!2O9%tOL)3MOuWjj{J8 zs&h+d_3Gah22p&THUearTUc8>LmTqe}nBx>odm!I4oCfmL{21J2}F1^K8PNrPPHaI6}ABaxhH+d=KKumh0^=V=C!uk~E& z@g;=g6%VY!G@My8OfRZN&7wVAqBu^$V=ewAMe%K55R1Ewq+-TW$p$8hqH$hPMn>vI z;GJpe5o+SN@56oK1?Z{Ezn-OQv`8CqhK@Ig?#|Kbz6t%r(og( zXNa8Gq}gP3& z2l%Fp($e^W`(6A?aLRwUL6o`{&qJODOZ_hH)o^d8D8WSxEc9{`zi{%Q3GYM3dyk9U zR@Fa#A>?%U3YdQkscc{$MnnAk$Ws$mrQcIkN7H-~b-R*ICQhd5*?panHz~4N#RT4s zi)lF7$kxDmCneF5w$DsnV7-zboQK+cP2x|m;h8jF?fIyZ4)1}6?>RjTOrJlA{#X63 z39InVBbj)4N6%*cOr((^n^a8TT~C;XU19AEY~_e}UU19~6+bV|$5MF0^)a)EzSIU7 z)ouIfaj@~LXESn^YHQ&urs~EH9aP zb|~1m*j&$g8;9~cDQh@ZVH(?p)21I7*!44&d3*5V@NeOL!8gH1yJIJGJ&J2RTnjHf zYiZMntL1ictim+54SObD7+CEWH`V@U4|4olc#rTUu<^}9uXBHHUUjYt`AE*k7oI!H zu?o}JHhjC37fxW?(pw$m7sv5$;oZNfVB<-bjXoatwb9^Nc|DswV7oeFsflA1rm<}} zt>?GFd{TPPc?lf<7T)En{rlrC8=s;p0fZNna~X9iY1un*bs zHqLCr`dfI%@5QXLGG&!jw^DlMdh&s;+reaxRrpD;ZAEeZVPKDE-6Z|SALRJA@Lpc6 zq}v}mVd`mq=QE+KK0Mw+Y9*LBR$&_3hCcC=f%P9-nf{!=-Tcn2zlHbgT560s%UpNw z*449)>+;cq>yL7*!cT&2!)jEjfvtG%Pb0>!w$@$qZ{a<{mYT0-wZU`s^z3_kZ%Tjc z;#h^B1lxu^ET;_2vB`A$v;RVC8#MnG-c@XA!D@=RFImt;&rbUcr8SGJP0B`)Mxg`Wi520wARfz3?WM7yo` zw)TnU-@^NXwH~!+>9OhobKf31R?m9E&FnEh136aVC&9L%tVSBxn05QOF0WZ8I>Yo3|F zDLILS_4=xLAKkFnsH-&me}qO`Rk-G7<$Q~?qnW@d|BHx(+i$ao+4Nq5_7^6se`_k- zg0l$cf^QS1&YJIzQ!w!rdeOtRYN`=+?pthBxfPZ0aHdRP74C_$Y`FJ|Ha`_k$w};B zdDU&-v^{s)J3rLJHo?Bv)7_ZR{O=;*^}k0+<#3?GrDy3u$y<_5+E~Xsb%= zQUA`>G#gI7i_K4kQ~no`)wgSPcVqj1{~uwcHI+6p{GCB+#P{j%%mhx!Nq`4H{*F<> zYleDjWrYdLh+|ga*=tri-=8todsi{r`Zy&g0b?!68fzV3bPo7wZ}Qr5?jR;CBd1v< zuK|<+A~~$QNqZ`s^1lep8-Oz))-_|_O4VT1#;nre6=A$`J9)t|;&myCq#XT}2s`Lb z`?Eov>{vmXk6=}Ub4HS@N;JtcFvUkE>OJ&lJDf_h*#T=L0F? zYY0{iyk;Z~CN3s7AGg%W#BSe?EMiOvHu>criNI^&n1+?@F&){OdT@T?^*;ow`hX3a zv*BbM?1YtxjR755moG)x*=lYS6L_Tv({QU*U`KZULs53PsvE_s4VR6?rA#Q%T|cRl z34hX&<$hX#73?umBJi3OrXh}VfUtaxE3-oT=TfX1wHwMRXg*2&{ZS_q`&xBp`HTOc zRea}2MB}|i;=5`(iJoIiFs&$Wel}yrLmkEDvu|{kJN49rHm4J-Lq0~AjaDDJpY_3U zZdg?-)R8r+U?;*Vtg4M5?PB#Y9)I@vc~?y8GQp9j0M!Fr_0aal5EEbJvw(6^>@eL{F%R;b8?uRJ}nG zk(g*CUZdx$cMg2iVH(aancke8y;MeQ3!F=_3P&?!qVDx>Y<{i(cso0p@P=B_WYu&v z3Tg?a6=mIU!n`XM6eC7oqO+j(z117k*lCW$?W&Qidfi{G(ykG~kqzjh!u{FfV;^`R ziKSSD;}kOC@ztNL_q)x*HvJ>sW4Y$6XZp#X$#`2h8h0VHXBtP|T>YFKnWP7@iEOsiZURpAl zU>c&~gF3P2J$CbZg+5TM!aE0KqJZ9y4Xe0>H#OvAnAmi~NLJIYCcEqN2&UoO^KJfY z)0@S7)$-g7tMEPmnW(bMpVhrGke@kONFqAiG?KnOlT5G9hZ0P~K7begY~PH5Jalv+ zhE;eUfJ{7l;?IsYsK!&z*h)k{u<>uV8K#O3kp$Ba8U5_fI@PMi0}t6Utit;MWTNFq ze^#>UDYZkJQW7x&Z1~^%ounj25lqASu1!Z)w$dr}y?ZH!Rd^qOOt>o@nZ8kO^}UUq zM2rL*hrVYXTD&TnU|LZ!QvKP<>o)4Gwss7w@IC;U*mcXFr47wZDtpO<_JkAe{r1TP z`M@-c=R5q_{pNW{zgbyNWmVxQnM@4c;?Lq^Pmyc!Svj{7eZj_)ZZmY1;eB9QQ6ew; zvvHM9k#5sUF|5K-GMRXB)t|ZgRfF%ZY$d`EY_#o}q%@2xGv zDjX$~i6!U!ng8N}G-7ojiO}fTO~2~)r_UpphFg@<{8`^w18MJNS%g)EqhvCX3{SPa z_+oltb#Ai_EAjohkz8{sOAarZOfU_%38wq8r%jg7)u;0^tin+;nRqs%6RTs`Ndt0! zq?niwz3B4(Zsh#rK!RyF(K@CbdpG4U&A9iQVik_7$wa|ho!N>BoVKigTOxwfj3jMT z8*+B5KfyG_IdgSoKE^9_=A{!9tKLKDHhtQk-1TWh@U9N<0KkV^boDkRH&ZB9;W(a5 zoQA%ALC<&eeEJcINJ)gJq6RW*sw2U)qFip@oL$_IhqWkvf?^ep56VQ_lik?Ct?#J4 zafL)+-v`q$ss%lvEv60>lbd-_DZ`IE`W6^m5Q zH4LIlxq2?8&)19*^R{)SSXFD5AcG2pss)NK$w9=;YE3JjoP$_-Cm)?$xw{zFpa8?fp%%&HZ2w{E=!D7y z({N%|Y8Y+&s)5+Myf&Lz={T8qwU=7m&5i7MlT2FPU}`fvKeB2Ze1hAzmwLZg1BhmP zoOYC6Ebl5BjH<@4s>FUl?oMi^9tm%ogGl)7LU#{y6z_FRBJPz*CeJI>Q(GGP6HF^g z^-8Pg%aikY{l%l$?cB%7T{X#c1$L8O|DH_J`VBEvnh-`R%@AaB(*#p&Rc%Ln)R!&r zh2DIAXUPbLRsTi9NvnG&m_oO0Yd=AO??Y?gILqX7WM!6{B*Id!NNcE9n1*@(pfyz2cnoXtwK;82 z<~T`gu#kvBt8{sw<|o^SlayliI?Mf>WKEAHP_Lf*)rB+kyxGkuJ`}5Z`6d&a@I~Zz zGR;BUF20U*tT~fybIvUh+jYsLP>~3d{OF_)rs0mNF{!lDp5em5^&8Ptg^NU}iJ-#m z&T^->T4~`)*tg_!@**vkcer@8@B_iB+igtbgKLDEH>sIUCboRLOj-P3QL=vriV58A zFb(@GOWmQx&jg5WHCs}wx&k(~FAh_8JX)fYiC!~r(KT24iAU>#B?7l|Oe;#=;i>do z@qwb>xp0bA*TBY(ry=U|%gH*KcxszU&&T%^UH2W82;3WB8onRwn@&qb^$=@T9imuu z18mrkxoTj?cRHDvt=ypc8y!T<#;X#6djm{E-1*B@`o+s%?DxDzbE;f?rl`Mi7bP;0 zGV(IL)vTqMT;`iZ;NC|gtTf!_(KeMHJp|W9{`o<%Dg#sv9Y?C+SE`zA{3X7APNid# zyhS&ETZReTM`0RbMUQULu;@l2a3kDugnF`$?M!5mp^y5xi3gF1y`S$;pWk)FnvM<< zf%_;-!#PDMH|h1Bb;XN-iVUmZ3|q3-wxzl`pgoa^*Nv~y!6ofQa%UHbzf!fUu+4kTR+G%MtWN=>LxXf1~nlw%(OFoxWmmeLY zok^ZegTMPYl|BX{Fw>V|6`b}*Y~xC+mG+F!L42rtf#xrDkB?o`K_V{w5k$0qZ;J0R zOFNq`n^u&fH!sqjZuj`Pr+y5p;IvRut?x&ZFWk5(6DvAhp{7;)dG9?vB?6BCn1*}| z$)G*+AK)jibZ0qLcLye#I&5B`osOSv59XXL?$9>drt`D?`%45K0W`u&gTH(37Om+w zorj+2&#(&4wj`x`Of}g)SY)>Gm#DV?2E7Nn!b&~}ln6ZHU>f%CHor_$$J=xFsY4l7 z!O4-tkntnQFfLL%fj`?G%u=geq(yUeQG4(a5|Q5r{GH};Zsk@)Xy-#_({P)|uT(nT zw}ZOZXC%X_Bv9=ta?fp)-{KrZ#`jcuw_X?W$4e$6VC4Mo@h2Z`b}_n4|H4(~%I+>73(^a=f3MTp2d3e?*OphPLz9EF zYmcnjj#bb;bXxn6iI&eV(%F;l(vZ>}%S zjy+oH!m!HH4-&24#r7b!otQ!M&#KD?KXZ@>K0*-3ZoSCSN)4>NsF_xj@X2@Sx6nE) zeUk&jDy=^cGxQ-}VEn-L6lF`XJGA*CPv)IgR3fyy+rbMbniq~~I6L}lDzz))!(76O zGOV(UOJos@gEFzOQ7Uz9)rwuN_nl$_`=6Lrlwysq&|J$~u-Mh#DOOoVWbzZnbD0ol z(&>zr{%mKxbcw+JC#K;*qjCcb;zqVNos)SEfcw`q|wgJM#74es>8qAwkanMd?LwN7l%>EtgEneO~POu6`1Y{x@2;Y64qHmWf6cgBw#x(4q2O=Jb)<9qtUf-9A z?m#>Zbr-Wv_Lm6kM`K!1&I7Rsh*l^1Q>?-f0h!nj#4FqS;-52cJ{-IQ>wG|K6IQ<+ z)3D;@?8;6SuP2t=4yRa!BLXrJH_??Hed8#+4)2x-OS?1s?U;u7V5Tdp6YVIfUE5_Q ztll<`8^}cCTyAVnxP$oh^^`;}#x$I)`j0bPwzss<{dq*O3dbpABH_I=%k5WCyx8ztA}sy6*>A@*>^5|DVM+B1 zilMH*DOTY)g-i^6<;(`>{lXRJqS_4=+5S29yfFM>b?)b(k}2y&;0vTwY%yG}`J%V_H$J&TwYi zHb(Gyo3aS23P(0%!gi)JI~CZD7i!zkY{N=mKN{0;N*dVk0U`zntiq8EnTP}8V3DtC z<&;Jefjw_b!}&hbotca6S2Ya?tiq8EnOF`so*s2nqYL>+1oopb4JUI0aV*YJ%~RNi zVHJ*S$V6cv$Pq_UG6#YEXiUTG4oWvL&XH7sr@|^6|B#6qU?ZjISF#OqjtQ-;SUqn{ z!`I|M6tewFY=OWk9NCZwxSNAb2y931!yCkeRA_Rq8Nd21EQ^ku=?jX{vi{Upmgs&i=`!QXSXQx?_xh1({P8| zG|2g@So-!(R;#so_c%@=6RWm6v*tI_Y1jX0 zPwTs~Hz!N6grX0vqng>f$FUHZaD(xD+HVK8ZNX`YzJd9oE2&(ca@KN{0;7ab7YfGA_}Uaj7}#s4(#jgkpFAZ}0e zW|eKTJY*|@J#S1aN|h}xtm)21?Aq=V1gr3#E15{F@526D)tGgCcUXrByb}!5iZY#T zrw#4Lvy@Vm$h}p`_zbYD{K$baDK_e60Cls z&a83A-qIVyrHkJUe1mm_ur3|##PptfDBjnD{b+eF&Yara8JYE#=V`NoViop^WunlH z&dh%z=QSJMmUh-)-%#H5Qu0Y_Hm$)`nsNUP#Sv-TbIMWV;b#c*fc+AC`t6}Ol8gHf zyiX2JP!7LDoVU*q?)4Rl-x{tZI3fhQUVar~9Y?kmLmxy-@md^-#nBp=P3&@{tp<-2 zhD4Kf)xaFp#RQJMz^&}2f~@rwSFt_dn-s6baaA0%P!vlJ1Lrh2^_Of zl#=VpveTCovA$weDVBO-XEKSkt)^BVI)vcp0C;_G2B@Xi6&F2IIy0=o>-#b>x2F%A z^*WB*KPW8`pAN$ezgRA{-NYb*X_(!$S)?26^M!voFi?sDU;?l8D@wx?d05?;SU$$K zwG`pSDojJn%f1ucYtQ+Thr^^O0FDpiwSGmp-LM!V`!dw9%3Y)g@6LV6C8L(8_cXP5gL7F##$fE2BzUFQ@+`hFTtNY z1{*j96L^gr&iAQPj5+MeAhxx-uogd($+V$Eba%&x5v;d)9ri`Ua7-)8OJg23Y&(otJF5!Qc*PseB;UG^4oh@leLgy}y;Y8r zbr*V(>t1dIt1u0>9M=k^4V*mKktMYx0-cVX7uqb=*OAzIoqfpk?dCOPOyG52I4{H4UROF`w)oK~LdCuh_Fmp}N+ebLM3B{! zlfcW!H-zyYW2cKy+x603jO6xP$f%Feq-8*5olGpO(S(i8eyejCH0ptpZIjNxHxDR z$0`A;5$+4fv)V7sHvSTcMqi%NV1RfW^jsqF8^pAt9C+c&LmCed4&9$~tkRyOVBTq@ zYoT%wP5x^Sc5GE`!pAJ~6T43p7ns0x4AXG8>`Y%iZKR)Alv!NlRQ>ohh}7QOh{#0I z@xJ`^MlbR3q?1J8R-_SDT2W@c^X09$mpHiAN#sR7w0( zqnSkD-axZqrQ!7N+)a7v=1PM7YAUcwE1wCXHaTEB#%$v+@yoXH}}38uj#vunb)c242t zRu2_9RYiWC)a|$vX3mGzo}#qb@5`qzUC8rQ8ZQxeT+(b!m|(dYZO zC1x9ciFS>fn!gF`*n7G}XtdQY!L*{(1LC+-`q9o7!m84q1Z*T}He}-B+a_GSlb>F< z&3Y;;f%nE?8b+L!P570!1?c8tK_aILp50_EE2}+4X?@w3*Il}hwsIIR5!fTMl$Du= z?>~q3fi`6?Mwa= zmwx(khYen=vFaodcs8Ngu+p%nXn`+(dfbauh;b4*RnSMN);{qs(K5)FKaTcelg<^F z2)x@=vtgxS$FD;Z?j7jI8vHCSa;l(jSGB%fCYrqU<*M5NR(Q&DjtM;T(g-UJw;~E( z-cdJzo$c|QW0lq>V2o0&W7J>bE|gWhJENJ+s$CL+cmHA<_8KJk@`x9s+4sO*9ILb^ zfw523##)&uI>wim)=g#wmbQ}!JWItioOxER3Ad{`ne|@Vp6677&!B2PgG|gC&-k#h z)7iUK>vWi~coynf@I^GjO2f^hZ^L-(#Yt>c*;Oi5EuXZ7R1R9Ij{X*sgQ)Z_jBmX- zN%-2YQdfbhTF_Dw4l3-uSZtWR8u0qm_PX?evssDm+1`?QO$OV;PYd5D4){vT4SGjI z;O?{a7rfO69ir5dB^3d;nyGO2nQFQFO!fXArGAOeg#HumKBI8=8L`}bmaT%@%T&1g zOtsv7h6uR(jKbY#)N=P(HUYPqsc`q1YPtI?n>OElM&a%=YPtI?TLrh5sc`q1YPtIi z5peezg}cwF8hK`B!+W``~>PNn1?(iJfZuNfBxA&1J(rb=9JNihxrDm;15bW$yB;&988r zf{FFxmy_$I3aP?O+=;3s-s_LjPCiZy6Ik{8$y`#iRV8)Yi(Fvi{)$>6|J|dsayci4 zQ!o)SF^r6AVq+nGS8gWuued@Z|IMVBz^X&vCXyg#r@l(b4K^+V(P8Bkx)cbUf{Cx| z=aM`-zL>IzElsKI#uRHN+SDH?!ry$L4*#4dn82#>O~#Om%WTwPH}ivyS&w=P_n^Cc?&PKPPeu?~ zIjaC!W1mM{yg!b7td@r?RPqUZ-(XTb`Hn8|A1&vLHue>L?qA>r{}_r>Fj42}EYdnS zUDwY1R7d@Wh=2oId2uh9z^d3DVI(AJo9@$j%|-+ewc@t&AFeSJr(nXSO)z=TB1X5` zY-8q|(L(7Iz;E2yAQ4#gZF2-U*s8Ox))URfj_;$zxI07n^~LKbPQgUYeG5tLJMDED zH?;SW)P9^;7gvZ6>#$xTuqyYi2$FZkC7--8d4L%8&sg!XgAEU>0sqgryvI*GulN$VrXqNNReD*vO|*mt9&C_H%uZ?-8@dLOvll6ppv z5b{cQ;-%I;8u`=}ry9daCWR_7oPvqH{Ub?u_hY)T=WT$vrOV5j8dLeU8cieutIiHu zOm56CL2}j9Y*c>tofq!Yh231cly;9UKo&m;QUlB85pk8Olg=+jsajn!>GF`Cm&U1Y zppGfZjS4nm^=UtL1L_q{!9b~|`zq@V83*Kv48D?th#Bd5GCUj{`+H6^%7BmyS z&Ivr<^tbf!G=GV}D(#+5ZOqcfEBKb|Pc2cmkt?eXJzSR^t%==nq9$F-D{x5%ujojM zyl!qO-GBnMMXB1Z%+N1};uK8aQiuMkpuIRdrV0y!eisv1MH}`brLT3gl-cyk2+c+^yVAa$D2I6yRpgPA~Ry8~17SRa>*|{c845wfMmpZIQ z4ZO%djLo0{t^6edtF)U|HLpYSI2479_ZDyCE3(+ZF|_l#K4jI%TBYIFrghUi9?(w+akwrCB6 z4G=g56SxfFi;>^OMd5*8=>#ZUOkmZxiu1_o!!6Z$=F(MRP7pNtE1lBRiQyDX;8KUv zroEo=!~0KCuYDaP0;{yUay7qE^BLisZQC~DmTy5OhR9DVHNg1;Cu!kh5_;8o$Qxj0+%5~k?kvrV#lx3MNIa6 zunK!oZ~{LNHi_41ZYW)xf(cye5Pd!UlgBsON8haVlL)MmOE;xzfKVnHX~o(xv?ZNK zI&?}f^@X~N{gOqU7m^AN+~O^Lsu>_k)iKhkgJLL7!36e$;LHJ7wY&9p7oE2Lk3?YA z=;l%6*XtBhhcDU~)oq}kNU6P(7J8ORaSA4|KL@uid~+7N)0R-1lJyuSunK#bu(M|M z2yviP7_9)U7Uvx2DXPx`@@v8@bBQQQo~t7S?-WV{4{e}01ruIF!b#%YU{lL0nkO?Y zevIh7+?npQlL@T4@FA2eEmPFuCsr;nRzy8?qPhp`C{Dq|hLe$mJ}PBOdZXDm>ODbJ zI<%7f@Q?|t>Z>dw%QMrDT{U|$Q-jBfJrQYS-140ir(hyiTdc+hY2)DPm+yG> zP5$)b;Jy-pM>0%9#3VdWL~nh->t4G|p4S;eJ{oOEA@C-!FN%F%*az@^sCfV73ZL4~ zhGL>>|JlTUCD+Xb&l}Tl+Sh=BqGUuj7TL>&VvhxT83%?`Cu{5URy7*d0A8KvF;Ab- z=hNCVJWk;81Lq0$Updzl3sM-n^evy{`(!5ilEK_pZIqE;$Ts+f3gXGOHmuq33j~kI zScRVuzJmDnl&9A`PuIO`&u|Zb`(6CBaMol4UvY9~O%{0Q4Z%HUy;i+RU0rqcIy@DA zLb#hFvWW;7;>h|1<&wM%Ov^;-HW#sLXd_nZ)+K_+KCHs|gKw(yY@(OjAEga40;G8@ z?jLdf;AEqiZsJ#!f-E&6k2F`qvn`w_MJeyzS-3~oGPg6gq`4Ya;XJ`A=bfSA(2Xm! zif2BG`$5-1vx&n@ZmI=kh3$dg{!`CB9?Zv+*ddN**y#%*NspIjO!t=92;7gscd0(j z+4@g?c%k>@rCB^y$vs@IjqYM~-*xnRrJ4-?ZjF+WWW=8k)9~fF1@2d1EhB0STTm%h z&B%3-;}mQI|B|B6yAwpA3Q_bwhpzg= zGSO+$C=rlyocf$gmk6xFr4Bya{)sHU$x5}(l_gyNIfBrA6-|r1^9bBu;oc5bYa2}$ z4ayg%Pd)NU{qCUm3(1rk>yorNInER8nV3FJR7m!u4)9dCr^YIrCy06N94{(*-8GF` zzJ=o663-xUe+)CPdoxAa!X=4y(sE1vZo7YB_Iq)ij|0>z{Dg|~PySh={-D)_?fQq{ z-@+>Vw6LSmFkPI>D9*#x-vrNo>(&V&rsBhOCdfIq2a!>`8RFEne0*;DOM;&r(=yR# z;w;fG;Hl|VlMIQ#D*Uu?6Afu6Our`ZvmUk#&t>sUctyTQa->mDUCdK$9CV5*OW!$0 znaVoOWH<#Acr^je*`6{%2!|*>xk!GB*B0<-fJ;G9z64DXHK&f{;~QQgn7}Gr3b3ES z@S@GpU_- z#npATq)haD)g8(W))R|A;7#W-c5XzbL|_%3N5jqmy9_>hNG&#OWEF-}Fp$+_*Vj938PiBCx92g&j$W z>tL5#yk-N|^f|2QbIY2(3TyhrvZk-Xnm)0t>8r4&PqNqa1+3{)%bI?63V0mZ1o#Xp ztm%{NHGKwa`rNXnpG{yD%!E}~(FcuA^gUX1XXSmL^J(?XYXI2;uK6wiVRYlPJg5OVqV!ES9c(red_~{dv<|f0;_&6 z*Q=dZ=OwqybA!tML)e1FTj^O?NrkqdYHdV&-Z8gksT=pEo3!7B@k)jDc2m}Rd$o2$ z*y5L4>Cpn__4e!(OzdwKtOf?fn6mO=|7J7`=o~-~-!rebXA@WjEm%F!s$igdA&V51rve$7pl#5?M=v=Y3CKkQyO`J8vr{l}Y;Bktdn7iA-O}1e?WhSXv1LcnZLWE}J)6L)iR&ZOu%!)? zvew&Yo$tu{99Ti^cV8e^g{R1ry+XsIcB{ z%35zP+cJ}vJDf&W4{RWlHScU5w+!cSn z72Ek<&@fmX#3`7VW16nIE+}YOvphMa58SkIg&I1_br-8}t%RO>K_AvI<_f(8>u@*) z6K#f$S8KP-qh{6Jk{gGxbA~(g+mj0f6IeAmW`g>B+Go>KbBoGVE|z{OvxN8k87Re_ z!`@d`Tfbeb>JBKPT0mWO{PA#gra5Z4BBp{U8Oua&wvgi#OpHF6PyOM%PJQx9i&Xd9 zmq7>Bc3_UKP7D)RrNub4ele?0+*W1>&GpotxqfTRa0({07^l{MWf40e#`zuk#cl9D zFo9KCj8p3uvwFA=K$Nf2j0FRMQ!t^$IJN#Oi>TJ*InCFyI}5HABN12?y~kGVn>I>~ zHIKEEem|oD9lEoM5Cy;~m}o-Yn1-(nvb@2$2R_g*F9)!F2@eS-uxjX~qN>xW;p#e= zy}-I?^DxSmk6`stmVXUZ$rY{l+4!mz%{yl_ zo40Bg#VMHhrBpEK6C%`)0ov$%^P4RRvY#OQr*5Qp+{WYiCdc$+uV6f{c}XKShQHSR zIxt==?YM>F6in3hOKUvnPZ$|=S9_}OyJwghx0xjN_gN|tSmpkGxzB}75u`(+W@FsJ zE7WU#A2A%>d2m1;wRh+7M0>Z`ztY+`v`LaxOU|6ULJv&qBM$h)P@IAZ?AyW3SrhYvl$lljlFS@bqcKYur zCsFiKU4{v)I%{xH&rXUW>!C-57=3IeJzvjX{O$`euksbum~w;7BRwvKwRY9j;Xg-N za$bC1CSB9QUznh*a0(`H{uE{Mz87?*(23=cb4*~>>QD95`Aw%;e4h<_U(j&34M_a2kb`x_=#3c<;ITfO>mePGyur>>-<0=witi>sqz-4HTzA}iu3QP1g z`?s(PqH-!kUoE8z(N_l1S7C|1W~X2Rm%2In${_kGEYa6&0;^y>S%v5;$&S7)^DK|Mddg}Uv0HZ(N{*%S80pBW~CsZz7LANGK#(mTl6)HKr4#laf-g` zSX zt8=w$IXg1*u>8`UdQnV40&CqGePtAV6}ISW)?5v()Hx?bUl~PTg)RD;HG@P#eIFEk zWfXlCw&-gXfmRel$eQn3qpysjufi66%}PN+eIFEkH7NQjY|+;&0-^i|lRuUWr^ zR7G{G-ddr!4Lh|Dz9+ydE&1IrXWEpUYw$@ri|#TUFy0DI@w?w&esi_1r3cq=ZVK)og7MpS<~c z^H-kB6Y+UQBeC7R}2BsiEaSBe+SNDwQ>&b?bnD^;b2^Sn!C88m`z>=rXWFH47ZGn88eoqi6*v~yqTq> zfItGRaHdDM2}%Mf<&1b!+5jrj0PEg^wc7M+@9?9K3&%Iq%5 zzLCdNo4h4VK>}NhrcDU^!?-~nQ#^S~NT3yJtLY7vtwFMv z+M-jljHDU0yMfN+NGn)_jUrzZQ;@(qq;m~Obrwth&nBuXB+$yDQ?rbu8MS+vh=oLS zB?42Bz&fPche)T^w?|Gkj?`30pp`|ZW*K`kyrm%0sd;qG$xe}04O5W7I;8v0NvGyF z7Vv}#D86{_RuW(U%#tC#w>k5{bb_vB#KD@j=+rDDX-4gy-dvuw4sXVO zrx6EJkia_BG;dO!wI=^(5!DqEXl2oWupNT3z&Z=m}>X69$l zK6GFv>V0ta18W-BYG@s9V1Bm#dk5B^dN@o$0_%|0EZzPwzLNh_h@_L-kw7b438S4z2W}f1iKs%giz!H89nz_F9rhZB z}cBt<>6ewu?8uxDH|6v#k{2+7hk-QS7dMym7wX5avcb1EwH>Ygsg-|8tkI zCdh-`oBl%~&}wz)d9%MqBoDG`)!g&!G!BmRU_YMyG%y7TT$7{S97pFHDLxfg=uw>^ zfmXOuNc-q3-7%s&`O4ajzUVbp+3}KWock-2}$d9eg9m#L-n!M)(P2$cM92rR2zhas28s;dHy96l&TA_!dX#?|2 zmtV@4^Sn>$i>rcyPay*QnQM(VXmw}!KO zQgQ^A5qB>{8l?^dDFj-nD=b6Xm*QnF1+$?~Itt7KtzsLO;87En>O1T$D_%<`x*3CA zg4u^%&veb*-t1BzKLRj#>=Tr1!Zx zkN>eVL?$ozr2l2un_AWi)7>Z!Tu=0P)uh?g_ThRr`akW>7`}>!#fQklx1K7*(P0Hm zcHhGFfwX#xw5HizUdvY=7%!LjZ!<6j33bi#`0% z`Jxj7jb9c`k$+FPs1Rs{HKJ)lMy=L+)d^u+ujUl^<=_{E&qTZ8?pxQ2*U z*lSz$q6XQBR_ z{>;*1khYSO`qN}ne`c+tSk<4B)Sre;{h3AJ%8k0ha(-kGI~Bf0ls}*;D=f{U=kfG2 z(@pE>eP9VSZT*rl%r7}f#8dPY*JRKNpO41DjSUznOodHhnpJkv7jaUUnrsSFSd$@z zsU(G|Zc~_MrQma5Em*ajlC+$4aLtKsecK+yE)+;LHCVI7z_k}tC*bN1 z?Ym11VUatfIcJaD$|{am)o^atu46(zDixNH&iBzm*|1`3`B#_AI{p?~VQJ}1jt(`|t?wlr3ADnzt;$SB%1pzi%*@h8 zpk{*fm;A6>A9I#6Q;;&#WK(8lr68dyQeuxyViQ7V8IP&$q6%eArP*Bf+;2{!FAATD zVvwz;uu{JS((cbR9SO8TtqH|(nvG`DCY~}@Rm`KP6Hs4(`H`0M;W(DB&mLnl>3vY0 zfL53{otQPdAF~h2!6N86aBT_KlQ2KhSw8A!w4^bl2aO--72_HS`o5&HpuGkkUSBlc z(S8G*>*E>#(nNT-V=kL3uv+^yW&Nt`v<^IGj~oA&Y8OjLClyZV$mWhL$1cUE>A0$b zR=Ac$o~83eW8~N8#%0=XfU`K9J7a0--o9q_Sj7l8mRcr{vhMTXb{$^#WKaGdl?qEp z+Vl2q?Ceb!)->(1j;j%9g{9Rr-@l5o#7f=Rr+u2T`hkiB%umzg2PfuJq7`dFdElHJ ztuSv=0=gbE>fKu}&NLgUC{l1%j5VTZQ@mdp?N$$Ai>XvNGksO)u6c2z9`NT8KE=adb18HXp1 zW4`o0P?v$T2`nLbOS_YdA}hzRZmE}bB+v?&c=Oc0@Hz08Xg)YC(wIDaBKvaxvW~MKd=4xv-4nNajxjc@ z6D#6Th@r*<^TQHSjK0oBzV-fiS-Q|xV}4LM)7-cSecIq$66ZBI-yvT#s(_&{o5Z4X zh8j3)z}W=qNJ+W;swL}Wc9MgW(scAi&~sA#lAF~hvZqF*m`y9&IFjMmu8wM?LuRBy z7B(Gnmj8kA4~(~1b;yi#$ik*W&KmV`L`K@GLzbjN)@?fEEP`~%Sz|lW)UF!LVClK@ z8qNEr>DZs+c%}C3F)f_s)uJ(mO}U&k;@~Kw>J#mv3bXP>d$O~nTf%P*zj<8IqZ4}z zh8ROG_F|R4{ZQ6@u$ADN6P-ZQbEKHuFMz#0u-q`6`_+`Ez&!qxcG%xL(%F<65XR%^ z@5QcLO??8xdHoU=_0F`zBSeSg0W9t1G6PeP&~kX1&R`#kbExWKsbZ!l% z;O|cT`-N$T$08nW-EXjb$6gV0wjrA~w-Q4FtyE>dug@c~>{?FNV;0>R5Bmy`XyW(Q zbSZr^PpVCYn>jMlz!W6DUOMdV*?%Gb_S2#~%O5a-Z*4b;4GvNX zwDLG{t@)ib5j^asC67Tyx;b|u<#9E}z!W6Pwog9s%c+IDw4LRgiAx20xDOvbiOssV zOd-&!R%!c$nCJ*z*s7q5JiATQ%`=iEZ(D9)%fPP--zN3#e{2)yzxlGRmzNuuf&_kP zbO-35wW8v1FLtHVJB2_ie4Dh2^J=wNRl=JUOn7Txib5#gVEc!aMR~@Jt|Lb?B=CDw zzbLQC55>C`BUruQYdY>r#ah6VH^|Eva7SDU_GJ!vpDV;Zk8`F=`$PEUhqOl#zDMeP z0%;H5gAmqjn7RUq?_<*6P2;zDxAC9YEAPMzK^_T3VCY z5G#s5xheh~?XB#=!X6d#ru%DmPtqGN8qZeW-eFXDQo!6}M+CnbnoDBq!&XVFoUdN$ zZK49%ug$g_=qDnr64e77#Pa9ESlYTrO23Q!quLU8b#)Qm16r`Wm8&vr8Q6~1R?Mde&5D&Y{Egt=Id4seO3w*G@H;#L$7CP=mlx$rA9JNKeA`EHxzu2pByQ_SpjB-90{Zf_(Rw~>ROWTNg`)2&Klw|?4aQ7|WK~! z4?SdqA35anW*ZDlLBg)eFnx8Q@_Kn|?f&?uuZ;RFr~EScx{d@|;n@&$Zf#-vR`ch0dpXM=^RN z(28^*I_Z6Et=)5hi=08{Q*k<*3R94vbE$O8F4v5+sRCk3${vf;#n}wKPu6dt6|EZS z6nU_zqr0ytDZ9}5RB3cJ6{a9T=ThmGovj&XQ}qe{L!6=Wss5s~sgOV`i!$1B0!D^9 z+P7hSIXG_(>E*J)$hAq=pCxp#eg|07qyy1O?_;ao2es?VANF**k#5!dWTha1b!gT5 zNYeXAo8BjjKr7OL=%n|t)h_9MB%lA^%iG+ zi+_J>zl1eSIuM=oKDOHZb8~sQCA^vJK>Zb_Afdhw()&o#`$(JKC+oM+igX}4>3wXq zOL`wkdLL=i`(&jcp}r5&`v}teNSod#i$E(BW-%0tP~{F_d$9e zL3$ry)B9u*Xhkb`y5)S440Uwg!TDu@A06aOQlwx{jWw-~IIW0y`CkXwjR;IZ0&Cr> z_YtJ`kv6?g)`){v>c~lYA3=H_Su#WKlQj+^p}r5&`v}teNSod#i$E({zswr7t$H6p zdLL=i`(&jcp}r5&`v}te2%Fv~i$E*2cAd+|ixih3atD3qII7_|h~pKlM%9lO^Xd(e z4X7`{6eMumwd#EY>3yV4?~^rJq7|(znn>@XXX$+e>3yV4?~|2+1o{tFy^kQhkF@E1 zvIw+7uZC8NJl#a~2Ej6>`!hvlfg?4Js5D~#XkhaKZGs*k=6HM zpNKS_@_(zPbpNBOyxAp}GM*=0Ypwqit?Lf-wCa;zj_D|KZY(Dk4ZEu2D1%m5Z`SyS zp!kQd#Xqw84D3tPo_bpiI{R~~NqV)kQ^vs`8*1nmoxF98JUuKSwGuBkdHbr1+!Jz9 z$KDyOu(UK2c0DH6-(7F~PO%B}^zqwPzrl$U3d_f7J*3;$4~j2}{wJ1@)^~~6OT?VN zKIqu1VgINS`YR{d>d%()pTye=fmZl@)ceFd6~X@vm5mHL1HbK$MQ@rMx=zuoCOmthsBt^ytyk z#}d-**}0kg)c%VYLMPCm$BHM=sOQN{pUtFqu~hMu&U!%ttS zh!wr&>x)aBp&jd2st2$SHxuYD+W+%_^B*4b^)riC#by3Igz{+fPaNOBcbQ(V`Ay0r zxK048aXdk6?HC@5R#kq)@p9Xj>6;2=C*DN2X1krMvBnA5U#@cr_=qImA{?5|Zro1m31 z5hYAZ^l-Z~LM8sJ=pa8or6-T@R*2;hC-{csNWJ~XV{u56_Tz04IV!IwTQ{c5RWWt{;vnj&F){~THgKi=^S2EZ(G}m3L|!&--<;-iPu~i86x%Sa`lz5mRD^LM*4}_;o|5 z{^tD^fi&sJItQ>=zgQzKAd9d*Ek1{h<`$YxXc`f~4jkBLEboxdz?4y^l)oRH3?5NvRh@A1oNhN?TY}m zbVPr?FU?! zYkMhxrM&DWh6Sz7Y`fOq8g(I#JO3=NkNo{<<~OKke1o^^__N=-G!qVg?=sNJ)^@El z=1r$^oep63EvAd)fnk~7p!K)v{~pJKiZZ=UY-(m-qG$9an_E)bb@vs?_UjC^vVDVA z8uO-;xn%&GJuOO{AL5(Ymso$RIDO}(C;R9xe?GMKi3{rZ=ox)tsUiNX%+N4VJ1)#X zD_dV;r7>?!tGY6P(Grj{`T-B{qNg%t$lm%;(>Zb-#$CgpG_PR zEzbWt+(0W!pO{Hw-lXvw9l$EY>=QfO@>%=#%-<@1F^-Sxc19fNm&BWwjNna1ofA#SFC9lWbPxH(;$@Ut)KLtK36|ei z59DYS-COc;eIxiQ`}5fd^Pls?eb7weDbBnzZ9?O;8V92-?r=Br#>pf`cu+2>91e0;A6KBj`jlZn~g zR_>`?QJx)|NAV5gj>hwO=a%w~WiJYqklx-h?PCF1+CH4)@77-w&uh$x;_*)B1=4hT zcF`8{aKbyW<=cCKV=9i}!LjlDn0;%0=#j+(m=NV5A056YI{*H=K&u(I;`z}5eR-*G z4~0tH9N$y6+y7iNjyj?cC3eK~rvd&v?a@7fw5EN@)k^yAJZ~(Sms?^FfIZIN@$uYo znVTN+GnGo^SEGwu8F<`izUZ4ktDe{6Ih$2MpEKa8P>E5cJmvkvQAU;b|0u+vt?}H) zIj7#)@3}x)(@L)BByJX-B>jH&7TEd@*(dQTKf`#HyO*=I#81^{i7vrGa&%7*fmSEm zNxo-dINx_aJJE1*h?wFMAanUHQi!2Bllacn^ZA^&R|V2Eo_ll?iwgzHj|-y&TJ`TH zd4&@5Iook98xa$?LJXuELyr~QsSul5*?THU3u zcHYTZJZ0F;Y=o1?8Zl`5V7bsINg=dHiG0h7P~Pa{O@TDsY+cMt#Qrx(KD$G$46KeB zN!;6MGEd5JI~y^fevoKWXpoGl_E4ZzS6%XGmnnQ_uI$9NC4NFw@{%X@91@8JixPRC zCH~z1!5x9Lrm-{C#Oy8J(!rfhUjwVlZuAC|eff}{_p%Y4T1JSK4qfFGa~_3=Zl1(H z1P$XK=-WYB)0R(T!s~up`NmXEqSc1&i99W#4<9$-K{n#&8#ht(Yg-w)wwy#O|JIW0 zdp!Ba{tvSe4<~IBRr9$?hr1ONV$+vIezS}Rm!%&Gq^VRPMMSQV4P|)Fh7zrgr6lsz zvs>_!`%x2Ock+eLKfBtyY zyxRO+AWeHSoa>2gj{C%`FJmQIHGi4NQ%dYNuM2&Vjaat8OSG@CU%cX@C0bRWRuaBw zhxz!a>_q3uo5YyHA>yBSmDuH&$h}`hn7>tcDUc>lrpyAv)VHC?^EF7K)uX~mJfvwa zbNK4)#MM^8;`7iz(e{3zM634HN=jexG_N_9ooK&wmgo~wO0<7EQ6VnePUPRG|6}PD6U|QL6-|Dh>W8ZKO`_HAib=fd^L=jZ+_DqX>s1l%jZT}-9GW4~%F-J|)ywA| z+ao*C#ABlv;o+{mwIKx~;itd*KziPxq@6EYT{MzSEwA!RR&wyi zV$(AB>_n|1!D1wxIpDqCUm;xQCUUuBpQ+W{7XoS8Klpnsaq9URquB94iB=b=m0Y`U z*7T!jc4E(t6=Lb$jYi3nBNZa>XCmLw`LgNrh35ik+B0hEEjm{_Z*(6yLZa2c6N%jM z_P>3W=ge|?%jTGM_XyvG=uZZAXUwP9%0enb+_ zO(#U&tDKsR_)hyjemE6p9Zz(SXw{lpiO;%*`tL2W6GLhY6rROuu;L%w6yoswM1C}H z3;nK05lGV-^0OKuqE~I!dulU@Ru<1CHg-w_g_u7viH}~_ zMc-Kck=19&q-jOCx{DZ=Vz7!&og`Y_T$spPtmvbk2+r_J{!e)9YbB;#*4bIC&d(E%(_G#d3UH@>*hUyw5IiSsU^;abZ4(T3rVzU zeL0a|>Eo|geR?Mwv1RTM@v(;o8(+DQL@Ot1CH78%`n`qO34gv#bZY0xykq_lNPM(Q zA7D&_nk0Xw3fv<_ps-x~sH>ftt37p)vev#Y;xfmWxf zmCS87U%wr8EgRuBWQEwea|Fw=WsgE!r#Vjlx%2gh|6CPF(+d66uH;jXXAi;`3bcB+ zCy|?Sh3kbLT+T-H3vDW%_yw_9Tfzle`B5t=K6#-Ydi7E^qWP4aV%T3}*rDED3ek^~ z-~M)?-Z$=|K$`Xm-|`YiK22r?_B#ojpQ9Dd)kzV*vw}D*rm-AzD=NQ*d8kA;BSqL< z8!n$ddckp(16LygI-0q0V+sG{aGqwV?%z{{X~%GR@zisUR+Gpo$}57e%zII&#ENGr z;^4R;vicgP%q?*ah%}ukn=4f;Y&1kpJZLEMz97n@Vd_Gj`tGt&iS-eW#hX<=vS`3O zg}^x=(sYB%yA(0_h>wgqGEbTJO{F}XCoSM%XRisBc-Zi<*xJuqM!eaj5I6@!TGPh; zmm+2k^OocD{HDzNXhS@oQFacWwD6`-iG$BmM76nHWr*+@wU#4Sep2RS30=(m ztFs@UIscwei5de_#n`-!<(YzoB>pbW&yc1QFjqVlIV(1nhgczrR!1oh{~KPsZS+H- z61(<47W4Z$$wFN!D+JEAkfvxx%~WyH!$~%)TUnyjAU+5qk zHEf^|ICnx?)Al8%it6(nWW_2CBwC%IJnHUt=IM{pgi6%v@>ra1`;XW*aJ0MkTjEFZ@uI#B0=-nf2*(dy1M5e|YL*sf%v^q_B9QmQ? zPi{REDly>DWAU)mOXI3bdxbz>9cfM5UMp3ce)7U_EZ<(Dm8FmJDCVe7O?e_zVo6A< zFt5(XhF5Q<5a@X$O)>hDse&)a#~PGxCei97<&n2-WBuXcRBNA@nIGMp)tP#R;f~DF zxu!y(-;T7V)jXam{>bmh?CfeE{QWCB9Qy$AN4c1G4xGz*<^nu4>*C?Hx{A#BV=oKSPyBce!iu>(# zR^y|cL@P^sts4`h4~x4aRH6WlA5A88V$EXiE50-OxJc7k#q>UU4(r6Guf4DMwfiWK z7JQaoz5Olg_mP<&-3{33vADF0CAXJ_>Iiz>c>JR(w&*2(Tk%kzU~GC2PN%nIGv( z==-p%K8($3RZ1by_eEOM%2~#!dc)Wuw^E9SY-!=sf|lsXIg_p9M`nI>UO1y$d!LP9 zH7nFsVqO?yLz+(5NNgbY-fAr4kHvEIYtjG2*c9z#<@II5ZB6C1Q<9?-9Er-5cpb+SPB27AEcNghWx2_yp zd9mW9ZnzZB3pbs|i(R-WRATBF7um0ovwW>>R|xb!k*4+b3JqkzLDgjXnN5n9>bNYP zHyIMjf17n%s6#Y@Gwqe@I#QBQjB&Mga6%qj7AEniWlzl${O zkj_x0bMQh{v zjeWKFa^EM}qOY&-yUL3#&x_6r$|?lisQmxb>(&)EM`s6?w}F7o-d zMq+eQBZWYZ6=^y-vW=_USE8|aRJftFb~C-y2^-^iOv!#`|3m3QB_6JEm5ZC4MF|}Im=J@We}NOYOOW#yj7j}1ZUGLp%N=Ey2^&Pmze`AyIJ$dB+&mv zTGK9GsV`%ig_{eNY$nm_*ui*yeMdg`!5*)KN}TRnUj}@ep?g1fQwa1wktTg&a6Q?m z{XG3tbaRPT*Y8jspDLTSze*P>aWbl&oIcpW*mSU|LZJVNGdPCG3K~bAG?r+! zdv`n!eI04KR6kv)M5D5|>nTPjOCaSD9XM{ngZV zCtWf*=Cunm^HSBLZJVNG~L=W(p9>(T4gw1t|8G1)d?!`@E2F<8WL|* z{aR5WEPYp||A{o|OA5Hile5f5!;Y1$JzS<0svcD0+A-=AE2bF3*OXKU^gofNHRL-k za-HWxW7E4560J~+p%PI(_2ufse~m8Q`4j^EPoy=?ZN01fyyS0VWqe+VR$HUv`M%=a z^&Z|S*|Z<}bys;IpFNuq@lo+>(f>r6&ICN;D$|SEGoMu-6)*M8I(p}KhU@?Jc_386 zd5NnG+g*yq-My|5=&>SAJHzVLmm`0cW&_vWP`p&q?QrK`C+j7P+!ZR(Xs?SraknZv z|JOlrhIP22Rmp7f7)Vhz|K#Y^?P9M4<6n4{mEeM_js-i|JEYSA zXVy5o%G(8Nvq~=(D_-if&GGz2(S>^JJJ*CtRG;lC&xX0O1LHd=1bVDUYud7xu5wdF zS7wBDP`uP=`Ud|TyF`DS@3K&dBez`TlAVoNr`sPn{w{i~NYlN@HOcGi*@S)m_<^I< z2R`^U5y9-VcTPFKTBOt|$szO{B#~Fa8Z64D=b_#DQf4LTB#-~Lqd?rnM zTi-!G^XnnAYEV=8~gNR#bdvRP3pq z{)U~6WxdKZ<@~$BimnemZ&lf^cl3~byb8%qe-09uf`sZ*_r2sP`yAEe_Exh5dcsJn z#OLa@<;eNf<+p`#N*+k7djWo*(pUC9_gv()U#jGRUa?A;^EH;`20O@Vd+!LeLRFwj zwECsDJnViz@bEi|2Z_o<)!&W&QB4j?N*6ml9VJ?!|EcQqyVvU{m!DWB+LNXktFxHVj1e`qu964R>Rtf9?S15!k4{Dr%}%0shgL|_e&;b&As>Cy&r`hfk$t5KCDTA|KXB@Qg`mS1uULteY2ctxn? zReiYpyPaiVgZ#{USUyGZi$0aA)6dtgpPc(4*=RrQfRYD#NGkDqcug77q6~|z{8I6w zP@At3!-{yzmSHc97_UtVfgTdln%4TC)-riw5jM2t2E~s;HNQ%{c+g3%9hRRp4O}VE z3iD9CrTO#-=GrhZm%%s z{}{?*y%mJE0&4+jy1`|2HGXvcFg9T9D+3kS zsQ4Z+B#!6#eH?Gr*RpeR+J`(m%yk%h+3$^kR#+01sPicH#QWxBSlL_`6as4jX*!d9 zQ3oFBMZ2(vJ1|sWqvHEb|2Tg6W?$~dEPE}ReEVqrQKkno%`C>y3QM9A(FYeM6rDVP zZSd0+0&4+jx{2o6T66Q7?(EpwdJKQ-K#w^7*Fnag$P|IS$DBkMfV> zg`9Kn(QPd|Kxema&4cddVzom1F|@)Gszm3aEfS_ZFT$?ddnyE$3Te{G_%`RO-(NE9 zyNzb3jz%?hA-_1DuZY^!kX(6=F#3xO)Gq4zuE1K zy%D`QgrOCdL?wE(?VZr}S8t<2_h5y~Lxr2R;V;k|EvG_|iblc5!At5xEg*lk`JcF-L0L?uuujWnImB;ELkdiG+bPl%#i zMx}IK>f7xChMOK)-yomRl-CTf7cKjTFtoxFszmXq3TFQI1>W*Rs6t?=kk+)GgUa)+ zK8wWI_LCVZmr*HQlfM5&|0I}P>sea6V{m0YIM*Ukw#Q_KR#+01h^|o2Jj&N!{AM>z zAyB`KG@Y$J-;E#oabEmdYYao>GU}dBkBZ}69CPU9+F5#rtM!ZU<<~9>?>(a#T4704 z;+b>vgutc;#P&sj3W2qNG-+6BHRIExbIL94`!iH7qwe`4eS^=hRo0(Tk4lm1754n} zvs|*z=6(#Vup}yxr|0g3tJg@aF?+Z|U@ag`I+@*d`K?2hq~G^;43*2MdrqNmFl8pw ze?5~zrE2kSAzpWAW%>8~c8WS0OQI5Oa!xZJZTXAbQPEo=uojS}J)`F)n5z_am*x}o z82(m2U-AG?_SJv1d>~K*O?Pdjg>tQGQyE^X0YfWPF{{Lyc5BV1fre~Yy0$`~iWzCz z&9Qr*S^w%O|Cm7crh@huHOZm$4UW1xP9NFN;>q|e>%@n?>@KJJ7h`CJB~*zjV@sMB zwd^F%y>?UxEEUqE3j2A&>^YYdNVA?8s47NH@|?gp-YssH{<4h4>uWuGEO&l2R7SbJ zG0+N2q7qf|-%qG|yPx#Am5U*PwSY8vOWn)xGL6T}>p{B>)Ci*{*_lS?;3{Ey#WfZW zdE8lN-aE&5Igix$XoV$FiC2H0J#ip-v>YFNSs}0%kfwO89>fm?PLtkl0}WL9q9%D5 z_4D=fF4j-JN~Th+9+{IjoE0o@gm*X43QM9AlPZ2Zacb!#dB_~45LgRHYg+Rrd(7rR zGv(^l;X3}-jgfIYx?hCe=?l$wV3#rNOa1VOf6o;n)8p^!XodTaRYI6Yn`=IrDL+4d zZ$bjkCPJF-aQh=Yp~3jhtm4peiieDTsp?st@=Z;c{UAwicsEoT&v6u0$3f=^cXOi% jXSpoArPBN0H?MxRK~*Lu%y>3K7RX&ud4pJQ>XZKuxJrrL literal 0 HcmV?d00001 diff --git a/khi_rs_description/meshes/RS030N_J5.stl b/khi_rs_description/meshes/RS030N_J5.stl new file mode 100644 index 0000000000000000000000000000000000000000..86ffdd0abd4b076aa02a778d7bc0bf0f8b943bf2 GIT binary patch literal 125384 zcma%^1$Y%l*T)A57J|Dw1ox2KJG*GG1PSi$?i5Kb!v9>s+ zXp4R4%-y-1&AohY`#j(G&a>zLoB!Z8>-}3B& z0|&O1s#c|O?J8q_9`nbThcoxg+{FIVeKo2Z||A5kCaC5%N4JVU?w-MBOO-KexwCA6F@8K~ z#1G-egA!I*s#0~z=QMtt;KzeT{1ARTC}EYQN<3e=x^S6EemrP|5@#01<_E%$2PLQq zX!lpo!yEBK`0=21S!Jn$tKk0X{qRQo5Pm#pT~=AD;BLCV+OND3KZG9-T9;LpD(IEQ zSI37p;)n3#LF=;0QU#;S`06irAHx6o;U%nkr3zLbU1 z8!gU<(g-DBJmO4kd9)AQuVvZMSC348c0VPkYT})T&ZG&3S{}(#xwQR}ef7*$vWL+K zC15<_ieq^Mclf9k8{AeeJSb}%C8#RzB0$;X3V-D;@8pVLn%R3)^)QyzRB4`Pe1>n`D%4KSGE-W z_~^L_WnFQbV)(XDNJ#p;6j zY#vlKtwnSG{iuT0c?2xUt!F4yOJ8zmR2aRYFkfMYB=3R!>b^=Irt8;B>8*Br6L&ML z5wH1AF^+AgDoQh^ZE)zvbC=Z1UY-+1BQRfKrYAjUO^hvl(ojD#E}cFuV0PT9>OFat zw<)9tRZ*I;rsEpvdn=^T19xl+qY>-Or3bBvv2~$c^hR&)X=mqbjN4Xv6kq=9X(yfs zRZ*I;D{wy^6uhNHzdaO2Bi8+pvk$F_v0~!~>2n?|(Q-{X5Z66&9DiKxTj@bnlxD2i z^1*u0qq$o5<-dl}2+UXb1R*_WO^k)ajM5vOE20&@dnxYh(uq9Vz+(1XWR*vESf4hAhou{_`<~@{sjf z=OjlFt%;v!THx2USrTR<*^s^}s^4M4gw1)Tov9TC;>K z)0!A-zbK(zyhLkp@z}Arwhdo6SC<P_G*_qbFSi=Y1wOVz)5f278 zjHB~8RZ&{z3UD`zkuXOMNljAKB~AlDL@i7?leD+6PYGYH5T zG%IKD5>y4V5a83g1E!pa%E^};;peWrqJz+02d83g1E!pa#8$Qh&uRZ&{z z3<7cnVdV_odaW}z@IFH};H^pK3<7cn)5;kP$Qk4sMOBoRIfHIF z$n~76C@pga0Xc(dVMX>nQ$aT1tx4t#0&)hol`|NSGswJzswgdU20?NLZ@rdE zKA%B0;H^pK3<7cn&B_@J$Qk6ApejnsoIya&pjkNsddPaMvz4O=vH@>RGG`EwGiX-M z;2n2VMQNEc2*?>UD`&uKCF`YQkd9!PGYH5TbSr1@j!vt;%8_axgOD=_$Qg7iXD}dV zkfW2TC@pga0Xc(igLAP=SoPA`y)@mTjkPUcik~xD3 zIfHKH3~tC7qz6?|TILKU!q_ZWCPxsWX@nh&Y)X4gLl@aDoQg}Yg7oVQAog3 zs(1ZRWmMUFd#_{N#hJ91wCI`195h0S9O+|>RM~{nFmLycL8_wT zk+B>jhlo(^d+l`h=?)s9#11yz(7N}uJf6TBRSDLpt9#<`xz@X~#Jy}}I5QSAuqAZ8 zV$2v5CW^EwCB}xG38fKA1f2^p3MQ&8X~xPzUh)IvB?lUv*iQ+nvgbal6Xz0ndej!? zzWliR;mu?y5g47>_@Qk_%cCgdS4APey5A`e?yz_XsB_sxoFs^S3nT zg@OuN9(7?aqbuxX{B^r@7>!VZJ|QvozOAm`N?ufCSynQR5>(Zu3+MX}RkJ*X!jo5f zc=CGw!9euplK?$m&eVVavYK|7h)ePFDZGCMXRAuk&5#gi7)_{z1 z)KU+sQpY`GFsRWyV-!5&y!zbAL7#Exb4~9p8Qh;AO|Z`VYP*rf&9U%Q)Oo6l5>$1z z=8&*mB_>(Kcd!rlvmPTh4V!NBpep)A#@O-bQ6f2HGHqUsvCWBe?xI-@V_o_U7SHp| zH)9@-chLwX+|JR)z*WbsIq~VZL81?2WS4i;b5Me+Xm-X}O3BO3;~zv4u|>ibIeg ze{8ocj1p8uXFkTpz20q(uH8=r*DU0sWBd5Jh3+5cj*)G*kMqw>I+!isDYdjKpM&-c zs-iSwzg%i&*49Ue-S^wOXoU6>S`%YO3-9GG-bITsRR+6g&&d0!taD&9Pw%t$l1G1b z*RIz7MwHnz%t4>xsfyB!)qgZdtG{BnSU;qmi$)IC+2DLS@LPH2v?j*t!Op}e*qM0H zxuJvZMo<-{8Ee(@uy$`nZ_$5ZVHb^TbiQ_03mqgqXieY&J1nVShh^)HUM%-B70hr> zG##q{)@X`(*qCA4Po%_>!Q=U>`YkMv0_qu#-A;`GqiA7ga%~=H11GQTsGTUlMuHIbc9a z%;CHdO2kf@$UCOH?C^LLh8^Krup|7hD+SJpUV^G%9`o)-GdAExQ(=|}lsmR?4`dF9 zb*VD0&Z!?XHx?Z%z&#$}uxrp6b`35i{UMA-C_$e^7>nDh3$Z3xf3SZ>93`k~@l$S0 z)v8$@lcVPGWp&}bTJ4`5bXNst1Ml0nu8)&B59OF>5&4!i~b(ft{CRx372&po`fR&iJf7rmk*l8oci_l=j?r2Xm! zz*~S(@D^ZQ+hRDkd*3ur6{Q)wd32yYx93VN|E5S6jXcOVlAn8iL3+@d80!shGqS+j zjGv3vb->*2ePcpZlx8gZn@)Q3cMr5=Df_r+WY^;EyxYDYd3|V2Fek!Wnd$IWW^MkS z4p=9=Z+@tX(y$v9)Ih&cB%^-v)OZ(-)Vkk*4?a^;deE8}n+tE3{=8O7Kbn7>12Saq zTRp0xG-LB(LiCBTW%WTDX1i#l_P6Ev^$&HW2d#;*6Pa@9so{-chEuZ~kRfyRc9NP%pTnt& z(v0PAInpd$bhth*+bS20+&jC;-Mh%Q(u39nJ6@@U$za!DioOolbMJlvRZ*I;2KrI6 zM$+DT-!tP~G$QW2b@!b%Pr=CQhwHg_UxcbC&DhH_0b=UXmiqGb zkuDlZzB`xks%;zTL2H61mKFI#R@lX9xhx9TbMO8RRZ$woV4VVDMx*Nb=^iOvG(u-* zS`%Zq8&w~6qgw4x?V$5HRZ$xE3h=*J`8C82JD4{(L>ddL?_EQg$a@xNCNQ7q{ zCOu|EuHclmdr;Me6(c2)D*yKXNSyD|R}$YR`jJ!G?lHA@H>nzCF5{G--d`sU@9!e% zd}r6$=&ut2RXTcz`D;0)zfOcFY9)y*Q&w?Gf1TLZx{3FkD2;@t-(pGi*Z5EL>NxgL z8xe~UwZCVn9H{y#AwA*~$`8hkq#3(me%6wIv(7BtI#T55R)-HPc+-tn^xgZ0Jh1QY zZoGr(t5@U?qk;@P&e%VvK5N^jtTR70iWD?Li8^UGKff-Wfi&!RUA&{seRSHK(AiE< z)!mq!yvV2`mdCVLceH^;&Y17(MhY6CM3Kh%`Jx*oEsx}7OzmFw=jM&xc7m#Ya4~+P zjc$1?YHDh|CqFk|R*MugLW#!x0{HkP;g&~bF-OaiJwW6gVkfAoOXq{muucsvk5Sj= zXft~Si06(-K_irCS^KziPyH5_$DP1NT8bK}MeEUaf~vyL4R>b9+}83)ow|{BYIADw zwp^s35lZw~80&2CO;^if!|X@A(20y<(Re#SRmTI*JANtD#q!Ag&qKbsRwnVRSfrp4 zO6;C}*)i^?K9)z?TdSQSHj6N)*$Jwexh>c=wR2a?!;xm0b4Z%3;!XZYK_iqX*|&o0 zSb~0*M@+^A#`I>H#e+F^f~p$Vak`5i?_hb9n6bzh^LJ*EB1fd45lS4nTHT!_xTocD zXnQepPt$ZF{ZczYRhhS~c5ms|%<|YYwuCwVbvltRL!_V)N_5`%qx(vWc9uuqkg;a- zWywXwwRVE4f>ZwKZn3nc<#D0^IP+L&3Q;Cyq@WQ>T$}Wld;7I|mdB#7&1Snx|C%+o z*a@oo>!-9vQde2aWA@Q4=A&ot&9KCgf<`FuoE@#knkxoXKCBqvH0O&CEy}K~lN&y0N)A!vjWO|#Z99%NybN5V--#36IK+2&}Zji9Q@yBZn&1NK@T zPIpq#B*P4I^^*ueBb2!KM=N9QDz}_b8OxnJjriQKy4n0pq>Z4ex6|4gKi%kPdED-u zRtzp*-8^$YLeK~$E@$g*G@sGk@>tz7vnbr-gz@4=grMsyUHj}r;*^=hAAL?4^)5#W z8leRBhVuw*qdC%TH4EkGDfa#G#F-CfP1Ob5_ zG(w42r8DtSMmEc1d#%RW%Jl=x3n}abRdwp|-uW>>Hsk#Y^a$JBOv^l>hFPQO5J4l9 zDDu-gr{jEXV_>=!KwNsbnm64&*{Co(S`12;h$l_{!Hv1-yt*N4{rqGo#j~(KZjN8r_s}*XKav?2Bd4s^0CcX(5xRnLCHI zwq<1WTG4yMSY*%Z+L|ph%xO1T*$A4QQJS%BnbV04DUKOk%m#wywRCLLF%R$0m!uZS zM;|o?4UMu9HxsrtejW;Q6!bny!_}>MP}|Y)M{`7qHnu#G-Vb}Lu2xuM!&_2!BnQp7KvH?fT)Dzp-@Hc#pei~)+I!;LnH{x72Pc}jEBCh%R7G3J*zgg5 z^WaO_#Il98ZCM}9&g?UTd(sByh4VSY%J4e29FFE%bBma9PqKEh=8}skUO4N!p5-Et<91h&_=_?0sFwmc!9p>&}v3_x@7tERWaMdK;;3Cl_x^Hxo2M{b&mr zo4vB6+4|QEV#K<-wj7S;S}VpcavvGo#PYcDA-&nJUlLJbM^ix~)Q`51u?0KFnQ2P~ zifgSRY&jgwwH}we<$fC+Zg~`X*u(tz@RNDBcvC?m)Q`3h_I-+MF~2YI!CaHho{`a9 zE8WB(qrvVnmdDt3OU%QCADM5LHxV>K{b&mr8@%y?`RdQ>W{Z>djEv@5%fpKpHI`+u zJTjC#WF84TYvxPUM9>KJqb-E}#O5!|g@g8(&&SuZWn?th+Pz9M8s&nFOs-KII^8uZ zm)~MO8Pr(N2=${aguOl^u{iweRI_;1`nHUW=304^H!${1+hcjeoUnKcA=4= z5$Z=<2;;m)keJlJvbp(leOpFGXEi$8F?RS=GBGDLH^&rdBxr>C(H1h6;K5#=;$aWt z>Xc~ld1h{YzS$PJ%FtPj&UWza;QcFnQ}yS@xU-{ds~TN1=vu;9(eXLOl+N=sGmS&k zXxP-UiXYYYeu5M=bWXIt>n`dHZ=M>w#wu1-O~ANB6iGFEx3y=sA@#o2xI)i zIerLzUZj{dFHRfM=7mX#p*+-h+WCaDT>izJ((rW~5UYS_3icA}C>3 zapJ%^E#HAcHsV}Vi1BO0ac8Et|n zDRN-OVJE7d>m^EWEYG)nI$|S!YSz?Pw&M9pBq+^T5_eNErvDVP545UnvPh%Ax>{~* zNuDm%jHTO`$?~RRjf^|%>$&m%dx&Tt@D5VdEUmUN^qbXEWhaJauOoW%pM8idCCec_C=K7qSOj`dRi_^5j7Gci zNDn&^TQ^XA-c&~Ph)3)%{n-6y?NZW%(y%uO#0MY-06|rS9Dlp3epg<4*ojXCe=|?i zs4n`&Bbq+l<*u_wlOB|Y?<|2h0z@$ob1kv)Jq?5gU&<*K>%w z!`s@@gVKy;0irAry@8;r#fL|^OC@R`J?upCKWdoSYPI$u0vvB$rOz~w9+YP6!|yfB z+(0x3531U;;*+aes%Fx|PV`tl)~H&ngJ=#hHuY-;6U^O52~7)CxJ8f$EMQ5PW+Xn zg?7==O5{vsC!XjdoUBWP@vP!9PHD!bHLfdm{F&B#ST3`md((7m+xMyaw{9oglLO4= znO~Tcpz{i);jQK1E~0!~R&(NtOE#it=_n&C%_0|$T1qq4XlM_S^k!M3@U3$;g3fT1 zhPmW&Q8A-V5iRs}s0f|a!Z_m|BUdjva}Eq_XPlW;+*;LM9?mBwoDbEiq^fKq=zLCT zc+Z)yu&C6hpO$_=B^yCkOG?8V_ZOM9`%j9CZGTp>J)hGI*?vC?{8&I+aU`!OoVluv zpsLj4W1ZXoYG@p2i2EhC!v|_v#Za;3{=de?8H1g(MNI?OzB&npI!8RMWxSfOkkj77 zSh@m@wb-jeL`+KEqy$y93BKg`zI1(A6MSWnqpJu@cv4#l1YKW`&8%TO*gw(FTAR9Y z0TJAOr|~#pHQVzb?MwDv@*x!d^6bQ4#?E}9HiD{X7RA`s8O20nv65?#oPyq4de`nJ zY-I$&+l=2Q?~dkqY2^^yH}XBo@t z8Y$-fm`Gc_Baw}uISQp2D{+0e$Tx4V(ez^*le*J-Td$2YKDg4kJsz!7MT^9Nv)q4b z{}_~@=Rs-4%5NzkM*h~s%=f+1mhaL#XkX9wEE^z_4ecBRx22k>J5wW*+5A$)45F0^z zAEjXz=S(N@Io)~lB=jqqEz!1bxlqA4y5qDuk6{Bu(Nl}f>2L=rLC=ZO@U6k}K=CC1 zVRKD3-S$*O+iuS?v>~}f!DAcEh-4LQ1bzOXG<-SmV|@{LJ4h^raZWQb+V*9S@)|on zB(i3PUoUkOt8d&f3&QxI1U)B8!!BplH|EL=56uhbblVdoZM!{_nK3lA=ff0}uA=2_1bsfIG-LPcXApm+sw1%P(#(>!J@?(K?i#$Tbsoc;<`B7i))d*` zo>PLJ6QyCr88Fz)kS3SNc1O4Eu+X;KGcxCQ^UP@l3W~nX%G(IKmqBUB`fmSbe!I4v zXasW!&0cBS^Bh^|UX!eSvGe+krrlZnjzD+KORxiJ+@ASbso*C?lnuX zK4Lk{)Rds-L}|wEov&#$eppm&Dyi9a?r7WXndO*k3yfB|%893UE7%CSM@DJJ_9S_4 ztj#@K42AnavvAt>ZHJS)p6zX5orgQFt$FzIFfk9#gA(+dC=Fi-4XDqf`V|*>k2nR* zsc742<^+E^8Ipr{8DCaZ4h^vpbU%^O@K@OG61;bh5#kMu51O~rw%fC%bctpgkIIe~ z+o4}kf}RtlVU7AYk6+z9N+g33MYAwU+dcG|b+pX`dWdzo_n9=ir!>s~8C$ctwAN=? zgt*u$y`TimChga%>&Cib`HKLp?*Q+!f!vLtITg*d7&}+1fJm1kju(1aRpoFF+*_jA z8Kq$_JVkwxVoMrP0_H?I_t80#t}FP}i~28CSYHUqR?!^~`sI*PeE(!_A21k%E5dLcf`5{dWhRFM5gf_Vwn~K)pcBaI->Kq@WQ>1i4%A z!nx*KZ+OG5rPn_{&SE};?@K5_Rn<=Q;zQ=;vpkm9$e>?Mmdy;#9w}&q65Yc(@pb{Z zERXKbGV5Cb0@^vA9@ArJ~BkI@J)|E}Aml|GAWV%1d*`aS+j*%uw zjyNl&YRT~%pC%6vI2Xh;l*i$3Ov3AHHyWnZ8`qAo5i<`BapvmKnLl{H!A3I{<;tQD zo!Z=(#3BWCA6cUx&%J2>e)OQNWh`Oxta|0F4nF%{gqZkiCw?tsYA3epWsTnaX~E1+ zBq$Ak)9^mCzHnPPZtRG(5mZIJ;hWSl8TGeI(rK5DMu?QJTJn`IXG)L$cRTX53Fb== z>IctiuhZ)}I;GZLosF~+R7G10U&_`C(ob#~sMXjQA(obo;H|#7EInSeYQ#53-IgBI z4@T67K)uGfKHBvskv4*=XlohE^g{x@QpvU2{b>P5Yy?%&*21&%vin-XMQ5~S10uw=W4U-}&BD@Sl`B8rKeD9spni9%}@FRa~(qqo!#QgZ{aOpw)7~7P= z)T%~3(FRnhXCtVJwwAGhXXj`!?~>@pLL&t2)wH)$KgJvvW^40bC(=K)u4f~tinf-q ze1F&1?k7#B4{+BNI3~_j?&cXqWJJ-i0`u;$>Dq&}AG9{Fqii0u-i~w5IM39t#>?+r z4Ns5*YfjVt+VsNpS&h43s@Dr!-jeDc@eYBYqmul-%^%gWjiC0g8 z`01AUtX3_W+gv-4ri1q5sX;b^s`|or0G|?M3Kk_+{d*0DMSky(^`nZD@2;VbM74;||kcHn| z#4L~Bf!GX03Lt2N5<6EE;6-W%T4(;S*BGr7<681~1XWF#0e_8u`kd2q9)DN_wu(k5 zF>!eaKbHHh({s<8Wu2iFypUeDiV{>cs%8kUy=9T*Q6GrHK%@i@8llAHk>Py&{PmVc znrZX3IZMy*pm+pTy|`JKU(6bAd1M7*DiC-cG(w37HyiN3CN;G@R?l3jmA%t}W2-1Z zRo`b1=NS(ycX+PVIv|39Ko1(B#4nSZ@_#dKad@s(-2^MN>w5y6ct0pXRk`klbG9~z z%i~cCh)jC}oajL#l(^QR89%-{*yZtfer}o8`DktfdkH0|Do=@OJj3~%*4H~obhQW? zp+vs6jrgVqMcp2c!ATZrEw^ov9+aS}f73d6vLTZ!k6u880D)JRMksM*ZXKTB*bkP+ zP-B+1{b*tn?>Qx?ioWw?Y%~x*0f8PgLJ9ja}S=+T~qw`)s zL!LT6et*>@(_pRR%3S)Oe!7jIs-uD5IfLgk=hx;U@h+&m)+r*5US_d9_o1o<@Qqh$ zM+=@;zT4i>y?|D8K#;zvLqnSfRh26+zT}r}-RX z6SF+kHce`3u8Q}C5WPN>hW)E;N4a*qoY5uTduMuY=v9Xdxx`_fWO%UAbcy{!+Wle7X9FBs(|DloS22v+3wT)%zX6mXs-~On` zE8eyfbgrc|Jl6*I(F*l=uhsm}RM5Ld?|JWa$DGq=hVu*Q@k_uJc^7C;>zvXi{L#ji z0nmAuu0HVX;D-6y^N7#d!PX6IYb{+x?H(n5-K9nUwOxyB-PV@L(0P~o!FK=~)@cm} zp3@fAY-uB?imud*jcWdg|2+E-o^H!1+loW454~=19&=7iIqSmspifwIjiOh9vBznX=wrs_ z;+3E$Qi7`J6=5vVle656YU^yUF50#_J2zC|3I2T(hBFbp3XFYRc#SvQwaB?;w4IIV#$gWl#@V6Jv=hwbR-)8>$Zyh18o-j&H*z)q3mLKEIwUSI9NY zS^9Eqj&H5u@3x0^))EXDqJL^w-lVEz`;$2HwQnF*b|U-M{k+J#k@|?X*=@wGQA@+- z1vHWbrD12HiY7iMeW`8iZ~vNV#fg%}{OSofe#1h)nSv*JAU*&w3ka$T*b{6F40tcU zbg~oe9uyOMqtfX!;}LZxWj7N1o>_WOnz1$(u?PsN`j9ZQab!e#c^-CRVT(*+ZI>eY z{CGsMwgE=6t;M7Vr5XDHh;=}00)nbej80%o*_n1@N6p}ab@ceeiGoF6mUKb_*vJn&8)pDQtsUh!oemSQ!I;*qQjCjsvOD$VdDw|#6WVCgPlxH_g9-^s ztRLIO8TGL-uX=M8r!-?#qCfC8U5o4O=7$NYqB*sl*m1XlR%k>HJ?nrPHiBl}lxFPv zVMWcsMcV7%7JOg^UdivC(K(9annAA*y>9Re8_oh|#^LSs=D$C-5oKPOt_S-Y%KJfS z#%fJ^X}C)C)-OGA*@)%qTDh|Q*+lwLny~|u|K`_2dg+f29YDgVT1Dp%pdE^aw`9@v zwQCRC>J>ZvZX@VDpfqDCeh=2By=toe+cB}A9`ycGnz5a`+n6af57u|ysEf0x8@@=9 zGbcS;m@8dsMrEw;%cbW16a(~12Lo&b?XQ%EYgJ~i**#kieFST4BYJe%<9_?xA^j)~ zdzOVVibRtRYX>%j*uH!1*S(x^rw#0Q!t)uOE8$wTPA>v9x3>S^FdIQt^y^l}uHI}c zYQ0XXyU!J}eJ4ZbTKk;1=6RIZ)jheM=Xt1&psM0K3K|o7eX_nti3z-FBrcLlKUB1l zfd1-MPl}oJ{_b1FTk-*Q)^a+>K-SlCsF}EBu>S8a6>J1mjZ0v-)6c7CJ#(5}*6~$^ zJLyB)J}_zjp*@4HSMaNjRW!#7^_ z=kV^gN9fU;;m^m&YDw4Ks_lb{bojl2y#MgUZ~8gLpCd=;ov+p~sXJBKdt%pg6^$c# zM(gvEq_Yv!kJ5~tJl4-la<+n=?QO6~wY-D-Q@X}{e$`c+&cXCb!(R#ITV_VB$gfYy zSl&j^`GeB%-k@oSnR4hidZBYEOgaweIoZ!+zN3bz&CILcYgJiLciKy6YZ;rLc&^#7 zVpe_m9Zk^QKxw)@!V~=h!_4?Pr5-+B7is2xa6h>0l>LXQ=&B7*sR_56!@td?e~d0~ zBd8yx;a4NhelX(-H`kB9X>8IJl8*Bag`T+wtSn~T^C^+PnMSJ4dPK#9HiFIulxA%5 zox5gu&QIF19J=`BayH|wvyeOw+IE`ZFgA6{9kWiqRQmPSB|#Tjw!;bC9UIAxi&rB$17vSAo*-W&fLmBJ+z|TAmeL&{>VP zoz7j1J*yQUvd6vD7Wc1UBj{D2Gz?jHn27wPu>SgeO_OF`wC(o!YT>gYVrvDi-|LgY zM$oH3X?SCDxw0sozkoh5es@+}$t5;Vu~ zj>i2tCFODWCFm-t#r#}BT9%3p1&vUGzO{y57h9KBv^@#G^Dxm)P?hyJaSqR$(WrXq zL|*u%j=?D#3L2q=_1AUsEjj#-@U|3U_2zJGWSfSzFHGq<(XUP6Z!LlN4v29;&621F4cCW8l!Py*gs8}Qo@mdC^JVe(hM-j5w; z;+v|u)uza|y7aBp!{a^W@zOW(eN<5E(fUsFtg}-4G$xHug1%jbzph!?L%*{6fGb7y z^EQI2Xf_DDg9Q`lqr2bKmNn3ASsx{62FTdjL>2S}fiE0pq6&hxiq?DjRD?W_%{lQ6 z*5I`8v~qrDTuinqf<`Dovs(D;%yHwit*>u{{S-dTMo<;zU3d*Ke!%&{O#14*S^*&M_hgRWn z)Y*ynDtxQ&mq1i{P(pnNpa`VleeJ$C=Iwnew6;zdgQUmVW;^mXO|VmR_l^1V<_gU$ zVkh2buV~De5G3CZQ<|~nH*1?$iUsN~uQjk`OUb?y?w02~-!MRrajWkf82d4(wt2Wh z3Vq(>hBkt(YLtdugMY4?Eqfi)nq_P#XiKW($!WB@R7AFl&cQGzPQPmIcz9Gx)u5qm z#i4DdHNp7k3SWiY`%}A~prN4kuFArU^e1)cLDwtBs$Sh=Hh%Gkw!2e9+v-ePLTh5I zQqWBEn~Dka0nZu;S}#3YdKKW^cI*uERt(dFhc&ci8MGy|CiwN|m6^rvaU1!+g(GdV zsP&5l4*ZgX&fu`)H7~m`iXGzBF4wlr?UYDdzlZUvM`QW@1Y>0uB^NguLPE%Axk_`Q!eLWze*+Zn_AZm@`nHPebUf2M-pPpofS zqiEaht=c>&i^y{;L`yihmW`k)yT{hODaF~@wY4Fa>>gA_TPTMf{6EjgrDKiGcIvnq z=SWF{QI#qmtGm}{oO_8_rNUXC&X4Li(x}G&JRVe~%5?%={HsK)QsInDXHIn-X^(^Q zpej|4?dkTm(1(asDx8s_>{fHII*zoD2UW>3s=i8~hnIl1%d&M&UfS+KRjQ0_S2g*x z3a^#7Ubv#NY~34K_BnIB=U$a6<6ToV`4D)|y#(|nS;qNX9rwNGRHe$;`|LyuSUK_h zuS2#$uOgPeojI2K-objM#%fjn`a7)5;9)wn*NJz{x;|dwRkH}^hfHJm#`M@rE+(#^ z_qz8w?h*ViC8!EoC2R7W$K06(b$vh>4}4Hnrx8lj3-91uIXae?c)1Te2B+?*k9~B` zeeKb6jS^IK=hPr)h;sx_+zo&E>(0<u`PFc`8^Y3 zy@KwTRenFM>5J_IRoPdZvnlVIHBOw>ZeNcOG(w4;L-HA|e=KEr^giP@*X(<&rttDR?VO!NGp}$IG6j@l)@@Vqg59Tkc66=3tsb?doimr)_J)ae2 zek`6=pIt(J1L@5ss0w?&%7Ylom?*+*yDpVp8NMT<5lT#Zd)QsNuIHOe#yXX(Z=MKB zr*HX5en;l5i>k0Dm3P7Kp0Ai~4oZ_$Pu3wq(0b{4P#V6>OcSG5`?Ll6BxCS%7gm|4ngTt8!H! zCdLiZH)Q!%OT8*Kj1pA!$CRzkaiJx7&%rZ*SWvUL{;3JygUu|_;^iErPvYj5bE}@G?C{brgtaHK2 zaQ;iq!axMiJ+18++*3YFQG%*expm6gKomQ%LHl;>069BYf7{0$FKTjCmVX&&d3cC{ z&NyxN(7t+Iu^^1rMG5N7*z~Ls`ml-FWUJKm$#*8ic6I4hhux10jr3H9Q|pWF91f!d zRh43QR8b=D`JVi3&76jfh^2L5S*frb`>+w;JId+yB~&CnF)y$oA6QPa zdoWrTmX!+2Ndszg{n;u%9x4)_U^~n5ey>~l@t}lKAss%T5^wYVz8?>`gNC|mSXOuQ z(W;(C=P5b;+z%DOdMR-Oev>Ifo)doVIVF?|=@EUq8sk^x_j4X9f+|XUcf7gr=v9cH zdrk?ZLOQLhkuhPP?&r*Dt0>)RON=u)>driqLwoJhu4+<4vutemp3lR7m{uc8bw_Om;sWDnjeUa(Is^#^;lj{CH48 zsgO7lG0hmm`o#HOE7jvrMSEhkwfT6bW2x=;T#i8%iBB{ekcMA=GSE)Q`#}k%Li#|J zWV|8^wiD7rMNmbF6#>6EXAIzWLVBo3d?IboW#^8c$Jhz!K?$Wo`qHHDo&6?8_#spT zRg`EoX@awU<(dsjxh*P>{QOxu#zT*}-TeKJn~sXZPBU zlfMvN4^VTZKk>FRgJV0@;p=|KC!d#IX55cZ*EtS_{6cRhuo9aj`QO|38g|h zn@D2htWfj|;XQK|K@}y!W0D#xlMMetc+Z>?N+ms}<~8yrPWy%U;$cNlMTuFpiy42M zZvTb&;z0vw&lHMh&SF!aKV$YP)f2vT9_v!$%p(2#Pa?zI4-Lo^{IIp&U`Tm6GN0{5o4VNC2P%89LGY0&I>G3>ad%8xO;r|Si zgo@C5vHU}LT6eXiIA1+y`QtjDTVZ4`7vn=H6?&+-5`NWj?BK9u*|r$&bRI%QXuVjz zI`HYfZkcf2%~!U4+?)<;_{(5lLaC6rxFpCqx}y^aJ#y&NBF?%?wXML1 zEqvxgRmGqR{Kbst&bfUP8`0D9@;M39a(MGIrii<0P;LG8pj5cwBrRTpT%MHYcT8-k;jA*Yf&i_Wkx}LNM=Y$yY6?$T-sJCG)u6EYX5BuHbK~?IDo8HMb z0+F`U!nlE{`|2NSyKMwj<(eGkHkZ}qu@mM3Q6>LJ*YC#$>IGY_v=LO5{di*cbzYC3 z8b1+;zQ>ojFB}`D_pBdlBd7{{iF&?b?Cgscu4DTK=-cP5w-Ho@SEPNpC?5W)Ie5$+ zGAAtWoIU*WzxcNRUwRy>RL{WUYMqBKWlR1L7ZN-|b7-FNp(2#Pa+w8Foi97#h+6h( zZ&<#;W3+cuJ>!ECN`)ROUtugw!QFAU+Mm`UV?Co*MQFWP9yH;MbLA^sYk%%|HEh(Z zi`s=;J>+>%LaES0dboI53gcmS<&cDm(0Z}_>QMzA{^W@p_C>p7chu?-sZYL;#fMNT^ibJ3 z{Cla_vbaXI>7eJm^|whQv|cQq`w-5@&fE+hb$tXSdkld4V;@p^segO2fQ zkHQ;D8h1+m?oQFJCP$)MlO#sM7u7gpg%X$5PgMBRteP{mji4$lXK0Y$Xf_G=ER!Ut zq|dAK+;kjCQv&{r~4*GQnkxt{M;a&f%R_5RNd&5 zD~T+BIgez4u#@`gmHET{L?S++RQ78%G-Elv)$&~8l5>yr_`PmLBj(^^H+tM&-PAa- z;-oAqKgRx?Q&I1kJ(Xye=eiG}RMZ=O=kCX{dYy=3V*9o+lDOxnY2@v@N!I)9aVO(_ z;t4iC_)0Hjh<@u#P7!r!y$_*Ug&wN4@Ye&4%j(ly<;1l{nI+L}UzCyZXaiYq_4&Pw ziUVJ{@SKz%V;%d3=pki-#f;INeF&vO57k=6N~SKWkJ}L<%1_K7`|F4P&5aB%$IE)> zeACDHbo`ev^iY2Ai`MQCeaib%;#&E8K7>-ChiWbSn_)N0=%><$h?kQWbBxU3&5gnh z7C5lpz;Qi{Cx=Tqv8?em~JHqvyL*Mr?neYZ#fF zJIXjxx}~gl*12{@y@tzVS@|)xKX)bFRkf5T*7a}MDoQ97^@iV?+*wBN;3y*2_MR&} zj#LRZ7Tw+^>vb+}U>s|5&*le7d-+QGho1|Je?Io~AylhqYhj$nmC=`W$R-LG_*oKd z-j+9>pMNgvb%#5RC3n)uQLFqIYg)0AKI3$D@u}>OK7>-ChiWa%)R)TWv$iG^3r~46 zOEo(29;i`^W#tFoGZd_(&tDQKvemyKJt(16=%HE*|LVfVV)~J(hWXR10y@^EWjp1r zKB=i~#-THje8ypKng)t}2R(U-dcwwc2&#;;wt6aNtahSgt~1doMA^t@ay?fON?^I) zxL~7ofsQaICO`Eutn|6UqHv=sK7>*su{cdFqww;YK;-%^kl*W2S)~54h>nrwksXXv zD~fU~!+RA2-+5SXHVk|(0$F&<$#<*Dw<6Tv=LN=S7AoWVMfn=$-v`KlRWN&+u908 z%m=yFs=AO+d%bp|@R796pBi@;z205cFcMj8oRKN z>P3~>>!md@_D7cV&Yg9Kh;034**xMC6<&R3T>UT@o(=M|{O-`=BSat8LJ}%M2`sC9 zU-+xv`)QoLoTEjblNo&orNUONdpOk?e{}=oJ_7=ByGx9Y5la`w$iAc^v|cQK*+WiM zB+wc1F-E+**26*TqAEO|_rp}90*BQf#vEK3gBiMK26b>CXS-aB;ZMAW5hQtryE`?;ZYK%RG-9r_K!# zU7k(%A(RR|PL3aEJaPU69?y=xcU|7vTWkwDED05%^u@TT~yxWs`^)TF<@GLNvH^|7t3Gv;Vy6P;;6p8ipbolun(bB=<#K~dUk4%>u~y_ zVnGvK5-LLL#j=_!VSKo!y6P6GElM=arArlg=cPt4oh9UEl-eDPwcd;xT#Amx1Cm%nCQ5)YwMdB0Yv~I?| z4Ug=E^q_=NAw8?xFk|%_Ol^(OcC{r`kgAw98wtif~V zcl#15f+|WZ430J0C62$7O6$V1QeioJvtdSt2h06!$MP|N>CC>7FOb}x4~Z#T@3hl-$z5}B(lcV~Gp^nVaah4kCq z`P@qf#`+;t1XYx1S0$f&R@whWC>7H1}Iet11pBt8Mx&H2^)A?rdysjv*a$7$rxz|HQ;uA0)`B%re ztP2UH!ZOTC+%{i%Jyaw<0rLv~>U<^ZLPDvq46`e@&AVO?6^T#4{K&sL@5;K6P%13L zD#5?He#l6C0_J&cTR*(5QgtDrR9J@9j(>F>l#%!ZtZ>}64thOQT}UVumSK$Zude4Z z5}$x|m)q8JuZOA&38lg^BjKn7(f8e&f#OtBzLPDvq3^@_^$*-h`io_=% zbKp=;nLK<>Z?vw9I4;4WbB_NaKwtUy? zK?$Wo8oxHhT${mvU*3k(2$tg$m|w#$G&RhzCdbz0#y=He^t~@XI>!%6y$bI;ekluO zTr)Txk3Nvk-F;vz5O?ObaNaLE$tcsqL#PNPuv|VUh5P>RNOY>0*_|#`UGu=7Bcul< zlnROMzf5wUe?9_;>o@l}XKXDX4m_-;@9MG58T72U@u_B2*^=&$LJasn_4TiTU;i@J zXL_vjqqC5>u&Sz#b-_2nGJAHHkk)dLYz$*$-xu#;h+Xrr(0oTgF<7(B0uZm|c4aw=bx{^>4N?_T# zA_lyP%QbIrfscL7g3pHg5K4s}D*Iq8iqLwo{GC|t-q{8-nKt{f z@B8=eVe|I*-qM2-N`)ROi-OFOIhqAI}B&5K4tLsizDWwSAL@;&sC7MI*FcEaSbv zs||avsgv%%3cr!sJ^fE+d_t-4xO!TG9WQ6LP`uxG-)V%_i)HLn*lXbTch6_rpY*|S zk+4%gA3~|HCiT<@zbU)EL@4%K?7uWZ>%}t6JO=iDcsKE?#QsF(V??Q;E96*Hbx{@8 zgk#aO4$hfVB@|{if#Z-yD1l`pz7N}%kFjRcD(}xzDMlQ>xJ>R@sJf^MYf{hDFzeQ6 ztUM&4B9tJ0PIw#Ms`376uZD|HbNgzvE~>)gYHtAkLb_46P$yig>M8q4LPaQnW$Q|V z$MB!K?SC|*w-~bHun(bB=%MyF;Ma{yj0|lJ_dNG=51}HoUMyQZ20XU+9kD-KitmOu0L05p-7S>XFsI`x(C~eC!Vo`;8 z0gg^A_Ye7&$7L*JU>W)t_sk3=FOh_b#3#Nl+MTy3UfZyFFj^Oul?uzy6S-%Gi|?T# z@d@ZL+%xaSCsZUp0WIR->8DkcP%5OM$8hX5w)5~@D=UI3O29SaaP91bJabhS5=w<- zI0ufs-`7J$;uCP4Q6(u^{F6nHWe7+wKN+=c5Dxb4?$UCSasG$)<>wP^`1XYxP>*luI53dI$lnQAa zf4Cy}dZ-AhC;|81ZR=NF4@xK%($=ix$3sO>MG2gRY$M9+K?$Wo+M4J6c&G@fD1md8 zZD#O#P(rDY#u1DD-fM+~>{lv+DoR*uE#yA&=PMP7Phg9%1}_ndB~(#Dsqna!4fyd; z5mZqEuPj~(Uk^$s71CdFIC37cRoL6Gcc2P;H}*y>V-LYQ>h-{aBvd3mf#Yv`;F4AU zKcQ4ef64mdw~Dr%`uUtktZJ2t(6;;a@DkvGtEK0;*0YK_k$@|W>mc_%4;4Wb_~E)M z3ApOG)bA<#p%iV{kN z1YQliD!v{nLhHq{wLaPj=|KslLITDguAE;8Y?V9@N+=Z)&)wyJ%ttg>XNZ<_Na~_gV5n8Y1hik2$ zR#C!QMdf(J8Oi5&Z^l4lN z?S%ADk@$qQKH3TCK?$Wo8b&j&gLXoCs0gYkVXcpLLV8d_sgSnTM?2x;p;Smfi*OzE zL#PO?7t7ZA_+?I%U6R&CRamxG2|pex5}&ZvN4tkS4@xK%($>0SC*-xFgi;}4tygwJ zdZ-Ak7t4OvLFqvWr9#45we22~P!U=$mesl|FRJ=lM7D|&N`-`#4cI*-0WINklNMct zDje5p9fT_)S5#jQN+=c5IIrXU{{It7g#^wDIK%$`gi=}O!EwI){|TJYP=y4}pu4Lj zFYx~pN<}=}|36`Q$o$G`;r}3%3O%f=U?=1~r&m|0kg%?_@&C6UZ*}2iX*i+C0zK|w_ickW}>bQrvu(5?!x6labp(0d; z9(cduN?0D0P!URCSsnLyynV7m`|El?>7gQ2g&tOxVR=wOMJRz~b=>2Tv;AxBhpp|U zhl)@YdRQ5b}#3e?>?S6`?Bhz&RIZSYJX#D1l{l+(W#A-$8=^ zlO8HURp^1M4a6)DN~j1Wu&j=IJm4I3I2Y-mB2d5voEDHLv&* zDnbb?tK%L5#<&h6*PwM#6&}aguHLX|`56mo&}TIzRD=>(R`a7I3RncEbx{@ZcG_Ac z39G%f*_rrRgmtYnS{GH}aqAlTAykACSXRe9t+MX9^iUD1LJzAiSRRy65lUcL9rt)x zeOG#@2vwnn)!Vr*p(2#PvO4Y|tTCw5x~K||TVvDmpoEH00?X>S$HST#q=$-76?#~6 zjO9TI6`=%{)p3u9H780B6`?Bhu;xn3gAyu22`sDQ9uI4#mL4iXRp?>O`IZMIRD=>( zR>wUa)`}xNRD`O~!&)_HiJQe|G^C7@L@LJ7-{ z5IE=Jd_wD@Dm)I?(2a9|_v(5H6`=%{)p74VH*t2Lbx{=_hrZy(Ilz}t5lUcL9rqBp z2I71|>!K<=4t?7DlnQ@cOb8XB1eVotj|Z;hI6Kg~s0xq6*z`W7!drJjs0byntd4s; zFeky;f!0M;cpT;!1Lpu=LPaQnWp&&`z&Qw<9cW!tg~wqQHE<5_B~*kGSXRe91m=i1 zJJ7nQ3XjA6HgFE`B~*kGSXRe91oSC^vjeS*s_;1UTLb3+UqVGFfn{~vLtxI1vjeS* zs_;0h+6K-6zJ!WU0?X>Shk!9IaCV?|Q57DCdBoUL;Lr-jK2`b_^AaziB9y=~9{221 z1A%!75;FIpgi;Z2w`^4`C9L+!CptwCKZ~%gl}YQODm-poT|b11Py);9xTjUtJ(nIT zLRIKt^%Bd25-LIoEUV)l53BD=4;7&*^ssun;Y+9pC9tfHdkAX`3R)Lc;c;u!S{{^8 z5lUcL9rt)xbBXj&5voEDYxc1`D4`;hz_L2-@vvq%>7gQ2g&x){YI#sXMJRz~b=>1& z&D7FEMW_lrtkuBspoEH00?X>S#{-{lu&2-1vL5ZIq52~`t(nI_xJrwOrP?c4dv+I8& zU_8oa0`yR{uLo6GW$E$X2pEs@*#G9tP^<;tP zp=e(Zs#0VAzY|cee1bqi(Y_v3WtHW5{5Jy5Rz7oBtwKLJC)(!{suqOO0PQb>Lx-9yqc5)8+{7YLtm%xlPUi{B(coua|Y?@IM-fPqbcCl_#0m$%(oz zGedkrsqi>kI)ZP=P{0qNBB-Low-amgRX4Z8Zzsg}poCH(eeLhje8=W>^7j+%tx^$G zQKH$+jy$1$KVBw7>%y{9Vfk^Ak^FL8RzHM_#3zRMg zC3tP%>}9!Bz$$mQHKAWT&_cFKMX+8<;90}j{|`c`kRG4Evis7%)%_4Ef+|Yjy?`tK zKM18ldglCwuC$Ho_#spTRg}O!1wH5s5v$Ie5=w(-bK{ed%KFDiV`@+v2S^aSS-=Hu&h*A{$bTl=ZGT}z7PmVLPg>eIKN=O zMxAU`ES6|pSXL@5Urhd&b7v3y1+(~sio_>I%u2^EW=i>gl$`~57037Y7q{SU!97@$ zAh|m`XmEFT5AK@a?(SNw6eynL?k)~Rinc&0P74$(4u!&d&fI&Fvs`}sdGkCi=b7{U z%-NmYGc&t8yEm3VRK+0A=LGh2m|>`MZWSj;g*0SeRgDOry{t3*m7$V|J z1gVgQY!a9|F$5Ya26<4$39U?Rku5mg7h-UNR7gWM3CtZwj0kUZ6QZlp0Q(Nub~PGc z{sE!;66Eo2RSW^~OxP;nAk=cOj{z2}<_U#eKeqJy3LU0V!7GmFsW0r3W@*vF# zII=Y3z$}jP#8`9#nAx&QLd;yRk$}3{H>=Y3$c=y!DMi9#nAxGR+M+ z_cOAZx@N< za14Qlia{P;FWPv9z?t%Y5Trr^dTkxYVc!_!;q{`8XFBG{*9lS~0i%zOW4bRv9$qin zm}QusUnfX~1dO6O&N_Sv^6+}m#yr8E>FWfkkWd*5{fRF@9$qinm`&JUew`o{5||s< zi+`OU6%yDBVUOoakcZc+2*?c_jlND`2B8WGnq|fi5on=D^{vpGq0MJ9IND&|#}LZ+ zoFEmJ>zw%kO~PLXEBSvPLK+T|2>D}`#~xd#>jbIPp2Hkb^~r!ZXMK)6_o|Ti-&YfyAQcjH#`ta(ziQ<9 z=#x>1s$c{~bG>cF3G#3PZ7TP~z#NBMS24)LRTu+CQFZ^) zmmm)((57+^fjJJju40gft1t$P&gvT7mmm)((57+^fjJJDtNM2Ga23YD9Ebe$jvt&L z4=2#3a!(A*amaNQgFIY?F<^9#nZv=CJQzV9PM}TYo*0na9$xC&#?tlyU)4=2#3au0zy4!JIQU0j9bFb2n5v8eGp zh9D0o(57-v49s!JTor>nT!k?($00w3FF_topiSi-0&_h2ba@qnJY0n_U<_6>W?zCl zoIsn(Jp|@B&fR%kT!rN@2FKio(=<+yhZAU1xhDqZIL_U9U0j9bnB$P2-nQZdc{qVK zm3v}fj^o^&*Tq#>4r6f4T{TVP1bH}tHkEr~V24r8!@{PgYzC&)$#p6QdAJH=(32Ejf;^l+o60>zsVQykgZE#l806t9j6qLmd&immm)((57+^f%yknrDBkWt1t$w>hLAV!wIyh+(TggK_03Y zA_YjzWkcTP;dAJH=(5en!f;^l+o60=| z<{#vtia{Q(!Wguw! zj`;_<<83QWkcSg!Q@JMw<{!>Sd0kwE<(PjsyYwZZ~|>A_r$>b!}%z$i>t64#x6Cx^d-o{3ACvkiI{t@5$L&`s1hk=m*8Rd(ae`Dx!*LRD%wtb*QKs8CT_COk1fKoFEm_ zG-^9yD1tnw;zZ|s#YCfpxtuXnTXBL^Nb~XBxmDyr6(?v6_T4J-d`?UZNG(43>0j6? zPLK*|J~}(Miae;|#F^nY_3(D}z7T^Gq(YjH&dwO*K@}%Hj9R4M`PB9cF*rdgr1|LV zj6oh$aboU{OnR2#-M)oiWIRDo#xH&*{EYgzb4u3{H>=X+G9EV~__`oOqagnR`M9b_8Q$aDr4w z^RYH2hT3!Tpo$ZhPTXc%u?nLk6m5Q7t>Li&G? zwd6q+C#Ll%ZYB%P`GpvqAQjSZWr_yd{)98gNKB~dkWy07M8v{-&Pv1_S&k39z zLneG71}8{`G;JZ)9MigLtH^^YPWbFc1hS~&V=WK@bJ80_KwAma`NU8jZ;Tj%uEJx8 z2t;{ZXp;(UI5q-~`4?i4=W_y%lfd3DCWbP2U1*aEZ8&=b_Q^3s1X`aHq{4DID|I;A zV+nbHy1U9)*~5SH<82sgQv2$_?Y7lTgQlJiK1CF=H`bd}DBeR7hYyf@i;j z@QFbxBw(a=!wkSlsQn-huNQ5|jo9}fsdZHhPLK)-m~ogellejn^6+}mhHO$<<+~r8 zAQciY*D_%a=ZvAYiafktwDIZ@^TiQE?Kvk%g#^qQO_+;*AqIJPy=dcAFy@ORhT1Al zkO~Qy)v6rvC16gi&TLfitGoYAkmqxPVmo4}J?A|&zuuu<8woAq()cr0SfcLsn#!dd z<13A|SWaWRFF_vMDk9LPat~3UcDNPx_h1!+JY0n_XpZ7bkcSg!Q@Mwj9r%+Ok~Cb! zAP-kz44P~C66E0o+ElIxtwYk)A|3o{A+L+8u$*R@z65zVfi{(Uh!=ea8)v%>Q8CEF zRTzV2%f1A8IDs~mdx-XDP8v5ad5$@GxC&#?tlyU)4=2#3at~3vNHUr5dSkU8jwvTvb{Dh7GD3S-b6 z1Yd$YoIsn(J;bZVBjjIG0#pq0a23Yj_cAn%6Xf9p+Eng|G4fNmd>uJDn%BiuSWfp& zd=wKlw+4bt(pVxC&#?y)0jX zJe)wA$~{EcRqf=Izn-ZW4p$j5*9Mx# z3G#3PZ7TP~xS6wdPbaAG2+qdEmro_3O9qHzZt#HkOx}p3VKZc7&;E zQ=cAijTybl422Pgd+=9Pi9owe`P}X~-yt#ga#Zx4p`ERkJ%{=bq{5ogA6nure;j{* zFtFQUJu*e8eK37)Sq(f()`XfDvlmdmmkYm5ZsKpAU$E!syO)(WgC7LIZ0YQUyynK0 zb?lT~(>n;PchSsN=JWE29JHoYd9zGBi>P4ds+KS2S6uOT&UwAK9~2MvqkKs*yj^qq zOis_Q(URx$81M`2rstR6Z?4R1-agvFu65$R!BuEq=+WE!ZP{@hW5g00ij)xXMu*vM z_d)eLyzq_a-(uORGikdsN4SLgU#FnQHf4a2{Q4bax+Daaz+BG|gJn*&{;}MN>`qTfbSv zkxfJF7Y+MZSnt8ZgUr&|Ry$Oj)-?Ci#O8$g18vvTnJNa=i>i^&`k4do?ol+=q-oQV zr4n;QnEk4U=l8aY=kH?PE%(Tw;X|1_W>W1&Do$(Kh?BS7J5x5Y&zZ?p)>6Hw>bAC~Ic;|i zMN>_hwtUcI{Y+Q|yL}taubDUPRN73tr?f-GX-#YX;D~#FWnuqRAwb2TdQnxR%y;H) zx2|ZaNz>Au{zcD|BES76%JZx2eR^jyuVkz5P;pw*Iu82Yy(WJyd&1>V6@%(U)y2rP zW~u&-6iqd0+P2wS^h%2p*r#iIeqDa}z=!VS&AT{MoQ4>EN4s}7j$>!L(^AEtdQr81 z_Z@eSs@)V#HNnb+qZ9NhyAD~;#)sK>US+Jf%AM){Acu<6n$~Dfpu0d$(>i&xr;0)K zqKbM>UX!NXybz-QaI}||1bzt|J=E876{j_=``k47%Z^zkx|a%91oh{r;v)mpqO%WP;X{9{J!@%RgJ$&2IhU28;@sBy?20P}eF0R6w;4IPceABeip7ToL zdBr`PKpW0Cf#-3|xhvVZtLow^tO?F`fq4U$+MfK7m>=B33A7<^1mm@!JSF-q0NRag^@Y68bcP21ra2jzVj2f2q6Xv4TG zaNLayhMHn^Ahgi1lllP5jYQunfpjK_fd6m71ji^C4uuUO}pxuUrC%_aStcZhIyC3 z`JASC=WvqE;Z$8*g*CyfPk82uS3UDYSrg`o+`|d9V|%zsp1G)`xhU1eRajGO4>#fI zGVv**f-D+4-xWCD#&& z&fLT6MY~$oNBX0K*i)|`&~@M7g9+s7(B?h_sjw#RF9icJ&~Is(wNVLV&l(i5H*x?{Yh`&2cqw`u4OB}93nq0=%onqa02Z)T?UKYV^#t2 zqGGqmmT=5-K(6z;xC+a?XAcmQj*Te$U}l&cw8KM?hZAVWKhs5=eE1NE#RW%1u7Y!S z5ac?qi>t8Qdrk}3^ScwvW^UG8)?DWy$ioS=-;J&>X|Mm`Tg9!{XWIbj)*`Q+66?n}ye_W7a&I34#HD)E#FJ}* zGOS*(BFMvukdE8+$kzd)YB_wOShYh7eb@NBa(b3Z4uY#-9MM0{%PHP2sR=}Z;qmjm zDLP5K>J={01Ha>qql`Mo=r_HwJScfm{qCO;KqTx|MjyRpmH4fshaeAbI}vEpua0Y4 zhf*2cX;aiN_TL+(VsL^~7~`jllk{^>he3=U`)j%L*GeS|^=hC9+Fn!@j2B=0kfp8K zLTV9B8{B-8o-aCq+#b^0vFD!?^qcOQb}Hj2cfgZBjh8z*DuO(mK)Z736MEFz-mq1L z?rzt^?i@0Vfnh!bsc_G|qa6?v{_f$v5wyXW@wBhn4^m;hw6{*8ebI&br8vEf_P2+q z7}P#o#c8}}86j(In;aCsXWv~o7lCUvv!!1(b$!;fRy*_5>cWEG(en`bjw}soeKKAk z5~T9ZWYnEIU&3>DRMS2uW;P#ecHftnt_KzEiNOi3;`htwPT|)He)o&$uM@S3j59OD zKd$a;5$#KG72Q?C{rfh8?vWuubWDs0w9u35!!)z~fyL2imoGBKe4nMK8|@7brkUff zZ1SxBl&FTkh|g8QFDIKnp82kinqcS2^E7A ze9wt?#85=3u8l;A8fDep?AoV#iIhb$Dm(Ui@bj(WD!QV>{re)JVsPSWhta~+@2EW| z+IOqCimvD|#uo|IR-B;gGbD)ijX_t{sG_TQw5dg6hzPVkS8Xmk9ccp`I6!Xav_zK!7btcmvBDz551u8`R>Z+jKv+X#N|ooL?}T(vA! zRkOgVDk{de5&Rhf(Y`UbYU$YaX4(XWRE%#UpyyQ2Snw<%+BXJQMb#f-u6&VD#rQUY zKhq)FHwIVn@#@56ayZXs(Yk-F!4=2#hVkb1S2P0AO&ySID0*l%G7rImoPLK*?q-c}V{JAc^ z4Y=j?sF24Ei`z3Mg(!kNyk2Eb%Vp+@pBjh;^M^#0GOOE7>typKyef?GXN^*3_<@IR zO*`1{8H4pV8ai-+z~b;Hs7Ndb$hOsA?|kw*iO=&$>pR zTHe<_UUHLz;3{k@Izu(BMyAnb9lMDASAHSUb0ANAv$O~hX!nZrHxFh`CkiCZU~X-i z+Du*!*9c!)H!wP1!a#f4f29;bs+S9rm=B6&H%q(Ie?|;Sw!?M5Y$f}7m%NgnqnzOJ zG;QL?lJ4qns@j=m`a5EvigJb51izO4&)AUdkGk5$dS5hn79l}<%Uc1~Wt6Yz8hbt5 zKGGttz+*f4cvJK5m!+fmF-Mxt7){IHszCIikKuN~x_e#RgZ76$P0e&K#w(g?f-8eO z0j`KSBkfe1{Vc3Eb#w!B!anKd@i+}%x$T!SIx=d6-6dZhi+j-Svai1BceJjesV2DZ z6PDKX_G5qB`e%uXF@JGYv*)|-9V$-4)9@P)qef5bXV*BkR>h!tQFX^v#mv=fi=wF} z$Pe*6q+a(9_MXfSRgAm4OPg2f-*c!q4M%Y6?x-Ho?d*LK&r}Sm7gdz0*a}pWrkQ=C zLK@VrY0oI1#YRsSZ*FrHr{ULut#0m;30Ipvi-k*E{RQiH)td-Mchoi`jy#L5v$ltN zN0r`O(6l*StGlB+Ei;$7JOp_-;XYs2oHuNHRKn5t-o)-v4_tEnBmKi|C&5*}eX3)2 z-m=8C83_D? z6?8VNxwE}1<l_9n1=a0|Nug%Hs zT7000J?NtFAxMQpzC8iv>Kyn>W+gVKaxbkBZoIfRSnUU_R#)%c;17HqLxt(I*uO2zH#Ah;@O ziOWoPXs^B}T?-)kjhN`}wezA;^Fmh#!Bw~)a5Qy1nwr+m3{fSD_ud zJ`s-xybEB!y8u1}shles8%FPNWuKbF$o=C;$8U*Q99&pL}w4K33Yg@#}EO&mW#2NK>Z4YN{Da-4iWGaTftgd;i(H)(uIIU?n>NRzXb#3jFeP0>egEp)~SKl>2nrecxWLE|K z#P)7><(FsG%4PC=PRu#m#;jcrR}M7)v9UYpvA*{Hd>a)(9!{VQYtq#>6*Mi!B}1Q? zf3V%5{&*jPRJc{i#&t6v9V!Mf9xbfvj;c4pt~W725#-_Zq7AFnz29eeG^vz+a?&V! z&AKb<7;u7A7-Rm>p618n7enCwUaC;{&VR%0$$Lk;xQEw^Hmp|nexIT6@k08Wjp6p% zJ+;lx2~uHsrA0l=QvF`SRqCdUrQMA-j<9b}%4=~CuNQ4tlkWXK!@~KQ^e5rN>?{xJ z`w*nUnw~uDV7`w(!L4btf6U{y`}VUB)?23t^6+}mhBfKlFFLe+9#>CSthfDO*d8B( zR2bvty2j>-)h8iF$oXXM>?_*Y)$Tr11bKM9Xv1oC@B6g}qRzRd{@cn}?SxO!D=|L=495TwGIVn>|W zGnYrV%vsDfH@Fl*9$qinG}>v}t@lB)?Yecw$MU)4*pns9Zd0!7=YOoB&N1q#F-GiY zuwr+R%rfJcF{f)rm9?b$oQ4?Q_iMAyE+I#yK4CoXnpF|x;Y87&@|h2Nebkrjz%N=C z-WMbTi(fLDK2Pl+xC&=WFrODVpVzbmuvL@q&arx($fvHO=o%2W9kx)-29PM+e1>~o zhFWkuk{k?@XI{*){@CXs$ioS==^ZmotFS3Z_PZTq6~kf1llG%e4fU}>&< zZcLt?K+W`NdvQx1AN3d2lBH8EO)UaF!;?VyUE~`hc!Y=GDtcQ1V=&@fpv;ghmAo2p zU0oHGN**kp&3vkQQF^-q38LW{{j^{?=seA9H7$99Ao;9&PFe839~AMZ zS*R#5V7rPz?}A_qiU;=qB7)_kTK+O>-j6;6sW1j@t)`Vt6(s*?5+DaJ@1}^hf%Qe` z$EGRN%;jh>xdnu<5yPjntplLhs~k2mVOv0i#t z3hmgpom$lmmZ8nQlWW&M@F7UWw-(+|5J9s0?jmx|ue~hvoc$0g#?Jat#h`b-csxyu zS1DL7^e-YKa&_||Xsh_vYTAHmLGn&`4w<|1Rz4DdgZw z*L(<4VGP<@SgY1HNFIsv$~d1pq3Riibx0u6h89sV=v_jLLGj>M@%)2jhLBgr-oy!f z2vT7T+FDIJ5*8$<3_N1=?UhLp{U`jQuX$;x81zmg#-MnbHZygwT=(jTaV#RE4?!x7 zL0b!F`;Z`cciJqY-^~1qD7ko={-Q%I6@%XGRL3Lc>o8m52g`kBXB$(`d3sS!&{km# z+FDpCJ1$7R?qA&4lc$7=abbCKePpr5Dh9oyiZLi2yzTTRNWTB4gt2SBr{CoSsW1k` z*0c+=g5<`!9mUi8K`O?TevkKc$311wYy>>&wkJdfH5eZrZu}3Bs=vSWUd5DbYMVN4@g0 z5j`#AbQ9Lrp8hYSW~vY7vgD(D2vT89vCo9B1-^^=Pt4cjzVf_rNFH7<+W%EK z>q@a_8pNoXFTbmz>xMqyo-aWvj1l{6yHtie(P>5&GOiCEp|*-Vyk4|hOq!tADK{Bn z?E0gI>tRr^(fQSIAA(dEBla2ngk)8t>(pLhbRE!N5#-_ZqMbVVZ~Bg($3ToS$@;j~ z1%7WdtKH9sAQi@lU2E`aWRK|TUG5q=vv*Pid3e2OH|d*7{Pw6H#Hi46vdb^!Bg0j= zgAYL}j1jwLV(0b=(Y5xck)00KQv`WaoTp3uRYtTzrux4+U$MwQ*C z2=efH(GHLk#k2EkA;#5N7hO4r^_9imZ1N#Ug)!*KpQfexbSC=#`JuAuur`Vy53d*P z3}>c_t^M#Fla-Bbxz3ClF1zQDJ_M;SM(lIvQ_cT~e%UZw?k+o5J&Pv~uNUo;b*76! zeKNpr%ciRH*j4mgxE%G&vzCh!q{0~Vlw8x=zquE^wp_SOzi+8}l1m<5FWPtaO%(|< z7t%GY;gq+o!c9lX9trOI5TwEw^jsa*a-Mn~9kyVo^jqD*;2vHt+M#JDim_?dLyU#t zar9={2Fu>t$NLbZ!kXy0x~6ry^CP%qgqI7$)Z;q{{Z;@K!s{Phcn@q3em`uA13 z%gRlE@gYcsF=!Okw78k$xvyt$E$>eFs0i}#deM#@Yxx>4To;NfWv?unCeWspvQ+L_ z@%uG`uTLdfO-o|dGf-U=gI2L(IniGyX!S1=M1P&2HOWX2{dHoeOewO=ovK=a=olgb zEvzd+k`L~=6`d+9PnhI`z5vQ&2sC^M*b+Cch(^LE#uo|LTQ{z6_U?zGQ5d^Q@AIvK z7Iov=V=O27>jWG%6IVwgLG;%NIAcsaGms$q>%=OV(#+^>U7}-%2(+*+YDKiEebA<3 z6GNb(2&xNJpU1cc=QPY-(+!vFiZ2S>dZdcQW9%Lng-26=k$JA#4?41%b_fWpzY`E# z<+a_uM9|fSiukQ;3Y!y$N}p0Ou33u(r!|ceT;;XhzQiwOQ>YkauQs$f(f#CKDn{Gl zD+H%CjT2nuwcWl1w2^^(4sB+0qIa5j0^4e^wNh|e(?$XD@j>-KXft@u8LR3Kb|T0X zUn2X{%f_zTU2KfwofVrIrpy;)<2?FR%9(oYI~B}bzs`drxajf*qvo%D?TTANb?)H= z_KCEL9qK*z%IGqyt$ps=t0+!z75{<+Jo(A;)|mLTjlHbH!XWP9gmZoSPn$}~^DP4H zpZm0Oal-qig^6$N@z|PnB3%Kw^m%#v=GM4w?%_n`^DFgUt6gT4HW&7M>!pEGKQY59 znDj+Rya8MFhg*xAW6sSKySi=HlRpVCKUS$AA`b4*w^uJ{4oEu#h;l_n%6&&NT8##8 ziRKiVjH10of~&4|+n|3px0IP-^=#OWjz??CENe2`uj+(_aDuCxZPgsU zwKN32wS@b@39h1YJT_{7Q5}K*%{n;Hjs17ZqB{iH_up^w*qa8a@)!aQ?Q_-Ha$Usi zct8Aq5dQ5t3W`Crrri%6toGsE*l`BMh}kOdmOMD#U2W~L8hc?sCdCi8-$hInzocm= zxJS`m;?}AD?$Y`&5x>hWAO@stZ;$=^to!%BpBkLts@kFL+-pWgh@vm{0a5>Hkgfmw zPVezFNOFR!PM@l&wyJuvXdtGv$z^x@xFBj=bg1MWPP}YV)BPdC7_m7m5;ew+v-*ts zC*(lrUaD+xH{U^URffC$-R*j{7P-%C0K$LrD3!H`&EHMF zRa}MTlwEL_Gj6cmKWpXgg z(Wh#dT=++Ri|$$B=p5`nSTFHgH4&I+naFO9*MAvPSqy75ACAW#Bd;3cGj@_^Gki3; zhZBijOw>i&P?5Uj5+I_}KQ~I1Z6nish+}brs~%UIrQaM@K}@l51`yHUU*lo9R0}-|(mpoIsq6~PD+~NdRz1*-`zcDRDoZLMJh=%Dh$qN;# z$zS^vv$%&7%}cG&?X`xuo)=@}3@Rm?zb_#_-TP>Af~zilT(5t3qO1sVEdnBbpbyuU;kMC4a0xt&~OF`gNrkP~?UFQ-*@##3{`4b@>+?-`}iZ zX!m;A+{1~HuKW6dmU+dd37F@9r0i(?xow%z`DK`c;Hn4N|J0X_4i;qsFwdtBJ#Wb5 zON}|%TiV>i30LM{^`MMJ#rC5sf!O`>Cu2zWXv6=bli;d+bx-O8-vx_3@ZKk^d!1ZG zj(d_-E{&JL(Ym~SNvc*LA0W*Q{+tN`^|MhpH_}&y2_i(~pVYhy+8LT07 zrAXIvX;an z7G#`8E2UkJZHS z3u`dOmafLYe=^BIw<_7(!-?oEoAo;h>WP$jFh;+Oi;a$hQ_3g%Dmw_S>a^%5z3+rd z;#g&j@$jE{M&+(4WuqCPHurEMY{M~q#;j0rKJE8F#5ud#xP4ZWlkU}W5M1@5tEK-^ z&k$J_Vn(@NEjRK!jU#ivsAY2xC)&^dMgOHvMG>@j9T1ss?=r&A-ZN^+-P%6Yce z8~B^C>`Xf&ETWywvxsNy)YDh>-yY`?V?VBd7&lHGGiK$eWcW?%Y;zAM{3CAY8QfXK z;qFMZ`7@Q={bzHd-o+XYf~(?>KdZkyok!e#y9|gVwf*F{PnC_!4eHw5!-*B&UC?KC z$ST@}A(61@cXIrgTE?FGB^(4-{kiL?p5$X5@xwUm+f!vJA@|HEZxrklXmbxIN>4ei zzYNYMiax|%)W}#{-U|*f22M}qAh_zybz2`6kX>AVk9po?_ej~)?=P|F&|K4dWuoq1 zN`J9?4_>QX-Zen3nI6x0A}3nh!wF}e7o6Bhmd=~sxc=_EgWxLX zo{u_RUk=Lpqp`Ba1B<$M)D{%n7ONAh?QW zfu?1Ts@O^rI zdApt^jZ6GhZ#nEo(>6)um6XY(T|1x6J)GcM3r|L~ekTuJ$RM+|J8yA6#zIA>%@hBDcS9$$k8`0n8 zkgY2D+uXwmzO|Z`%rCnPUshb^Xn5S>1XuC77OeRFBdhH5x}{#Dbyq9M z$?*h9IKlT1uALw6G$NL}Wd6MA9pgD4sjrrwrZ?(S zO{7kXb2vSEmyzY)5c%7V^fvc!f^RL{0|>choPJebzMdOxae}M(j2y=EGFOd$pBl)x zBGPhrSc~%g)3oh!psbf;rg8k;7?by$yrpOY|K05PRE&QHd zf(YZ-!YZ=lyEKmZ6`wgd_D_2?&uz>bT1);F{Ex+FWL(9scQh?>@qFV*y$&+@<=u|9 z;;rB$=09j57eqvhI{#>newU8`yw8XC)pndQmdsgbtZCcI=Dix9aX5R?4S(k~<_wHu zte!i}9@1D7M?NJJXP&JTi~2v)1IqY`JdIWgeqEwzhljQ`22Z^xO0*baa}}SLIEh_x zwi#xX*P`>1UJfEt+&lV}ZhoR^f)$SI9f%Qm%!o7hXHlnhcblvDyoAStHNw~9${VL| ziu7fgJBS*mf7NsB@)I)UGQnw0JJZ=uCVa71)W6Ws<|;lfaT0Yl6p|6U4~c+$hJz?q z^Mu|$U2-vD++x9L=zV&ZkhzPm5<9w-vAK%RWSm625!GeJcPqud7Fiv{n!onz#>C_z z{fGsE)0$TFL~R+7c&xY`KZDIx{48-2X}{|zk8SEHa^?Ta;zZGBk@|+jDMY2za|Ne0 zt;NvJ^6~Ww;=-hB7FY3EjgxqKZJ=D$GOZ}kYr2D&wt2Una$X8?v;9oLY4~#F?m_Zk zis$-}OA{@w;&Ux0QSbUFdA?L#{hzs($qAeR((@rs!#%RsqvZRg0s6<=d(=FURD90p zBuYVyk*8X@PLv{ZXdWA$BJUn1%gt;pat?DoUE(VKL^d=`a6<>dpG|QZ?hbA%Bm*a|(uc2*jwe_=SDeJhxz*)~ zdvQhl+SwcgKaV-BX~9k4N!*|rV(qQu4uT&8PQ%-Pr8~;CD{JbT@7{Af?c-;@lc;fb zplp|-hd#C93S_YjRly#2e~@iOUR;Zc02x`-=|z57E;85WQwk`r9@A^#J1-!(~n8=WtqaBXJH9up^&2p~puZTLe~r zjudvfTmf>|#1<~@;RLRMq_y>$mUdHByTV(4*-d0D%?YmJZxU$QpoqqHz6h!*F5gss=#}7>~oFN%cPTP=-k5z{(b|TiSJw3^Pa|)5rZ0qaDuCFy=d&4 z7N1IYw|`jui!rIiV;3j*n|jA)RW|QOPV{b71^+O++QlQr!IKL^xQ7$`%|Lik5<0{# zwq>YsHs`NVoZzZnMQWRuW+e2+X#IAe-F)kGV`bsdI`?pbzqJQzYu}HsuddE!{Co3Q zG$**q`KDfzzem|4Qo7AOLsz&S-l=OE>yAX?*}&gRZMnXd`5`)u+jEv2PZDl7+qB(u zEq(9e9!~K0{NRhE(}vltvedU+XO={Bf~%bG_LbP&)owoNS8MknP46|OlG$habQPVy zm%8C9aM8IKfrk zTv2b!!`<2xW$e07O4|E>PF$7~T=i3jB<7J8*}YrkSHiG&H7R269Fj}t9!@ylybo<( z!u~M1tljSI;xe4zD*jHrrdh)>+6&s$w%b3<5y=Uz%5nROyR!JsyH!EeGTT=Y*Rrpr z`xwGKoN&H*FMoe$-R{@MzJ7F06eqZff29K6UOqq1YX5wI-M&Y?keo-BxW7+aK}F~9 z?LQn=%ssYxP48Cq?zq+}w5*>!v}2TudpO~IyZ_Yw(bmFsgYC9ylZ9}CtN3>mV3--I zSv}s3w5P9K>e_xNN%WJwbyaju-3r&HgPAP*<_*B#)? zk@^cWUkT6CI9?Z5QMu=Jd<7Pj}S@-{uI zyeIW7Db^eax7%e}@8TX#@cq-YjPY`rp{K*`c!39_IKfr4Rh~WncXDTAJbdTgJ38ZP zZWC9b(E1Y0JMW5b)3YvIJZWN_7sKqS@y5BhhZB4YH7#|aXX3xoqwH-ZBcnLMRlG$s z?dSdN?bY8uHpJG9QGA@>eLEi|VBT)$vLA9!d%1|SQ#eKg-kt&UE3ZasMnd zJHl3dm{e*HC%6i>Had3Ci@)_ZtDFp%$A;(AxrYmmiPD^%~AS=N?Yzn}S80e_w}qh|UMw8hd*r zvx?S*uL!_8fdArTF>xJ$Kdb|IT`7xs2i5_Mg!^;RpOTq)e-7S{nxEJBdEOy&;E3Ti zSFMLTcgf56nYrQ4os-D<^q6sIa2zXH-);_~G(1Jj=FVasg{O#|*0jgPwi)XV*yg8Z zy=|__4R`J$yZM<-;Le?sI55^v`j5V61|)3gAa=r2#Q7bvn(g5!BB$Z&-*4l}UaNMR zqt7(AxvC-Dx%;@&&oto9os;-9sf7F|$x*X_yR?I-0#6bD4bEm3gQtj`hB3-6B)|9~LK;!BfOQ>2L0Zr-+=^w7Yso z*)m;KGs~2}EUqdJckad|PGMGnJ9kc^Pvjt(aC=HKu){4vAFoQB`W zxjj%`Nd4YDd);)4tMFdN!@2Ms7`SuiBpSj!GMT5Y+YR^OIDvQ7XazQ>AqL!&IX7^I zxeo5h@Kw-!wX$IN|w|C>3{;~Ic)QV`{qE5mE_m-|lta8tfy|<(Yew;ZCtE1u0 z-NRX}&EJN4?%dJ(Z@z`j{U{IjeG(_`;r=D|zK>c9&fCXHq=S1)^A^-}Z;idTqzJz4 zoQ4%Caq=2>(+)7>!@WMS0_9%vJncfG;}09mwAg?|0XOJCJ-!cy2ql>NmIp znQ~Y~vozd+JXXL@Hy>Y9VE z#;zV`kUs2jRrBQpT+gs_&lw~C)h>3Hq#sP~;Y8DTll210Dx0Z~F9gDGMYOT`NH=@e zo>CSkxT?y+DSFvmmCX!QF~*yVrZKE$3%l;Nz1AZ+OxHTqG@q1ODL8#;&ouq^-=Suj zUHEK!{@@)(-EJN1)~Od;+`|cHj6FMF8{b9OvkMnq=^(gj&E}>0#)XjQ@aIL|J z3Yq1aNk<RpZj^(BpInhHtT8 z>-vujl+!-uvLBS+XmJlG0`mW;kFFkUUTuv>uwB#IGHS?}_Etc$dXJoank^kKX)FA#-_syvsS|Ondq4SyL-#-~|W4ReY4tv^B3f z$i)v@S#htQa*Q9G;G+c0+)}PKveqka*B5E+l;b1xpZ=+5?yt92@N+EHz&ZNVhtY@u+xbfj*AF#pZE!-HdpNPU8N8dZxvJSdF3w9_Sx*}$V4NKhmDoXW)wIBM`qeg- z%|feiCE&jNr;W|c4BM3~iOoHnc(!zq2J zUUM}(c)WyLbv5n3#@1;8cKD6tHurGiT7w_;CE0{oZ!xa2u$!imY1?PC+b&G&Ah_zc zF}7|cEp0A%f?HJ~XDXR|c?P@M!gMzGaAK~$Papm+*c`tKGb-|7UU_u-1M5Vg><)sf z(p5XHTa62u9R}c5#oRmdIS zAh?RpyWpy*d~sQ{c|XeX!5w;Iu#vxdR(tOK^7ax~lbFiY%*55){2Ysa zXR*HTbX{}*ZCpW@`)*&uDqFz*xnLRi9ne@0CvJb3udn{TmiaIju4pu_EP!v~E+*8}>BBo)otb8)L4L~k|5c1~$ubCtKbhZA-DqV&8g%9%qiV@5r_ci8wt zk7r*TSII$e)tdch^(SLP%(Lrpt1|z!-zf0=2PQkO` zM$=(;tT6wY4uY$S<-4lSzWSZn;Ro%^ifN5o0mFZ z48P0+jVD?SYf}CGHurF%;NiEr>s$`AUmA?jy8RdG~6QN6@bYet7Qj@ISG>^i^e8*b?4xc~4hN#13OF)#QJtKyiJ z4uY%r*#plY@6R>*~PGY*2Q_&Z11b^oXRtOdBEcd;;VkNC} z&g33WRGYI&kJuh;UYLmMsp~wgDi5aiwm*1a$w#j_NPzJ9q$iv6`y6oDvKliWt3ILDz%`G#p>$XzL zQB!lvdGWd2RkzO*UCL2wmsX-%vB zCXd{*TG*K)>R8;v2|kmBrvM4#$`(hO*x9p{au8hQJc29U#g)%{HMZlutY~o$C-{sU zTK7RsnYUD!b#*n&ec1gAK8Eu-Dy;19TT8CU+sg{u=x1{eC-`hY(?Zkg^3*Snt-Qtm zbIe}3iqEw*t=1-&EOFzJmA2|9$DEoId{zU$<32r)O#5GUJ57;?4uY%rH3O`A>7GZ1 z>DlehGafsx4LHGPXRv;EsGqFRwv^rT-y05stN67KJnaKw?uKByTHV`@YaCASStk5i zTG$<9eZ}f_`D&LP1XuBEIQa7L#yiG!tD1f6%@xPB8YlQ{8NPp2c%u>1j}y8C-A$E=Uv_v158XsdtH$SX(2SVxOgam*|^arXEnz3YQQW{D9v z3t!qjp?tmOvgJ+!D>~S`maF*8S<`- z@RTfUit!-6%Wgk0r-R@sJ|lt69xP zjyW7B_|ep~lIgA(w{I@A5~XV4Ah?RpI5q9|QPcQ1vc0w9QD?`@k`w%_gn9egW5(s9 z4Xn3&Iynfg;&;{I>1%@t#x;@Dz7SQ@=5wkb5Txk&liYj z4^a~8#u!&17AL&6Ql(lmLB)9Aehb9l1owP_i1rZsp^Y%ceE5n7C%m>&6(~7L#en;m z5Q7uk^93T>L(E#;MV>r*&Kf!Hu^I4dxF{Yc+P&%iNs%RKZ!vN~Todg!`$vkX;gRmz z{SHEmc|aTjA|nvo!-*=HdWwk?;+P)dVWAdMj5uoj@ouZd39kBO#bD7>+wG1M9tkmS z15pKtcR+9tC)};Nh+QW>c!^av;P*vGY_|%p@UuC=Rc(&+6wOcn=-xHuCy22fh%G>5 z0)l%ualTM%vE2RKON>gCQ~E!dWvwk0;vl%{?fZHnS+76c_#FjJtJbX%+`CFDvp`!x z`f4UekX5vStH zf1#~7!BwzNCbX6AY2D30i~`~*5ZuFwxzFmE+Xm+l9%AOyK>N&+`v$fZC%6h)!GyNb zJ*_(ti1R??27-GyadKfb^LCER!b8OGo7SEl&ovDptpmj}XUER~Vv%?H~Peegk z1lo$X&$7qDoMu#1t;_cb<_tjW1tK#L+{1~~?RE3XhVtIl-4zgI|Jf^td<1R939jP% z1YZjU;w}((f#4oa{CcspneJcR+qypn<+Pi_T4Zc1PH+`(1^BIBAesSD6bSCROo zm?sAYds{bhNql?9kAEAD?v!y5T$N_0Zf?(!R(%5m?iv)!V^7j5%3RP^ynT}F_BUU) zZlzk6?-M-j17ZRYm&QIexrY;DyJt6_%x>Xr-L{>x*mFjgk@ujjIKfqXpI|%(Vm1)T z{@rSE4=2to%WVE!v9Y&x7gtMSuS=0v20&YJf~$Bdz;CPru^tG2Ah?GUYa`N{ajaV2 z*0s#L*25nX%aO-RI|#1YIWV``@`vKy)=g3~zFjn5GkF}^inot_>y5kD^nR*!`98r{ z(ts!q1ojNv!-+B1Ub(B!>*Ht4WCh|991rf{#J)#Q z-GPU@ds{c-((6|Awo)=Xv=t|~inju+5b_duwsQ|BHnjW8y|HIIZ|hcV8)X%FnMv+^ zP|87Ym3$e`EV!hKw{YWR38)Zo;}z*1mJCV%D-%?jq^>cw4tu$*ET3efi|y)k--CuA2Vlkh?^U z=HAxbvvH^uI%<#%gtp?_&f99d9^%fOYP`3tBE5tJf_peI&C6V4H z-UM%qVn7TAVid&S9!_+Am{>oUZK5~E?LVp;zZV)Rael=Ku6mthu0H(3Xm5-+KwJSL zKM>r*iJitgy<76J-Wcmk_civVtR-{b@v}P~o2>t^xW78K@C_M#f%of414qo%A8a4# zJ+IOyTViY)Q9;(6o7UzYPQaIx^w{q$ZBE$2$kd^ceAFqfgWxLoE|MPmy`_V#!;L?C zbb{YFh_>KsMml{ZiSLt>c-5_~(csT+@?zC(7WZ(1Z!LU_b@o=H&G}w30NRST$+NvT z_42ufsP^Hsro9BB9T5LPzso(Gcy{Ny9+7R3_jpVS_#W<4x0BByYaIkrIk#%Omv{mM z_wafvj=rLoDBQ<;JaSy0W3+r!Rc3*#l;>s7yf6yqYa`=9>+<$Vks+OkTGmmuF5f437XXL? zK(t1JwGSuO-%2A^>~HUF-DBJSGP>n%AhE4D!Bu>pG!2O!Ks*3~dpP0WD5Xdq+REFy zi~LU;@1tF+tvJC|ycOV$Tp(Tnksn%@dpNOtbrSK{kcQsY-P&ZMksxgr`EQ*N2fC!XytCMLt%D9T*>*6Zj3h*v65D$UC_9eN-#191h8 z2lsHIP`-BJc#$OD)?IbAs9av{oq>7I39jO;08eFrSO`QBAh?GU^Gh@p3HHYGw(jmL zspYGj=ZuxJN;wFw`jp)e6RM^5w(d`1?Pc}O_Y9nu@b6J^t_ID4fsB38WOdE zNC^b@aN=&pp<-N_bGqj~!%@Al{O#HA2DTL^xQg$SrXg_wi0eRb4=3`Z{eO*}c~}-z z|HenfC4~@|7tIAX`l*;@hzLA0;|^*rxS)nBNN#|LySPA#B9*=dZ)&M!zV_P4Wd4_KD zHN9|Kp=Qmzm|zvVpeWrzoB(0Qy?2h)a!&-=2v#NCh*5nitdj2DoH<9I68^IG7QAAA zQZtsQF|~@qtiH>~q$syR%mXnD1V@27MFe?z#te)D<)XQ$AlR@ zh~6Nq>n=x_IM8;X`fA|UVeY$He*OUc{EXU~l>=acRqTSI>;SO?gq4%w2ou+fQ`FZV z9SL)1ymm*o)1$&3tKq)~*$7ts(mh@+_V<sR1*x52bPeO~4g z$C307HiA_t-6yMlAMD@n&L@7>d9FTbeW?)vuh^fp)6&(4{f4>n;(SbapA*DB5XB%k z!o>EGi`1C6hRE!B(Y8dr@713TD}TiVtN56(`W}dvKv=nOjxcd2AWdx^H9+RVZ-)%h zb84P5EU%bg6}x~+4iKpztlrKMCW3rssly-ll)3P?1KQ~gGWQspCI#CFR&_l-Nu9p3 znbYlVk8RWR4zZc$_wb7S;inFKOsG!;5e~wdJ9C5yex87*$Z6yB2_@F*a*V94|0SFegXkvZEJmCX(uyn zQ%4)Ys^JgDsLkfDmF{|X)J^B_38?@0*tAwqEnB6R*AeE-3+fZ=9yF5YP1AkvEw>S@ z;yeoKWNv30g)5TuWwC+VjXw^@Xv>{qdhvm#i#EvuWhD`|@U z_)(^fU=`28QNwbpr%O%W!TVqpuT_n=Icj8@`NduJeQWC42v)gP3oc*F zJ1>8xS-AQ&-RpvF^wk;nW|YD z5uh7gI$DIYY#)5I>;kIpOJdC{JDTV#f75IPXEvEe&0X@J=CWINv`W_;wwyla@$Ft6 zs_~6kuSHe8-D%a9r{>%=)2KDL{E2z-WL^EvLd}+Yp zSB{l?BKKoF=S=CT_9>XI-yisn$!8ItgM0=n%BC+jX%V&S>Dk|g*=E~3!?w5Js+mRF zsb^L6Cc0{yLGrATX?#Pv>7QEZ#@pJ`9-3`d#4{nL@nxV4Z+&&0e686-%{J2K(LK|6 z;y$pU-b`Jr4eG7iMz1_#Wg7K9f&RKOteJMGk8T^0@hFUGi~ycujjfaY)U@9<+bDxa z7EEIlp4nRe?D!Ppw*i{%&dGO6rWNJYq8Ih|m$fl(^jB?n13m|tMuw&QU#dRi#1gAQ zpx~?H$5pE)0H0ZCQTBJ)|Ch`0N2<;$Nrw^P`n!y9f5nAWWq(^^(Xtu@i~ipPtE`HI zzemhi;jXNhUwp8faMv@q_ac84sknZkY#;wWajn>0A>#Q?zRI-yI9SDXAb*d@U7zBr z-gv(GE|qEfK3K)|EPszU6_@DRhcyag`mcQ)K2{|!fB0aRifVCObvd^xMjKwJ(Yc*z z)rCLFEZS@JkfeJ}+jI3!<<2oK+Iok=PH=lL@%jEZH-Q!Lnf~inS%2|wXX1Y!hefc8 z_h%>ieBVZ-966_EpAQwh4|dw4-vr~~gh6uVHS%a1;rzBpo%u9WaD<71keSBzi^JsH zdD+vJ;>z*f+SJK-|AV&0syjzU8M6{|S*ZtD&|L025q&fi=%!Q^cY>wY3$gPYgb{cPr_J zHh!WjU&7}jR;S#SBKBXcsddc2Jc`aiCidQ2X!xX#m-&*0k?|tM$6HH{-)AzxDn8Q` z<$UKvQD|1ynm*WWa)gOb3sQ}rugA!INsZF}A}ywpR>QxhV1iZLnwUFpA1Df=e^obp z>?t_H1h);oi4-(WY*>FrJN&O=qhaj@#`7--mp@$lbE|Z&QS)s>9(fRm91vSUaD)l2 z>cMIY2VWP8L@(z;;Rz10aZ?^uHFOPf^2oDfTL2!f#uIj;PDYc7;tF~L4wZT&` z!7A=C7%hQ_0Wk#xN0_kpt2fTzJ)Exp)K1{Yxo5C%+?t9q4n#VLLJ%Bbf*rw{1H0Z3 zAI;CuvT@{0u!>s~Ghq<#ftUq?BTTR(in6g$9}$zEtfk_}nP8Q@muv$u5QOC}N0?v_ z6(u-wu$~c9T~tYP)sdA~=B?U3RDIFQ->~kYXiciQ3j?tT#QUkPIeU`Gu(NfXEOu! zJ{Nv4zh2|2BP%CZgxQF38wt za)h@luVV$)7)4Pgw;L#)j;?CX-Qp>jU{$NVGmH|ySeeBMX%Z;ux>C=h)>SiPMiOt9;UQhj$TvCA>g{7>hOHiA_}FN`;a zE*~%RKF@N;it7`vn1gU-2<|?~Xw>yN*VTZXR--2vo&2lG^Za)Z_dq;?yBuMHJ;Zn~ zdZF$3(c!IFngCk6^hxm3)tsY|9KdXrfxQa5tsz?5PjL4P# z(%noD3qhQOyBuMHJw#T`?-kMU(gRoDWr9@|pLH`@Rq&HnQ9lr^L0Ij<5hmDmMQNE- zTkPrkrFrA04mN^SQT2NnKh#qU_myE~rw|d|rmZM~yIv=Q4gX3#UGB2eT4V&otL~g_ZTO!KmF|uO(HO)z5FBBGT}RdZ*^1(v$FF8)at9m1s);WK8qd}= zmhSHTrJ>NhB1CWW#2WK`jjWL|E_d1Kx4ZnqXtrdubay+5ZXk}qU5+rp9%Ai;v^wHh zgetDUT_#x7czrEn&ZxY8ztQx zIws1TuzZ&I2|Y1>dmU%#-Ni0<+37E4)pk}ooi5$=05KIr0^H>Y6YL>YpgGseyxMk> zSY!2F+7_!;{ow5kN6WhB2Kzu922mO9!4W3dLq&NsyuJBm<4AD_UNOO{(3h(_8yuS> z-MtAS6U0>z9ASc8M@3`Bdgh1PD`Kq?WFuI0_v)dy z-7Cg-Cj*7Y^&lI;sPQ~q?z`;t@TKh>oAt83 zdkw_zAguP_2ovlf@(fM4s(Bwy7H8lU6RZl>UvkW-TGn?xLF@owT^TsS1bc`%r`KwA zw$EU38eTEMsu!YPbbR~iZ0YWMAZCKF#ta-`f?daRoIR1tV8`=S5YQdO^G#lzRwkEuRk|QbcI)&9giGc zL#DdiWv72qe{t;Brbu_2f*1zEY7dSu!5-py)XIIDckD>K^s?P#f>k3&6gw79oFv`d z58`Tw z;>dHsHiA`HgWK_GzhTnd3tcMd#fOK9ui#b0SB=!M9wS}uveO$DHB>8i7%tsC4dOnC z*U%muVS+uxw@k-A)>6Fs3I+ElCRml`tf$_&8CB*kh`AuH!d;Fq!5*SU`0^!fOK`9_ z53iVDm7ZHmEgaHUy1N_1RuEQZf+I|@>v+4ralSU%Sx+?F9Be13)do$jtfsH+A>I9Q zQ8PV$Sy#~-UX6%T)%}HCUGB2e#TUZVY5`rOyQe@*1aTJa!4W3dLu679*Vlcjg@~Wv z6%(v_*dO0qpQB25*Gs}`4~{Uw9%2=!f@=CFi(7~*@QMjm^{euVno|-a-Sq*H1EL57 zN0?yO@#V!oZfLofpKr!jl$c;u%R$Z653mZ9dnTM*N7LKhYAII3E6&ie)0|aRl!+h$ zL9|DEaD)l=5Z@9yAE<|Z+JhrZu!s0U-aS8kmGASy%GNT$ zD$c{A?iIvJ5LSC|gbDW0S{ctn-;{UP?9@5LMzE?^O;tU$v6gh#!?Tv&E>f6-!|XLI zygxfp)jL2`*mBF5+s9G%e9)E6wl-m2gn66cnf##6F7^+Z~~ zkId|ys^Gi`=Sz4?cna{Kn%Ms2D|64Qn&7!U=Ky$1s9UODY|iiftC@iH4SD{`^IG1L zqNFS+G)J{XTU^ov&&hbM##_Qlp53#|n7#FdUu9kJJcH*Syd|uyUed`NFrm39s;LVe zJM);Dw}dLadfSW#wOfhJrJCUJAdeGyOZe_<=UtAqD_V=$r!>K193K1dmhffkjTN=) zMgJ#$O4kJ6xA}g~Tf!Q2`5hvj6}9 literal 0 HcmV?d00001 diff --git a/khi_rs_description/meshes/RS030N_J6.stl b/khi_rs_description/meshes/RS030N_J6.stl new file mode 100644 index 0000000000000000000000000000000000000000..385b9c1955f4948d248cc85a4b2835570155a1ab GIT binary patch literal 10484 zcma)?33N@@8pppTF(gDuP&x>XidI!TNh`@YX9ulPR3bqeQ@v6#R(0^6A@??hD%E-& z9yL8gQDbQzn%sMj7Eg6Vkx=s()j?78m3n*cv(N26vb)yHT3KtaeE;A1pR@P(ef#V~ zc21XuTMjP|9NxS>c(`F;#riLfH2jeNVe|Vf+qcc>)V5$p!RdmtGdIj!MgP~&POf_3 z4xjOt1CK2t^0NnjOAF@Bo0k6F!NNo}E`WKz=(zj z%#p7)Z#5zZK8X|NI1F_PaUqIWVFj0@Edt^Nr7#r6Ck8RV|{f2THfaSgDd&*w=52zTQK6 zU_?U%w;d3775}K7P_$Id`uDcLv1JL?KuKJT@f&U1xgHqN5Wyq+g-6FGdP31sHGJjE zfw=PbkkNdR* zs>+((NdGi8)p|k_B^iDru8He`5hM=fRWqwkZWCO(S9okJ@fmwlD-x*M{@gh8?F&g( zKS@-%ns4Mcapwvn<%nxj%|4~~2N&!S9%D*l zTU`%~ATg<6yVM*~x zm6XuioGgh;i+slXVmC`Lg2a>#DOR_rhXP$BvGN7K(SC460#z;FOS2Nr7pB{iSle!r zQFqUivOX|^#OyZd*0qLt#rH}gF>{vnVZFZWQkNU{X)}Lm{KO3FnYhSetgc$0N0`5D zu;kx~8gOC*C(dyKBS>J~5T$N=(muAbC;RRu0#!3k`prp$QV?b!LlWh6@k&HLUf*OVr#!+2Op0VkV67lcw0mozRk%9W z5d?OF8aoCUIW^&KF6=v zcqdu;znF)*)|Ssv{;n3yZooROYRK*z__K{Q`0ctlYgf*%rnoDliFWqCZg)GM#D?yv z%#c78dK1m4APktLogzI^SD|9e+KVA%QCNCc10X zV{B*E7CXDo85?Wx;;YG4?3~Hc1O12^9c|5wRcGy(&D9tZs6ua|Dh>LwwVyw0k2-(C z#u|KWxMi*H7cD)|kMHNh9%hXr7TZa~V;K^tLT{q|dj_)Nxy!9Sy1C~9khSQSg6%wdIZ=&0lM6jA=sm?N9gSfvA{e81p{8m%xfqq22{~E#G z?RKwIiPr}bs6ua|qD;sBAis+vdI`QK?5{e>T(d7(dY~WC=uV&5qrc8@PVqWN0#)eE zk1SL2?7Z%eJGs2WVYkFSh<-$u-W+8gHnN-{yk8-KD)c7mTr?**uU21Y%R}Y+?uw0- z0=@s~c53XwM89M&4zBw(*V$UVd~e4$OQgdD69n#kN+mlrz6Xcziix{I0{2~{iH0s6 z96H?Sac7xx)y6xSw{~LS=hNq14>QA^5sPcC=+tH7o)vA3Q+Emik89Tiy zLjqOkP1OGOMvnNsf9zQsPeS7Q!bfyC^dkzbyTxf8YVH&+j$ufk3cZP9`lLJCk|Le@ zS5Mh^q7(BZ?o4=~AJKDW1E)_$O{ZB_b%q40(3`0Fscz1(<}L4M>M%h2j`U~?}U;j z*I-DX3cZQ8G#}(dJiRd3Ytc~~zZ8hKn8r_MG!-7`$4`)}GaV!P&d`XOw|ZYD4YS^dsuW`_;yhwoLRZ)t4lJD)bI_Y6hKJeiy-hj(*|3 z%S7MBeF9bJO*A`yy*010k9`zTYP4EDL7vr4zI#XDrv1a@nQ4i?^E1xtYpmY2e5}Ex z=wf~+;Rq6Vh9f#Magx2Q!x;8b-W>rvzUi|nV!m+c9wTZx?|96Lo5$jR*cVz~wz~);NZ<*H=mgK*{d?n_ox^vhA%QBD)5@dQZQa?6kHk4G z9$j065hU=0#J}(I`s2UOrbBDekU*8H&7iv;ork2b9t)G58Ku*UFoFc0kcf`*`uqNa zEGKvB^fV+;rFx9=cq%ELz3_aNv#woM5k`=}6B6GCdHrpT%yYIb&rCxCRjOAi5C8d6 zyYKPA&b6d!MHoQ>Pe?=;c>SH}FvdB)Bqj|BRH>e?Jcb;ZWEZB5aSm*r_7O&qz;j!8 zk8(mir==o+s;w!b#NOq3Tw8Bhm3)qK(prZRB+8%F_&ylq`=Halztsu}RB>;4(sS3` zBg8+eVMIrWw@jjoy#CJexw@I~XrbbBC{JOo2ND?35w6DwUVl6InhOskys`Vf>z>f$65d#-cuvc6o9lrDMs$Shae>#L_!S;Vcw?dBwJFbS zt_Knr(GjkPcm{E2!UG9!EL6P5$a9x6K*Adf74Mbu+~#^9fe{_y zdWf77nIb%p@Ww*Ld%irkxgJPhL`S$DqBcav3lAi`u~3Qnt7CinphvWLYUL7)+)Q{U zJ)WmbQR7FV-B)qXusp_)a^*{n6I>Pl(ok4ma z;f;k#bqVEx1V(g(>!CWF^gzNJ3zh12$^!|E=m^(Cb!zE>gf|u{)wPue5*X1Du7}!j zqz4k-Sg7y}CwES_E#hEAL#Ryr zGs4Suab1;_8V`(U2#p64UbYJlm6aL~jA#gr2NGVk3lEi*!HRQ*5e=cT1m_9~FWbd+ zRaR;|Frpze9!PlEE<99LYCJHaAv7LHc-byIR90#{Frpze9!PlEEZRYc=~5e=d7KtheB zim$i$Dx&egh=$O3Afd)m#q(Bt714NLL_=sikWgc(;%{f+uOi`!@{1beD)E-;-AVY3 J72gJl{s;WJRl@)P literal 0 HcmV?d00001 diff --git a/khi_rs_description/tests/roslaunch_test_rs030n.xml b/khi_rs_description/tests/roslaunch_test_rs030n.xml new file mode 100644 index 0000000..8e670e8 --- /dev/null +++ b/khi_rs_description/tests/roslaunch_test_rs030n.xml @@ -0,0 +1,6 @@ + + + + + + diff --git a/khi_rs_description/urdf/rs030n.urdf.xacro b/khi_rs_description/urdf/rs030n.urdf.xacro new file mode 100644 index 0000000..dfa8f88 --- /dev/null +++ b/khi_rs_description/urdf/rs030n.urdf.xacro @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/khi_rs_description/urdf/rs030n_macro.xacro b/khi_rs_description/urdf/rs030n_macro.xacro new file mode 100644 index 0000000..dfa8f88 --- /dev/null +++ b/khi_rs_description/urdf/rs030n_macro.xacro @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/khi_rs_gazebo/config/rs030n_gazebo_control.yaml b/khi_rs_gazebo/config/rs030n_gazebo_control.yaml new file mode 100644 index 0000000..7c8acb7 --- /dev/null +++ b/khi_rs_gazebo/config/rs030n_gazebo_control.yaml @@ -0,0 +1,51 @@ + # Publish all joint states ----------------------------------- + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + + # Position - Joint Position Trajectory Controller ------------------- + rs030n_arm_controller: + type: "position_controllers/JointTrajectoryController" + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 + constraints: + goal_time: 2.0 # Defaults to zero + stopped_velocity_tolerance: 0.1 # Defaults to 0.01 + joint1: + trajectory: 0 + goal: 0.0 + joint2: + trajectory: 0 + goal: 0.0 + joint3: + trajectory: 0 + goal: 0.0 + joint4: + trajectory: 0 + goal: 0.0 + joint5: + trajectory: 0 + goal: 0.0 + joint6: + trajectory: 0 + goal: 0.0 + + state_publish_rate: 50 # Defaults to 50 + action_monitor_rate: 20 # Defaults to 20 + #hold_trajectory_duration: 0 # Defaults to 0.5 + + # Joint Group Position Controller ------------------- + rs030n_joint_group_controller: + type: "position_controllers/JointGroupPositionController" + joints: + - joint1 + - joint2 + - joint3 + - joint4 + - joint5 + - joint6 \ No newline at end of file diff --git a/khi_rs_gazebo/launch/rs030n_gazebo_control.launch b/khi_rs_gazebo/launch/rs030n_gazebo_control.launch new file mode 100644 index 0000000..08c3f70 --- /dev/null +++ b/khi_rs_gazebo/launch/rs030n_gazebo_control.launch @@ -0,0 +1,18 @@ + + + + + + + + + + + diff --git a/khi_rs_gazebo/launch/rs030n_world.launch b/khi_rs_gazebo/launch/rs030n_world.launch new file mode 100644 index 0000000..39b63f5 --- /dev/null +++ b/khi_rs_gazebo/launch/rs030n_world.launch @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/khi_rs_ikfast_plugin/CMakeLists.txt b/khi_rs_ikfast_plugin/CMakeLists.txt index bbf6d28..9db7901 100644 --- a/khi_rs_ikfast_plugin/CMakeLists.txt +++ b/khi_rs_ikfast_plugin/CMakeLists.txt @@ -87,3 +87,18 @@ install( ${CATKIN_PACKAGE_SHARE_DESTINATION} ) +set(IKFAST_LIBRARY_NAME khi_rs030n_manipulator_moveit_ikfast_plugin) + +find_package(LAPACK REQUIRED) + +add_library(${IKFAST_LIBRARY_NAME} src/khi_rs030n_manipulator_ikfast_moveit_plugin.cpp) +target_link_libraries(${IKFAST_LIBRARY_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${LAPACK_LIBRARIES}) + +install(TARGETS ${IKFAST_LIBRARY_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + +install( + FILES + khi_rs030n_manipulator_moveit_ikfast_plugin_description.xml + DESTINATION + ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/khi_rs_ikfast_plugin/khi_rs030n_manipulator_moveit_ikfast_plugin_description.xml b/khi_rs_ikfast_plugin/khi_rs030n_manipulator_moveit_ikfast_plugin_description.xml new file mode 100644 index 0000000..53b7647 --- /dev/null +++ b/khi_rs_ikfast_plugin/khi_rs030n_manipulator_moveit_ikfast_plugin_description.xml @@ -0,0 +1,6 @@ + + + + IKFast61 plugin for closed-form kinematics + + diff --git a/khi_rs_ikfast_plugin/package.xml b/khi_rs_ikfast_plugin/package.xml index 051219e..1a4d510 100644 --- a/khi_rs_ikfast_plugin/package.xml +++ b/khi_rs_ikfast_plugin/package.xml @@ -14,6 +14,7 @@ + moveit_core liblapack-dev diff --git a/khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_moveit_plugin.cpp b/khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_moveit_plugin.cpp new file mode 100644 index 0000000..d256c7e --- /dev/null +++ b/khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_moveit_plugin.cpp @@ -0,0 +1,1400 @@ +/********************************************************************* + * + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST; Mathias Lüdtke, Fraunhofer + *IPA + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the all of the author's companies nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + *********************************************************************/ + +/* + * IKFast Plugin Template for moveit + * + * AUTO-GENERATED by create_ikfast_moveit_plugin.py in arm_kinematics_tools + * You should run create_ikfast_moveit_plugin.py to generate your own plugin. + * + * Creates a kinematics plugin using the output of IKFast from OpenRAVE. + * This plugin and the move_group node can be used as a general + * kinematics service, from within the moveit planning environment, or in + * your own ROS node. + * + */ + +#include +#include +#include +#include + +// Need a floating point tolerance when checking joint limits, in case the joint starts at limit +const double LIMIT_TOLERANCE = .0000001; +/// \brief Search modes for searchPositionIK(), see there +enum SEARCH_MODE +{ + OPTIMIZE_FREE_JOINT = 1, + OPTIMIZE_MAX_JOINT = 2 +}; + +namespace ikfast_kinematics_plugin +{ +#define IKFAST_NO_MAIN // Don't include main() from IKFast + +/// \brief The types of inverse kinematics parameterizations supported. +/// +/// The minimum degree of freedoms required is set in the upper 4 bits of each type. +/// The number of values used to represent the parameterization ( >= dof ) is the next 4 bits. +/// The lower bits contain a unique id of the type. +enum IkParameterizationType +{ + IKP_None = 0, + IKP_Transform6D = 0x67000001, ///< end effector reaches desired 6D transformation + IKP_Rotation3D = 0x34000002, ///< end effector reaches desired 3D rotation + IKP_Translation3D = 0x33000003, ///< end effector origin reaches desired 3D translation + IKP_Direction3D = 0x23000004, ///< direction on end effector coordinate system reaches desired direction + IKP_Ray4D = 0x46000005, ///< ray on end effector coordinate system reaches desired global ray + IKP_Lookat3D = 0x23000006, ///< direction on end effector coordinate system points to desired 3D position + IKP_TranslationDirection5D = 0x56000007, ///< end effector origin and direction reaches desired 3D translation and + /// direction. Can be thought of as Ray IK where the origin of the ray must + /// coincide. + IKP_TranslationXY2D = 0x22000008, ///< 2D translation along XY plane + IKP_TranslationXYOrientation3D = 0x33000009, ///< 2D translation along XY plane and 1D rotation around Z axis. The + /// offset of the rotation is measured starting at +X, so at +X is it 0, + /// at +Y it is pi/2. + IKP_TranslationLocalGlobal6D = 0x3600000a, ///< local point on end effector origin reaches desired 3D global point + + IKP_TranslationXAxisAngle4D = 0x4400000b, ///< end effector origin reaches desired 3D translation, manipulator + /// direction makes a specific angle with x-axis like a cone, angle is from + /// 0-pi. Axes defined in the manipulator base link's coordinate system) + IKP_TranslationYAxisAngle4D = 0x4400000c, ///< end effector origin reaches desired 3D translation, manipulator + /// direction makes a specific angle with y-axis like a cone, angle is from + /// 0-pi. Axes defined in the manipulator base link's coordinate system) + IKP_TranslationZAxisAngle4D = 0x4400000d, ///< end effector origin reaches desired 3D translation, manipulator + /// direction makes a specific angle with z-axis like a cone, angle is from + /// 0-pi. Axes are defined in the manipulator base link's coordinate system. + + IKP_TranslationXAxisAngleZNorm4D = 0x4400000e, ///< end effector origin reaches desired 3D translation, manipulator + /// direction needs to be orthogonal to z-axis and be rotated at a + /// certain angle starting from the x-axis (defined in the manipulator + /// base link's coordinate system) + IKP_TranslationYAxisAngleXNorm4D = 0x4400000f, ///< end effector origin reaches desired 3D translation, manipulator + /// direction needs to be orthogonal to x-axis and be rotated at a + /// certain angle starting from the y-axis (defined in the manipulator + /// base link's coordinate system) + IKP_TranslationZAxisAngleYNorm4D = 0x44000010, ///< end effector origin reaches desired 3D translation, manipulator + /// direction needs to be orthogonal to y-axis and be rotated at a + /// certain angle starting from the z-axis (defined in the manipulator + /// base link's coordinate system) + + IKP_NumberOfParameterizations = 16, ///< number of parameterizations (does not count IKP_None) + + IKP_VelocityDataBit = + 0x00008000, ///< bit is set if the data represents the time-derivate velocity of an IkParameterization + IKP_Transform6DVelocity = IKP_Transform6D | IKP_VelocityDataBit, + IKP_Rotation3DVelocity = IKP_Rotation3D | IKP_VelocityDataBit, + IKP_Translation3DVelocity = IKP_Translation3D | IKP_VelocityDataBit, + IKP_Direction3DVelocity = IKP_Direction3D | IKP_VelocityDataBit, + IKP_Ray4DVelocity = IKP_Ray4D | IKP_VelocityDataBit, + IKP_Lookat3DVelocity = IKP_Lookat3D | IKP_VelocityDataBit, + IKP_TranslationDirection5DVelocity = IKP_TranslationDirection5D | IKP_VelocityDataBit, + IKP_TranslationXY2DVelocity = IKP_TranslationXY2D | IKP_VelocityDataBit, + IKP_TranslationXYOrientation3DVelocity = IKP_TranslationXYOrientation3D | IKP_VelocityDataBit, + IKP_TranslationLocalGlobal6DVelocity = IKP_TranslationLocalGlobal6D | IKP_VelocityDataBit, + IKP_TranslationXAxisAngle4DVelocity = IKP_TranslationXAxisAngle4D | IKP_VelocityDataBit, + IKP_TranslationYAxisAngle4DVelocity = IKP_TranslationYAxisAngle4D | IKP_VelocityDataBit, + IKP_TranslationZAxisAngle4DVelocity = IKP_TranslationZAxisAngle4D | IKP_VelocityDataBit, + IKP_TranslationXAxisAngleZNorm4DVelocity = IKP_TranslationXAxisAngleZNorm4D | IKP_VelocityDataBit, + IKP_TranslationYAxisAngleXNorm4DVelocity = IKP_TranslationYAxisAngleXNorm4D | IKP_VelocityDataBit, + IKP_TranslationZAxisAngleYNorm4DVelocity = IKP_TranslationZAxisAngleYNorm4D | IKP_VelocityDataBit, + + IKP_UniqueIdMask = 0x0000ffff, ///< the mask for the unique ids + IKP_CustomDataBit = 0x00010000, ///< bit is set if the ikparameterization contains custom data, this is only used + /// when serializing the ik parameterizations +}; + +// struct for storing and sorting solutions +struct LimitObeyingSol +{ + std::vector value; + double dist_from_seed; + + bool operator<(const LimitObeyingSol& a) const + { + return dist_from_seed < a.dist_from_seed; + } +}; + +// Code generated by IKFast56/61 +#include "khi_rs030n_manipulator_ikfast_solver.cpp" + +class IKFastKinematicsPlugin : public kinematics::KinematicsBase +{ + std::vector joint_names_; + std::vector joint_min_vector_; + std::vector joint_max_vector_; + std::vector joint_has_limits_vector_; + std::vector link_names_; + const size_t num_joints_; + std::vector free_params_; + bool active_; // Internal variable that indicates whether solvers are configured and ready + const std::string name_{ "ikfast" }; + + const std::vector& getJointNames() const + { + return joint_names_; + } + const std::vector& getLinkNames() const + { + return link_names_; + } + +public: + /** @class + * @brief Interface for an IKFast kinematics plugin + */ + IKFastKinematicsPlugin() : num_joints_(GetNumJoints()), active_(false) + { + srand(time(NULL)); + supported_methods_.push_back(kinematics::DiscretizationMethods::NO_DISCRETIZATION); + supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_DISCRETIZED); + supported_methods_.push_back(kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED); + } + + /** + * @brief Given a desired pose of the end-effector, compute the joint angles to reach it + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param solution the solution vector + * @param error_code an error code that encodes the reason for failure or success + * @return True if a valid solution was found, false otherwise + */ + + // Returns the IK solution that is within joint limits closest to ik_seed_state + bool getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const; + + /** + * @brief Given a desired pose of the end-effector, compute the set joint angles solutions that are able to reach it. + * + * This is a default implementation that returns only one solution and so its result is equivalent to calling + * 'getPositionIK(...)' with a zero initialized seed. + * + * @param ik_poses The desired pose of each tip link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param solutions A vector of vectors where each entry is a valid joint solution + * @param result A struct that reports the results of the query + * @param options An option struct which contains the type of redundancy discretization used. This default + * implementation only supports the KinmaticSearches::NO_DISCRETIZATION method; requesting any + * other will result in failure. + * @return True if a valid set of solutions was found, false otherwise. + */ + bool getPositionIK(const std::vector& ik_poses, const std::vector& ik_seed_state, + std::vector>& solutions, kinematics::KinematicsResult& result, + const kinematics::KinematicsQueryOptions& options) const; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param the distance that the redundancy can be from the current position + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, std::vector& solution, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + std::vector& solution, const IKCallbackFn& solution_callback, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const; + + /** + * @brief Given a desired pose of the end-effector, search for the joint angles required to reach it. + * This particular method is intended for "searching" for a solutions by stepping through the redundancy + * (or other numerical routines). The consistency_limit specifies that only certain redundancy positions + * around those specified in the seed state are admissible and need to be searched. + * @param ik_pose the desired pose of the link + * @param ik_seed_state an initial guess solution for the inverse kinematics + * @param consistency_limit the distance that the redundancy can be from the current position + * @return True if a valid solution was found, false otherwise + */ + bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, std::vector& solution, + const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const; + + /** + * @brief Given a set of joint angles and a set of links, compute their pose + * + * @param link_names A set of links for which FK needs to be computed + * @param joint_angles The state for which FK is being computed + * @param poses The resultant set of poses (in the frame returned by getBaseFrame()) + * @return True if a valid solution was found, false otherwise + */ + bool getPositionFK(const std::vector& link_names, const std::vector& joint_angles, + std::vector& poses) const; + + /** + * @brief Sets the discretization value for the redundant joint. + * + * Since this ikfast implementation allows for one redundant joint then only the first entry will be in the + *discretization map will be used. + * Calling this method replaces previous discretization settings. + * + * @param discretization a map of joint indices and discretization value pairs. + */ + void setSearchDiscretization(const std::map& discretization); + + /** + * @brief Overrides the default method to prevent changing the redundant joints + */ + bool setRedundantJoints(const std::vector& redundant_joint_indices); + +private: + bool initialize(const std::string& robot_description, const std::string& group_name, const std::string& base_name, + const std::string& tip_name, double search_discretization); + + /** + * @brief Calls the IK solver from IKFast + * @return The number of solutions found + */ + int solve(KDL::Frame& pose_frame, const std::vector& vfree, IkSolutionList& solutions) const; + + /** + * @brief Gets a specific solution from the set + */ + void getSolution(const IkSolutionList& solutions, int i, std::vector& solution) const; + + /** + * @brief Gets a specific solution from the set with joints rotated 360° to be near seed state where possible + */ + void getSolution(const IkSolutionList& solutions, const std::vector& ik_seed_state, int i, + std::vector& solution) const; + + double harmonize(const std::vector& ik_seed_state, std::vector& solution) const; + // void getOrderedSolutions(const std::vector &ik_seed_state, std::vector >& solslist); + void getClosestSolution(const IkSolutionList& solutions, const std::vector& ik_seed_state, + std::vector& solution) const; + void fillFreeParams(int count, int* array); + bool getCount(int& count, const int& max_count, const int& min_count) const; + + /** + * @brief samples the designated redundant joint using the chosen discretization method + * @param method An enumeration flag indicating the discretization method to be used + * @param sampled_joint_vals Sampled joint values for the redundant joint + * @return True if sampling succeeded. + */ + bool sampleRedundantJoint(kinematics::DiscretizationMethod method, std::vector& sampled_joint_vals) const; + +}; // end class + +bool IKFastKinematicsPlugin::initialize(const std::string& robot_description, const std::string& group_name, + const std::string& base_name, const std::string& tip_name, + double search_discretization) +{ + setValues(robot_description, group_name, base_name, tip_name, search_discretization); + + ros::NodeHandle node_handle("~/" + group_name); + + std::string robot; + lookupParam("robot", robot, std::string()); + + // IKFast56/61 + fillFreeParams(GetNumFreeParameters(), GetFreeParameters()); + + if (free_params_.size() > 1) + { + ROS_FATAL("Only one free joint parameter supported!"); + return false; + } + else if (free_params_.size() == 1) + { + redundant_joint_indices_.clear(); + redundant_joint_indices_.push_back(free_params_[0]); + KinematicsBase::setSearchDiscretization(DEFAULT_SEARCH_DISCRETIZATION); + } + + urdf::Model robot_model; + std::string xml_string; + + std::string urdf_xml, full_urdf_xml; + lookupParam("urdf_xml", urdf_xml, robot_description); + node_handle.searchParam(urdf_xml, full_urdf_xml); + + ROS_DEBUG_NAMED(name_, "Reading xml file from parameter server"); + if (!node_handle.getParam(full_urdf_xml, xml_string)) + { + ROS_FATAL_NAMED(name_, "Could not load the xml from parameter server: %s", urdf_xml.c_str()); + return false; + } + + robot_model.initString(xml_string); + + ROS_DEBUG_STREAM_NAMED(name_, "Reading joints and links from URDF"); + + urdf::LinkConstSharedPtr link = robot_model.getLink(getTipFrame()); + while (link->name != base_frame_ && joint_names_.size() <= num_joints_) + { + ROS_DEBUG_NAMED(name_, "Link %s", link->name.c_str()); + link_names_.push_back(link->name); + urdf::JointSharedPtr joint = link->parent_joint; + if (joint) + { + if (joint->type != urdf::Joint::UNKNOWN && joint->type != urdf::Joint::FIXED) + { + ROS_DEBUG_STREAM_NAMED(name_, "Adding joint " << joint->name); + + joint_names_.push_back(joint->name); + float lower, upper; + int hasLimits; + if (joint->type != urdf::Joint::CONTINUOUS) + { + if (joint->safety) + { + lower = joint->safety->soft_lower_limit; + upper = joint->safety->soft_upper_limit; + } + else + { + lower = joint->limits->lower; + upper = joint->limits->upper; + } + hasLimits = 1; + } + else + { + lower = -M_PI; + upper = M_PI; + hasLimits = 0; + } + if (hasLimits) + { + joint_has_limits_vector_.push_back(true); + joint_min_vector_.push_back(lower); + joint_max_vector_.push_back(upper); + } + else + { + joint_has_limits_vector_.push_back(false); + joint_min_vector_.push_back(-M_PI); + joint_max_vector_.push_back(M_PI); + } + } + } + else + { + ROS_WARN_NAMED(name_, "no joint corresponding to %s", link->name.c_str()); + } + link = link->getParent(); + } + + if (joint_names_.size() != num_joints_) + { + ROS_FATAL_STREAM_NAMED(name_, "Joint numbers mismatch: URDF has " << joint_names_.size() << " and IKFast has " + << num_joints_); + return false; + } + + std::reverse(link_names_.begin(), link_names_.end()); + std::reverse(joint_names_.begin(), joint_names_.end()); + std::reverse(joint_min_vector_.begin(), joint_min_vector_.end()); + std::reverse(joint_max_vector_.begin(), joint_max_vector_.end()); + std::reverse(joint_has_limits_vector_.begin(), joint_has_limits_vector_.end()); + + for (size_t i = 0; i < num_joints_; ++i) + ROS_DEBUG_STREAM_NAMED(name_, joint_names_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i] << " " + << joint_has_limits_vector_[i]); + + active_ = true; + return true; +} + +void IKFastKinematicsPlugin::setSearchDiscretization(const std::map& discretization) +{ + if (discretization.empty()) + { + ROS_ERROR("The 'discretization' map is empty"); + return; + } + + if (redundant_joint_indices_.empty()) + { + ROS_ERROR_STREAM("This group's solver doesn't support redundant joints"); + return; + } + + if (discretization.begin()->first != redundant_joint_indices_[0]) + { + std::string redundant_joint = joint_names_[free_params_[0]]; + ROS_ERROR_STREAM("Attempted to discretize a non-redundant joint " + << discretization.begin()->first << ", only joint '" << redundant_joint << "' with index " + << redundant_joint_indices_[0] << " is redundant."); + return; + } + + if (discretization.begin()->second <= 0.0) + { + ROS_ERROR_STREAM("Discretization can not takes values that are <= 0"); + return; + } + + redundant_joint_discretization_.clear(); + redundant_joint_discretization_[redundant_joint_indices_[0]] = discretization.begin()->second; +} + +bool IKFastKinematicsPlugin::setRedundantJoints(const std::vector& redundant_joint_indices) +{ + ROS_ERROR_STREAM("Changing the redundant joints isn't permitted by this group's solver "); + return false; +} + +int IKFastKinematicsPlugin::solve(KDL::Frame& pose_frame, const std::vector& vfree, + IkSolutionList& solutions) const +{ + // IKFast56/61 + solutions.Clear(); + + double trans[3]; + trans[0] = pose_frame.p[0]; //-.18; + trans[1] = pose_frame.p[1]; + trans[2] = pose_frame.p[2]; + + KDL::Rotation mult; + KDL::Vector direction; + + switch (GetIkType()) + { + case IKP_Transform6D: + case IKP_Translation3D: + // For **Transform6D**, eerot is 9 values for the 3x3 rotation matrix. For **Translation3D**, these are ignored. + + mult = pose_frame.M; + + double vals[9]; + vals[0] = mult(0, 0); + vals[1] = mult(0, 1); + vals[2] = mult(0, 2); + vals[3] = mult(1, 0); + vals[4] = mult(1, 1); + vals[5] = mult(1, 2); + vals[6] = mult(2, 0); + vals[7] = mult(2, 1); + vals[8] = mult(2, 2); + + // IKFast56/61 + ComputeIk(trans, vals, vfree.size() > 0 ? &vfree[0] : NULL, solutions); + return solutions.GetNumSolutions(); + + case IKP_Direction3D: + case IKP_Ray4D: + case IKP_TranslationDirection5D: + // For **Direction3D**, **Ray4D**, and **TranslationDirection5D**, the first 3 values represent the target + // direction. + + direction = pose_frame.M * KDL::Vector(0, 0, 1); + ComputeIk(trans, direction.data, vfree.size() > 0 ? &vfree[0] : NULL, solutions); + return solutions.GetNumSolutions(); + + case IKP_TranslationXAxisAngle4D: + case IKP_TranslationYAxisAngle4D: + case IKP_TranslationZAxisAngle4D: + // For *TranslationXAxisAngle4D*, *TranslationYAxisAngle4D*, *TranslationZAxisAngle4D* - end effector origin + // reaches desired 3D translation, manipulator direction makes a specific angle with x/y/z-axis (defined in the + // manipulator base link’s coordinate system) + ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet."); + return 0; + + case IKP_TranslationLocalGlobal6D: + // For **TranslationLocalGlobal6D**, the diagonal elements ([0],[4],[8]) are the local translation inside the end + // effector coordinate system. + ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet."); + return 0; + + case IKP_Rotation3D: + case IKP_Lookat3D: + case IKP_TranslationXY2D: + case IKP_TranslationXYOrientation3D: + ROS_ERROR_NAMED(name_, "IK for this IkParameterizationType not implemented yet."); + return 0; + + case IKP_TranslationXAxisAngleZNorm4D: + double roll, pitch, yaw; + // For **TranslationXAxisAngleZNorm4D** - end effector origin reaches desired 3D translation, manipulator + // direction needs to be orthogonal to z axis and be rotated at a certain angle starting from the x axis (defined + // in the manipulator base link’s coordinate system) + pose_frame.M.GetRPY(roll, pitch, yaw); + ComputeIk(trans, &yaw, vfree.size() > 0 ? &vfree[0] : NULL, solutions); + return solutions.GetNumSolutions(); + + case IKP_TranslationYAxisAngleXNorm4D: + // For **TranslationYAxisAngleXNorm4D** - end effector origin reaches desired 3D translation, manipulator + // direction needs to be orthogonal to x axis and be rotated at a certain angle starting from the y axis (defined + // in the manipulator base link’s coordinate system) + pose_frame.M.GetRPY(roll, pitch, yaw); + ComputeIk(trans, &roll, vfree.size() > 0 ? &vfree[0] : NULL, solutions); + return solutions.GetNumSolutions(); + + case IKP_TranslationZAxisAngleYNorm4D: + // For **TranslationZAxisAngleYNorm4D** - end effector origin reaches desired 3D translation, manipulator + // direction needs to be orthogonal to y axis and be rotated at a certain angle starting from the z axis (defined + // in the manipulator base link’s coordinate system) + pose_frame.M.GetRPY(roll, pitch, yaw); + ComputeIk(trans, &pitch, vfree.size() > 0 ? &vfree[0] : NULL, solutions); + return solutions.GetNumSolutions(); + + default: + ROS_ERROR_NAMED(name_, "Unknown IkParameterizationType! " + "Was the solver generated with an incompatible version of Openrave?"); + return 0; + } +} + +void IKFastKinematicsPlugin::getSolution(const IkSolutionList& solutions, int i, + std::vector& solution) const +{ + solution.clear(); + solution.resize(num_joints_); + + // IKFast56/61 + const IkSolutionBase& sol = solutions.GetSolution(i); + std::vector vsolfree(sol.GetFree().size()); + sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL); + + // std::cout << "solution " << i << ":" ; + // for(int j=0;j& solutions, + const std::vector& ik_seed_state, int i, + std::vector& solution) const +{ + solution.clear(); + solution.resize(num_joints_); + + // IKFast56/61 + const IkSolutionBase& sol = solutions.GetSolution(i); + std::vector vsolfree(sol.GetFree().size()); + sol.GetSolution(&solution[0], vsolfree.size() > 0 ? &vsolfree[0] : NULL); + + // rotate joints by +/-360° where it is possible and useful + for (std::size_t i = 0; i < num_joints_; ++i) + { + if (joint_has_limits_vector_[i]) + { + double signed_distance = solution[i] - ik_seed_state[i]; + while (signed_distance > M_PI && solution[i] - 2 * M_PI > (joint_min_vector_[i] - LIMIT_TOLERANCE)) + { + signed_distance -= 2 * M_PI; + solution[i] -= 2 * M_PI; + } + while (signed_distance < -M_PI && solution[i] + 2 * M_PI < (joint_max_vector_[i] + LIMIT_TOLERANCE)) + { + signed_distance += 2 * M_PI; + solution[i] += 2 * M_PI; + } + } + } +} + +double IKFastKinematicsPlugin::harmonize(const std::vector& ik_seed_state, std::vector& solution) const +{ + double dist_sqr = 0; + std::vector ss = ik_seed_state; + for (size_t i = 0; i < ik_seed_state.size(); ++i) + { + while (ss[i] > 2 * M_PI) + { + ss[i] -= 2 * M_PI; + } + while (ss[i] < 2 * M_PI) + { + ss[i] += 2 * M_PI; + } + while (solution[i] > 2 * M_PI) + { + solution[i] -= 2 * M_PI; + } + while (solution[i] < 2 * M_PI) + { + solution[i] += 2 * M_PI; + } + dist_sqr += fabs(ik_seed_state[i] - solution[i]); + } + return dist_sqr; +} + +// void IKFastKinematicsPlugin::getOrderedSolutions(const std::vector &ik_seed_state, +// std::vector >& solslist) +// { +// std::vector +// double mindist = 0; +// int minindex = -1; +// std::vector sol; +// for(size_t i=0;i& ik_seed_state, double timeout, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + const IKCallbackFn solution_callback = 0; + std::vector consistency_limits; + + return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code, + options); +} + +bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, + const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + const IKCallbackFn solution_callback = 0; + return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code, + options); +} + +bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, + const std::vector& ik_seed_state, double timeout, + std::vector& solution, const IKCallbackFn& solution_callback, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + std::vector consistency_limits; + return searchPositionIK(ik_pose, ik_seed_state, timeout, consistency_limits, solution, solution_callback, error_code, + options); +} + +bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose, + const std::vector& ik_seed_state, double timeout, + const std::vector& consistency_limits, + std::vector& solution, const IKCallbackFn& solution_callback, + moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + ROS_DEBUG_STREAM_NAMED(name_, "searchPositionIK"); + + /// search_mode is currently fixed during code generation + SEARCH_MODE search_mode = OPTIMIZE_MAX_JOINT; + + // Check if there are no redundant joints + if (free_params_.size() == 0) + { + ROS_DEBUG_STREAM_NAMED(name_, "No need to search since no free params/redundant joints"); + + std::vector ik_poses(1, ik_pose); + std::vector> solutions; + kinematics::KinematicsResult kinematic_result; + // Find all IK solution within joint limits + if (!getPositionIK(ik_poses, ik_seed_state, solutions, kinematic_result, options)) + { + ROS_DEBUG_STREAM_NAMED(name_, "No solution whatsoever"); + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + return false; + } + + // sort solutions by their distance to the seed + std::vector solutions_obey_limits; + for (std::size_t i = 0; i < solutions.size(); ++i) + { + double dist_from_seed = 0.0; + for (std::size_t j = 0; j < ik_seed_state.size(); ++j) + { + dist_from_seed += fabs(ik_seed_state[j] - solutions[i][j]); + } + + solutions_obey_limits.push_back({ solutions[i], dist_from_seed }); + } + std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); + + // check for collisions if a callback is provided + if (!solution_callback.empty()) + { + for (std::size_t i = 0; i < solutions_obey_limits.size(); ++i) + { + solution_callback(ik_pose, solutions_obey_limits[i].value, error_code); + if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS) + { + solution = solutions_obey_limits[i].value; + ROS_DEBUG_STREAM_NAMED(name_, "Solution passes callback"); + return true; + } + } + + ROS_DEBUG_STREAM_NAMED(name_, "Solution has error code " << error_code); + return false; + } + else + { + solution = solutions_obey_limits[0].value; + error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; + return true; // no collision check callback provided + } + } + + // ------------------------------------------------------------------------------------------------- + // Error Checking + if (!active_) + { + ROS_ERROR_STREAM_NAMED(name_, "Kinematics not active"); + error_code.val = error_code.NO_IK_SOLUTION; + return false; + } + + if (ik_seed_state.size() != num_joints_) + { + ROS_ERROR_STREAM_NAMED(name_, "Seed state must have size " << num_joints_ << " instead of size " + << ik_seed_state.size()); + error_code.val = error_code.NO_IK_SOLUTION; + return false; + } + + if (!consistency_limits.empty() && consistency_limits.size() != num_joints_) + { + ROS_ERROR_STREAM_NAMED(name_, "Consistency limits be empty or must have size " << num_joints_ << " instead of size " + << consistency_limits.size()); + error_code.val = error_code.NO_IK_SOLUTION; + return false; + } + + // ------------------------------------------------------------------------------------------------- + // Initialize + + KDL::Frame frame; + tf::poseMsgToKDL(ik_pose, frame); + + std::vector vfree(free_params_.size()); + + ros::Time maxTime = ros::Time::now() + ros::Duration(timeout); + int counter = 0; + + double initial_guess = ik_seed_state[free_params_[0]]; + vfree[0] = initial_guess; + + // ------------------------------------------------------------------------------------------------- + // Handle consitency limits if needed + int num_positive_increments; + int num_negative_increments; + + if (!consistency_limits.empty()) + { + // moveit replaced consistency_limit (scalar) w/ consistency_limits (vector) + // Assume [0]th free_params element for now. Probably wrong. + double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]); + double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]); + + num_positive_increments = (int)((max_limit - initial_guess) / search_discretization_); + num_negative_increments = (int)((initial_guess - min_limit) / search_discretization_); + } + else // no consitency limits provided + { + num_positive_increments = (joint_max_vector_[free_params_[0]] - initial_guess) / search_discretization_; + num_negative_increments = (initial_guess - joint_min_vector_[free_params_[0]]) / search_discretization_; + } + + // ------------------------------------------------------------------------------------------------- + // Begin searching + + ROS_DEBUG_STREAM_NAMED(name_, "Free param is " << free_params_[0] << " initial guess is " << initial_guess + << ", # positive increments: " << num_positive_increments + << ", # negative increments: " << num_negative_increments); + if ((search_mode & OPTIMIZE_MAX_JOINT) && (num_positive_increments + num_negative_increments) > 1000) + ROS_WARN_STREAM_ONCE_NAMED(name_, "Large search space, consider increasing the search discretization"); + + double best_costs = -1.0; + std::vector best_solution; + int nattempts = 0, nvalid = 0; + + while (true) + { + IkSolutionList solutions; + int numsol = solve(frame, vfree, solutions); + + ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast"); + + // ROS_INFO("%f",vfree[0]); + + if (numsol > 0) + { + for (int s = 0; s < numsol; ++s) + { + nattempts++; + std::vector sol; + getSolution(solutions, ik_seed_state, s, sol); + + bool obeys_limits = true; + for (unsigned int i = 0; i < sol.size(); i++) + { + if (joint_has_limits_vector_[i] && (sol[i] < joint_min_vector_[i] || sol[i] > joint_max_vector_[i])) + { + obeys_limits = false; + break; + } + // ROS_INFO_STREAM_NAMED(name_,"Num " << i << " value " << sol[i] << " has limits " << + // joint_has_limits_vector_[i] << " " << joint_min_vector_[i] << " " << joint_max_vector_[i]); + } + if (obeys_limits) + { + getSolution(solutions, ik_seed_state, s, solution); + + // This solution is within joint limits, now check if in collision (if callback provided) + if (!solution_callback.empty()) + { + solution_callback(ik_pose, solution, error_code); + } + else + { + error_code.val = error_code.SUCCESS; + } + + if (error_code.val == error_code.SUCCESS) + { + nvalid++; + if (search_mode & OPTIMIZE_MAX_JOINT) + { + // Costs for solution: Largest joint motion + double costs = 0.0; + for (unsigned int i = 0; i < solution.size(); i++) + { + double d = fabs(ik_seed_state[i] - solution[i]); + if (d > costs) + costs = d; + } + if (costs < best_costs || best_costs == -1.0) + { + best_costs = costs; + best_solution = solution; + } + } + else + // Return first feasible solution + return true; + } + } + } + } + + if (!getCount(counter, num_positive_increments, -num_negative_increments)) + { + // Everything searched + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + break; + } + + vfree[0] = initial_guess + search_discretization_ * counter; + // ROS_DEBUG_STREAM_NAMED(name_,"Attempt " << counter << " with 0th free joint having value " << vfree[0]); + } + + ROS_DEBUG_STREAM_NAMED(name_, "Valid solutions: " << nvalid << "/" << nattempts); + + if ((search_mode & OPTIMIZE_MAX_JOINT) && best_costs != -1.0) + { + solution = best_solution; + error_code.val = error_code.SUCCESS; + return true; + } + + // No solution found + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + return false; +} + +// Used when there are no redundant joints - aka no free params +bool IKFastKinematicsPlugin::getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector& ik_seed_state, + std::vector& solution, moveit_msgs::MoveItErrorCodes& error_code, + const kinematics::KinematicsQueryOptions& options) const +{ + ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK"); + + if (!active_) + { + ROS_ERROR("kinematics not active"); + return false; + } + + if (ik_seed_state.size() < num_joints_) + { + ROS_ERROR_STREAM("ik_seed_state only has " << ik_seed_state.size() << " entries, this ikfast solver requires " + << num_joints_); + return false; + } + + // Check if seed is in bound + for (std::size_t i = 0; i < ik_seed_state.size(); i++) + { + // Add tolerance to limit check + if (joint_has_limits_vector_[i] && ((ik_seed_state[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) || + (ik_seed_state[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE)))) + { + ROS_DEBUG_STREAM_NAMED("ikseed", "Not in limits! " << (int)i << " value " << ik_seed_state[i] + << " has limit: " << joint_has_limits_vector_[i] << " being " + << joint_min_vector_[i] << " to " << joint_max_vector_[i]); + return false; + } + } + + std::vector vfree(free_params_.size()); + for (std::size_t i = 0; i < free_params_.size(); ++i) + { + int p = free_params_[i]; + ROS_ERROR("%u is %f", p, ik_seed_state[p]); // DTC + vfree[i] = ik_seed_state[p]; + } + + KDL::Frame frame; + tf::poseMsgToKDL(ik_pose, frame); + + IkSolutionList solutions; + int numsol = solve(frame, vfree, solutions); + ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast"); + + std::vector solutions_obey_limits; + + if (numsol) + { + std::vector solution_obey_limits; + for (std::size_t s = 0; s < numsol; ++s) + { + std::vector sol; + getSolution(solutions, ik_seed_state, s, sol); + ROS_DEBUG_NAMED(name_, "Sol %d: %e %e %e %e %e %e", (int)s, sol[0], sol[1], sol[2], sol[3], sol[4], + sol[5]); + + bool obeys_limits = true; + for (std::size_t i = 0; i < sol.size(); i++) + { + // Add tolerance to limit check + if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) || + (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE)))) + { + // One element of solution is not within limits + obeys_limits = false; + ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << (int)i << " value " << sol[i] << " has limit: " + << joint_has_limits_vector_[i] << " being " + << joint_min_vector_[i] << " to " << joint_max_vector_[i]); + break; + } + } + if (obeys_limits) + { + // All elements of this solution obey limits + getSolution(solutions, ik_seed_state, s, solution_obey_limits); + double dist_from_seed = 0.0; + for (std::size_t i = 0; i < ik_seed_state.size(); ++i) + { + dist_from_seed += fabs(ik_seed_state[i] - solution_obey_limits[i]); + } + + solutions_obey_limits.push_back({ solution_obey_limits, dist_from_seed }); + } + } + } + else + { + ROS_DEBUG_STREAM_NAMED(name_, "No IK solution"); + } + + // Sort the solutions under limits and find the one that is closest to ik_seed_state + if (!solutions_obey_limits.empty()) + { + std::sort(solutions_obey_limits.begin(), solutions_obey_limits.end()); + solution = solutions_obey_limits[0].value; + error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; + return true; + } + + error_code.val = moveit_msgs::MoveItErrorCodes::NO_IK_SOLUTION; + return false; +} + +bool IKFastKinematicsPlugin::getPositionIK(const std::vector& ik_poses, + const std::vector& ik_seed_state, + std::vector>& solutions, + kinematics::KinematicsResult& result, + const kinematics::KinematicsQueryOptions& options) const +{ + ROS_DEBUG_STREAM_NAMED(name_, "getPositionIK with multiple solutions"); + + if (!active_) + { + ROS_ERROR("kinematics not active"); + result.kinematic_error = kinematics::KinematicErrors::SOLVER_NOT_ACTIVE; + return false; + } + + if (ik_poses.empty()) + { + ROS_ERROR("ik_poses is empty"); + result.kinematic_error = kinematics::KinematicErrors::EMPTY_TIP_POSES; + return false; + } + + if (ik_poses.size() > 1) + { + ROS_ERROR("ik_poses contains multiple entries, only one is allowed"); + result.kinematic_error = kinematics::KinematicErrors::MULTIPLE_TIPS_NOT_SUPPORTED; + return false; + } + + if (ik_seed_state.size() < num_joints_) + { + ROS_ERROR_STREAM("ik_seed_state only has " << ik_seed_state.size() << " entries, this ikfast solver requires " + << num_joints_); + return false; + } + + KDL::Frame frame; + tf::poseMsgToKDL(ik_poses[0], frame); + + // solving ik + std::vector> solution_set; + IkSolutionList ik_solutions; + std::vector vfree; + int numsol = 0; + std::vector sampled_joint_vals; + if (!redundant_joint_indices_.empty()) + { + // initializing from seed + sampled_joint_vals.push_back(ik_seed_state[redundant_joint_indices_[0]]); + + // checking joint limits when using no discretization + if (options.discretization_method == kinematics::DiscretizationMethods::NO_DISCRETIZATION && + joint_has_limits_vector_[redundant_joint_indices_.front()]) + { + double joint_min = joint_min_vector_[redundant_joint_indices_.front()]; + double joint_max = joint_max_vector_[redundant_joint_indices_.front()]; + + double jv = sampled_joint_vals[0]; + if (!((jv > (joint_min - LIMIT_TOLERANCE)) && (jv < (joint_max + LIMIT_TOLERANCE)))) + { + result.kinematic_error = kinematics::KinematicErrors::IK_SEED_OUTSIDE_LIMITS; + ROS_ERROR_STREAM("ik seed is out of bounds"); + return false; + } + } + + // computing all solutions sets for each sampled value of the redundant joint + if (!sampleRedundantJoint(options.discretization_method, sampled_joint_vals)) + { + result.kinematic_error = kinematics::KinematicErrors::UNSUPORTED_DISCRETIZATION_REQUESTED; + return false; + } + + for (unsigned int i = 0; i < sampled_joint_vals.size(); i++) + { + vfree.clear(); + vfree.push_back(sampled_joint_vals[i]); + numsol += solve(frame, vfree, ik_solutions); + solution_set.push_back(ik_solutions); + } + } + else + { + // computing for single solution set + numsol = solve(frame, vfree, ik_solutions); + solution_set.push_back(ik_solutions); + } + + ROS_DEBUG_STREAM_NAMED(name_, "Found " << numsol << " solutions from IKFast"); + bool solutions_found = false; + if (numsol > 0) + { + /* + Iterating through all solution sets and storing those that do not exceed joint limits. + */ + for (unsigned int r = 0; r < solution_set.size(); r++) + { + ik_solutions = solution_set[r]; + numsol = ik_solutions.GetNumSolutions(); + for (int s = 0; s < numsol; ++s) + { + std::vector sol; + getSolution(ik_solutions, ik_seed_state, s, sol); + + bool obeys_limits = true; + for (unsigned int i = 0; i < sol.size(); i++) + { + // Add tolerance to limit check + if (joint_has_limits_vector_[i] && ((sol[i] < (joint_min_vector_[i] - LIMIT_TOLERANCE)) || + (sol[i] > (joint_max_vector_[i] + LIMIT_TOLERANCE)))) + { + // One element of solution is not within limits + obeys_limits = false; + ROS_DEBUG_STREAM_NAMED(name_, "Not in limits! " << i << " value " << sol[i] << " has limit: " + << joint_has_limits_vector_[i] << " being " + << joint_min_vector_[i] << " to " << joint_max_vector_[i]); + break; + } + } + if (obeys_limits) + { + // All elements of solution obey limits + solutions_found = true; + solutions.push_back(sol); + } + } + } + + if (solutions_found) + { + result.kinematic_error = kinematics::KinematicErrors::OK; + return true; + } + } + else + { + ROS_DEBUG_STREAM_NAMED(name_, "No IK solution"); + } + + result.kinematic_error = kinematics::KinematicErrors::NO_SOLUTION; + return false; +} + +bool IKFastKinematicsPlugin::sampleRedundantJoint(kinematics::DiscretizationMethod method, + std::vector& sampled_joint_vals) const +{ + double joint_min = -M_PI; + double joint_max = M_PI; + int index = redundant_joint_indices_.front(); + double joint_dscrt = redundant_joint_discretization_.at(index); + + if (joint_has_limits_vector_[redundant_joint_indices_.front()]) + { + joint_min = joint_min_vector_[index]; + joint_max = joint_max_vector_[index]; + } + + switch (method) + { + case kinematics::DiscretizationMethods::ALL_DISCRETIZED: + { + int steps = std::ceil((joint_max - joint_min) / joint_dscrt); + for (unsigned int i = 0; i < steps; i++) + { + sampled_joint_vals.push_back(joint_min + joint_dscrt * i); + } + sampled_joint_vals.push_back(joint_max); + } + break; + case kinematics::DiscretizationMethods::ALL_RANDOM_SAMPLED: + { + int steps = std::ceil((joint_max - joint_min) / joint_dscrt); + steps = steps > 0 ? steps : 1; + double diff = joint_max - joint_min; + for (int i = 0; i < steps; i++) + { + sampled_joint_vals.push_back(((diff * std::rand()) / (static_cast(RAND_MAX))) + joint_min); + } + } + + break; + case kinematics::DiscretizationMethods::NO_DISCRETIZATION: + + break; + default: + ROS_ERROR_STREAM("Discretization method " << method << " is not supported"); + return false; + } + + return true; +} + +} // end namespace + +// register IKFastKinematicsPlugin as a KinematicsBase implementation +#include +PLUGINLIB_EXPORT_CLASS(ikfast_kinematics_plugin::IKFastKinematicsPlugin, kinematics::KinematicsBase); diff --git a/khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_solver.cpp b/khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_solver.cpp new file mode 100644 index 0000000..1161517 --- /dev/null +++ b/khi_rs_ikfast_plugin/src/khi_rs030n_manipulator_ikfast_solver.cpp @@ -0,0 +1,12847 @@ +/// autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE +/// \author Rosen Diankov +/// +/// Licensed under the Apache License, Version 2.0 (the "License"); +/// you may not use this file except in compliance with the License. +/// You may obtain a copy of the License at +/// http://www.apache.org/licenses/LICENSE-2.0 +/// +/// Unless required by applicable law or agreed to in writing, software +/// distributed under the License is distributed on an "AS IS" BASIS, +/// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +/// See the License for the specific language governing permissions and +/// limitations under the License. +/// +/// ikfast version 0x1000004a generated on 2023-08-30 08:20:06.790960 +/// To compile with gcc: +/// gcc -lstdc++ ik.cpp +/// To compile without any main function as a shared object (might need -llapack): +/// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp +#define IKFAST_HAS_LIBRARY +#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h +using namespace ikfast; + +// check if the included ikfast version matches what this file was compiled with +#define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x] +IKFAST_COMPILE_ASSERT(IKFAST_VERSION==0x1000004a); + +#include +#include +#include +#include +#include + +#ifndef IKFAST_ASSERT +#include +#include +#include + +#ifdef _MSC_VER +#ifndef __PRETTY_FUNCTION__ +#define __PRETTY_FUNCTION__ __FUNCDNAME__ +#endif +#endif + +#ifndef __PRETTY_FUNCTION__ +#define __PRETTY_FUNCTION__ __func__ +#endif + +#define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } } + +#endif + +#if defined(_MSC_VER) +#define IKFAST_ALIGNED16(x) __declspec(align(16)) x +#else +#define IKFAST_ALIGNED16(x) x __attribute((aligned(16))) +#endif + +#define IK2PI ((IkReal)6.28318530717959) +#define IKPI ((IkReal)3.14159265358979) +#define IKPI_2 ((IkReal)1.57079632679490) + +#ifdef _MSC_VER +#ifndef isnan +#define isnan _isnan +#endif +#ifndef isinf +#define isinf _isinf +#endif +//#ifndef isfinite +//#define isfinite _isfinite +//#endif +#endif // _MSC_VER + +// lapack routines +extern "C" { + void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info); + void zgetrf_ (const int* m, const int* n, std::complex* a, const int* lda, int* ipiv, int* info); + void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info); + void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info); + void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info); + void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info); +} + +using namespace std; // necessary to get std math routines + +#ifdef IKFAST_NAMESPACE +namespace IKFAST_NAMESPACE { +#endif + +inline float IKabs(float f) { return fabsf(f); } +inline double IKabs(double f) { return fabs(f); } + +inline float IKsqr(float f) { return f*f; } +inline double IKsqr(double f) { return f*f; } + +inline float IKlog(float f) { return logf(f); } +inline double IKlog(double f) { return log(f); } + +// allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation +#ifndef IKFAST_SINCOS_THRESH +#define IKFAST_SINCOS_THRESH ((IkReal)1e-7) +#endif + +// used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation +#ifndef IKFAST_ATAN2_MAGTHRESH +#define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7) +#endif + +// minimum distance of separate solutions +#ifndef IKFAST_SOLUTION_THRESH +#define IKFAST_SOLUTION_THRESH ((IkReal)1e-6) +#endif + +// there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate +#ifndef IKFAST_EVALCOND_THRESH +#define IKFAST_EVALCOND_THRESH ((IkReal)0.00001) +#endif + + +inline float IKasin(float f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return float(-IKPI_2); +else if( f >= 1 ) return float(IKPI_2); +return asinf(f); +} +inline double IKasin(double f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return -IKPI_2; +else if( f >= 1 ) return IKPI_2; +return asin(f); +} + +// return positive value in [0,y) +inline float IKfmod(float x, float y) +{ + while(x < 0) { + x += y; + } + return fmodf(x,y); +} + +// return positive value in [0,y) +inline double IKfmod(double x, double y) +{ + while(x < 0) { + x += y; + } + return fmod(x,y); +} + +inline float IKacos(float f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return float(IKPI); +else if( f >= 1 ) return float(0); +return acosf(f); +} +inline double IKacos(double f) +{ +IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver +if( f <= -1 ) return IKPI; +else if( f >= 1 ) return 0; +return acos(f); +} +inline float IKsin(float f) { return sinf(f); } +inline double IKsin(double f) { return sin(f); } +inline float IKcos(float f) { return cosf(f); } +inline double IKcos(double f) { return cos(f); } +inline float IKtan(float f) { return tanf(f); } +inline double IKtan(double f) { return tan(f); } +inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); } +inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); } +inline float IKatan2Simple(float fy, float fx) { + return atan2f(fy,fx); +} +inline float IKatan2(float fy, float fx) { + if( isnan(fy) ) { + IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned + return float(IKPI_2); + } + else if( isnan(fx) ) { + return 0; + } + return atan2f(fy,fx); +} +inline double IKatan2Simple(double fy, double fx) { + return atan2(fy,fx); +} +inline double IKatan2(double fy, double fx) { + if( isnan(fy) ) { + IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned + return IKPI_2; + } + else if( isnan(fx) ) { + return 0; + } + return atan2(fy,fx); +} + +template +struct CheckValue +{ + T value; + bool valid; +}; + +template +inline CheckValue IKatan2WithCheck(T fy, T fx, T epsilon) +{ + CheckValue ret; + ret.valid = false; + ret.value = 0; + if( !isnan(fy) && !isnan(fx) ) { + if( IKabs(fy) >= IKFAST_ATAN2_MAGTHRESH || IKabs(fx) > IKFAST_ATAN2_MAGTHRESH ) { + ret.value = IKatan2Simple(fy,fx); + ret.valid = true; + } + } + return ret; +} + +inline float IKsign(float f) { + if( f > 0 ) { + return float(1); + } + else if( f < 0 ) { + return float(-1); + } + return 0; +} + +inline double IKsign(double f) { + if( f > 0 ) { + return 1.0; + } + else if( f < 0 ) { + return -1.0; + } + return 0; +} + +template +inline CheckValue IKPowWithIntegerCheck(T f, int n) +{ + CheckValue ret; + ret.valid = true; + if( n == 0 ) { + ret.value = 1.0; + return ret; + } + else if( n == 1 ) + { + ret.value = f; + return ret; + } + else if( n < 0 ) + { + if( f == 0 ) + { + ret.valid = false; + ret.value = (T)1.0e30; + return ret; + } + if( n == -1 ) { + ret.value = T(1.0)/f; + return ret; + } + } + + int num = n > 0 ? n : -n; + if( num == 2 ) { + ret.value = f*f; + } + else if( num == 3 ) { + ret.value = f*f*f; + } + else { + ret.value = 1.0; + while(num>0) { + if( num & 1 ) { + ret.value *= f; + } + num >>= 1; + f *= f; + } + } + + if( n < 0 ) { + ret.value = T(1.0)/ret.value; + } + return ret; +} + +/// solves the forward kinematics equations. +/// \param pfree is an array specifying the free joints of the chain. +IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) { +IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27,x28,x29,x30,x31,x32,x33,x34,x35,x36,x37,x38,x39,x40,x41,x42; +x0=IKsin(j[0]); +x1=IKcos(j[3]); +x2=IKcos(j[0]); +x3=IKsin(j[3]); +x4=IKcos(j[2]); +x5=IKsin(j[1]); +x6=IKcos(j[1]); +x7=IKsin(j[2]); +x8=IKsin(j[5]); +x9=IKcos(j[5]); +x10=IKcos(j[4]); +x11=IKsin(j[4]); +x12=((1.0)*x1); +x13=((0.165)*x2); +x14=((1.08)*x2); +x15=((0.165)*x0); +x16=((1.08)*x0); +x17=((1.0)*x3); +x18=((1.0)*x2); +x19=((0.165)*x1); +x20=((1.0)*x0); +x21=(x4*x5); +x22=(x6*x7); +x23=((-1.0)*x11); +x24=((-1.0)*x10); +x25=(x4*x6); +x26=(x0*x5); +x27=(x5*x7); +x28=(x1*x11); +x29=(x17*x2); +x30=((1.0)*x22); +x31=(x18*x22); +x32=((((-1.0)*x30))+x21); +x33=((((-1.0)*x27))+(((-1.0)*x25))); +x34=(x1*x32); +x35=(((x0*x25))+((x26*x7))); +x36=(x10*x34); +x37=(x20*(((((-1.0)*x22))+x21))); +x38=(x18*(((((-1.0)*x27))+(((-1.0)*x25))))); +x39=(x3*x35); +x40=(x1*x38); +x41=(((x11*x37))+((x10*(((((-1.0)*x29))+((x1*x35))))))); +x42=(((x24*(((((-1.0)*x0*x3))+x40))))+((x23*(((((-1.0)*x18*x21))+x31))))); +eerot[0]=(((x41*x8))+((x9*((((x1*x2))+x39))))); +eerot[1]=(((x8*(((((-1.0)*x12*x2))+(((-1.0)*x17*x35))))))+((x41*x9))); +eerot[2]=(((x11*(((((-1.0)*x12*x35))+x29))))+((x10*x37))); +IkReal x43=((1.0)*x22); +eetrans[0]=(((x10*(((((-1.0)*x15*x43))+((x15*x21))))))+(((0.15)*x0))+((x16*x21))+((x11*(((((-1.0)*x19*x35))+((x13*x3))))))+(((-1.0)*x16*x43))+(((0.87)*x26))); +eerot[3]=(((x42*x8))+((x9*(((((-1.0)*x0*x12))+(((-1.0)*x17*x38))))))); +eerot[4]=(((x8*((((x0*x1))+((x3*x38))))))+((x42*x9))); +eerot[5]=(((x11*(((((-1.0)*x0*x17))+x40))))+((x10*(((((-1.0)*x31))+((x2*x21))))))); +IkReal x44=((1.0)*x22); +eetrans[1]=(((x11*((((x19*x38))+(((-1.0)*x15*x3))))))+(((0.87)*x2*x5))+((x10*((((x13*x21))+(((-1.0)*x13*x44))))))+(((0.15)*x2))+((x14*x21))+(((-1.0)*x14*x44))); +eerot[6]=(((x8*(((((-1.0)*x10*x12*x32))+(((-1.0)*x11*x33))))))+((x3*x9*(((((-1.0)*x21))+x30))))); +eerot[7]=(((x9*((((x23*x33))+((x24*x34))))))+((x3*x32*x8))); +eerot[8]=(((x28*x32))+((x10*((x25+x27))))); +eetrans[2]=((0.68)+((x10*(((((0.165)*x27))+(((0.165)*x25))))))+((x28*(((((-0.165)*x22))+(((0.165)*x21))))))+(((1.08)*x25))+(((1.08)*x27))+(((0.87)*x6))); +} + +IKFAST_API int GetNumFreeParameters() { return 0; } +IKFAST_API int* GetFreeParameters() { return NULL; } +IKFAST_API int GetNumJoints() { return 6; } + +IKFAST_API int GetIkRealSize() { return sizeof(IkReal); } + +IKFAST_API int GetIkType() { return 0x67000001; } + +class IKSolver { +public: +IkReal j0,cj0,sj0,htj0,j0mul,j1,cj1,sj1,htj1,j1mul,j2,cj2,sj2,htj2,j2mul,j3,cj3,sj3,htj3,j3mul,j4,cj4,sj4,htj4,j4mul,j5,cj5,sj5,htj5,j5mul,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_r10,r10,rxp1_0,new_r11,r11,rxp1_1,new_r12,r12,rxp1_2,new_r20,r20,rxp2_0,new_r21,r21,rxp2_1,new_r22,r22,rxp2_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp; +unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5; + +IkReal j100, cj100, sj100; +unsigned char _ij100[2], _nj100; +bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { +j0=numeric_limits::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; j5=numeric_limits::quiet_NaN(); _ij5[0] = -1; _ij5[1] = -1; _nj5 = -1; +for(int dummyiter = 0; dummyiter < 1; ++dummyiter) { + solutions.Clear(); +r00 = eerot[0*3+0]; +r01 = eerot[0*3+1]; +r02 = eerot[0*3+2]; +r10 = eerot[1*3+0]; +r11 = eerot[1*3+1]; +r12 = eerot[1*3+2]; +r20 = eerot[2*3+0]; +r21 = eerot[2*3+1]; +r22 = eerot[2*3+2]; +px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; + +new_r00=r00; +new_r01=r01; +new_r02=r02; +new_px=(px+(((-0.165)*r02))); +new_r10=((-1.0)*r10); +new_r11=((-1.0)*r11); +new_r12=((-1.0)*r12); +new_py=((((0.165)*r12))+(((-1.0)*py))); +new_r20=((-1.0)*r20); +new_r21=((-1.0)*r21); +new_r22=((-1.0)*r22); +new_pz=((0.68)+(((-1.0)*pz))+(((0.165)*r22))); +r00 = new_r00; r01 = new_r01; r02 = new_r02; r10 = new_r10; r11 = new_r11; r12 = new_r12; r20 = new_r20; r21 = new_r21; r22 = new_r22; px = new_px; py = new_py; pz = new_pz; +IkReal x45=((1.0)*px); +IkReal x46=((1.0)*pz); +IkReal x47=((1.0)*py); +pp=((px*px)+(py*py)+(pz*pz)); +npx=(((px*r00))+((py*r10))+((pz*r20))); +npy=(((px*r01))+((py*r11))+((pz*r21))); +npz=(((px*r02))+((py*r12))+((pz*r22))); +rxp0_0=((((-1.0)*r20*x47))+((pz*r10))); +rxp0_1=(((px*r20))+(((-1.0)*r00*x46))); +rxp0_2=((((-1.0)*r10*x45))+((py*r00))); +rxp1_0=((((-1.0)*r21*x47))+((pz*r11))); +rxp1_1=(((px*r21))+(((-1.0)*r01*x46))); +rxp1_2=((((-1.0)*r11*x45))+((py*r01))); +rxp2_0=((((-1.0)*r22*x47))+((pz*r12))); +rxp2_1=((((-1.0)*r02*x46))+((px*r22))); +rxp2_2=((((-1.0)*r12*x45))+((py*r02))); +{ +IkReal j0eval[1]; +j0eval[0]=((IKabs(px))+(IKabs(py))); +if( IKabs(j0eval[0]) < 0.0000010000000000 ) +{ +continue; // no branches [j0, j1, j2] + +} else +{ +{ +IkReal j0array[2], cj0array[2], sj0array[2]; +bool j0valid[2]={false}; +_nj0 = 2; +CheckValue x49 = IKatan2WithCheck(IkReal(((-1.0)*px)),IkReal(((-1.0)*py)),IKFAST_ATAN2_MAGTHRESH); +if(!x49.valid){ +continue; +} +IkReal x48=x49.value; +j0array[0]=((-1.0)*x48); +sj0array[0]=IKsin(j0array[0]); +cj0array[0]=IKcos(j0array[0]); +j0array[1]=((3.14159265358979)+(((-1.0)*x48))); +sj0array[1]=IKsin(j0array[1]); +cj0array[1]=IKcos(j0array[1]); +if( j0array[0] > IKPI ) +{ + j0array[0]-=IK2PI; +} +else if( j0array[0] < -IKPI ) +{ j0array[0]+=IK2PI; +} +j0valid[0] = true; +if( j0array[1] > IKPI ) +{ + j0array[1]-=IK2PI; +} +else if( j0array[1] < -IKPI ) +{ j0array[1]+=IK2PI; +} +j0valid[1] = true; +for(int ij0 = 0; ij0 < 2; ++ij0) +{ +if( !j0valid[ij0] ) +{ + continue; +} +_ij0[0] = ij0; _ij0[1] = -1; +for(int iij0 = ij0+1; iij0 < 2; ++iij0) +{ +if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) +{ + j0valid[iij0]=false; _ij0[1] = iij0; break; +} +} +j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; + +{ +IkReal j2array[2], cj2array[2], sj2array[2]; +bool j2valid[2]={false}; +_nj2 = 2; +cj2array[0]=((-1.01149425287356)+(((0.532141336739038)*pp))+(((0.159642401021711)*cj0*py))+(((-0.159642401021711)*px*sj0))); +if( cj2array[0] >= -1-IKFAST_SINCOS_THRESH && cj2array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j2valid[0] = j2valid[1] = true; + j2array[0] = IKacos(cj2array[0]); + sj2array[0] = IKsin(j2array[0]); + cj2array[1] = cj2array[0]; + j2array[1] = -j2array[0]; + sj2array[1] = -sj2array[0]; +} +else if( isnan(cj2array[0]) ) +{ + // probably any value will work + j2valid[0] = true; + cj2array[0] = 1; sj2array[0] = 0; j2array[0] = 0; +} +for(int ij2 = 0; ij2 < 2; ++ij2) +{ +if( !j2valid[ij2] ) +{ + continue; +} +_ij2[0] = ij2; _ij2[1] = -1; +for(int iij2 = ij2+1; iij2 < 2; ++iij2) +{ +if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) +{ + j2valid[iij2]=false; _ij2[1] = iij2; break; +} +} +j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; + +{ +IkReal j1eval[3]; +IkReal x50=(cj0*py); +IkReal x51=(px*sj0); +IkReal x52=((675.0)*cj2); +IkReal x53=((675.0)*sj2); +j1eval[0]=((-1.02346743295019)+(((-1.0)*cj2))); +j1eval[1]=((IKabs(((81.5625)+(((543.75)*x50))+(((-543.75)*x51))+(((-1.0)*x51*x52))+((x50*x52))+((pz*x53))+(((101.25)*cj2)))))+(IKabs(((((543.75)*pz))+(((-101.25)*sj2))+((x51*x53))+((pz*x52))+(((-1.0)*x50*x53)))))); +j1eval[2]=IKsign(((-1202.0625)+(((-1174.5)*cj2)))); +if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 || IKabs(j1eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j1eval[3]; +IkReal x54=((27.0)*cj2); +IkReal x55=(cj0*py); +IkReal x56=(px*sj0); +IkReal x57=(pz*sj2); +IkReal x58=((8.27586206896552)*cj2); +IkReal x59=((25.0)*pz); +j1eval[0]=((1.0)+(((-8.27586206896552)*x57))+(((-1.0)*x56*x58))+(((6.66666666666667)*x55))+(((1.24137931034483)*cj2))+((x55*x58))+(((-6.66666666666667)*x56))); +j1eval[1]=((IKabs(((((23.49)*sj2))+(((-1.0)*x55*x59))+(((29.16)*cj2*sj2))+((x56*x59))+(((-3.75)*pz)))))+(IKabs(((-18.9225)+(((-46.98)*cj2))+(((-29.16)*(cj2*cj2)))+((pz*x59)))))); +j1eval[2]=IKsign(((3.2625)+(((-27.0)*x57))+(((21.75)*x55))+(((-1.0)*x54*x56))+(((-21.75)*x56))+(((4.05)*cj2))+((x54*x55)))); +if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 || IKabs(j1eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j1eval[3]; +IkReal x60=cj0*cj0; +IkReal x61=px*px; +IkReal x62=pz*pz; +IkReal x63=py*py; +IkReal x64=(px*sj0); +IkReal x65=(cj0*py); +IkReal x66=((27.0)*cj2); +IkReal x67=((27.0)*sj2); +IkReal x68=((25.0)*x61); +IkReal x69=((44.4444444444444)*x61); +IkReal x70=(x60*x63); +j1eval[0]=((-1.0)+(((-44.4444444444444)*x62))+((x60*x69))+(((13.3333333333333)*x64))+(((-44.4444444444444)*x70))+(((-13.3333333333333)*x65))+(((-1.0)*x69))+(((88.8888888888889)*x64*x65))); +j1eval[1]=((IKabs(((3.2625)+(((21.75)*x65))+(((-1.0)*x64*x66))+(((-21.75)*x64))+((pz*x67))+((x65*x66))+(((4.05)*cj2)))))+(IKabs(((((-4.05)*sj2))+(((21.75)*pz))+(((-1.0)*x65*x67))+((pz*x66))+((x64*x67)))))); +j1eval[2]=IKsign(((-0.5625)+(((-7.5)*x65))+((x60*x68))+(((50.0)*x64*x65))+(((-25.0)*x70))+(((-1.0)*x68))+(((-25.0)*x62))+(((7.5)*x64)))); +if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 || IKabs(j1eval[2]) < 0.0000010000000000 ) +{ +continue; // no branches [j1] + +} else +{ +{ +IkReal j1array[1], cj1array[1], sj1array[1]; +bool j1valid[1]={false}; +_nj1 = 1; +IkReal x71=px*px; +IkReal x72=cj0*cj0; +IkReal x73=(px*sj0); +IkReal x74=(cj0*py); +IkReal x75=((27.0)*cj2); +IkReal x76=((27.0)*sj2); +IkReal x77=((25.0)*x71); +CheckValue x78 = IKatan2WithCheck(IkReal(((3.2625)+((pz*x76))+(((-21.75)*x73))+(((-1.0)*x73*x75))+(((21.75)*x74))+((x74*x75))+(((4.05)*cj2)))),IkReal((((pz*x75))+(((-4.05)*sj2))+(((21.75)*pz))+(((-1.0)*x74*x76))+((x73*x76)))),IKFAST_ATAN2_MAGTHRESH); +if(!x78.valid){ +continue; +} +CheckValue x79=IKPowWithIntegerCheck(IKsign(((-0.5625)+(((50.0)*x73*x74))+(((-1.0)*x77))+(((-25.0)*(pz*pz)))+(((-25.0)*x72*(py*py)))+((x72*x77))+(((7.5)*x73))+(((-7.5)*x74)))),-1); +if(!x79.valid){ +continue; +} +j1array[0]=((-1.5707963267949)+(x78.value)+(((1.5707963267949)*(x79.value)))); +sj1array[0]=IKsin(j1array[0]); +cj1array[0]=IKcos(j1array[0]); +if( j1array[0] > IKPI ) +{ + j1array[0]-=IK2PI; +} +else if( j1array[0] < -IKPI ) +{ j1array[0]+=IK2PI; +} +j1valid[0] = true; +for(int ij1 = 0; ij1 < 1; ++ij1) +{ +if( !j1valid[ij1] ) +{ + continue; +} +_ij1[0] = ij1; _ij1[1] = -1; +for(int iij1 = ij1+1; iij1 < 1; ++iij1) +{ +if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) +{ + j1valid[iij1]=false; _ij1[1] = iij1; break; +} +} +j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; +{ +IkReal evalcond[5]; +IkReal x80=IKcos(j1); +IkReal x81=IKsin(j1); +IkReal x82=(cj0*py); +IkReal x83=(px*sj0); +IkReal x84=((1.08)*sj2); +IkReal x85=((1.08)*cj2); +IkReal x86=(pz*x80); +IkReal x87=((1.74)*x81); +evalcond[0]=(((x81*x84))+(((0.87)*x80))+pz+((x80*x85))); +evalcond[1]=((0.15)+(((-1.0)*x80*x84))+((x81*x85))+(((0.87)*x81))+x82+(((-1.0)*x83))); +evalcond[2]=((((-1.0)*x80*x82))+((pz*x81))+x84+(((-0.15)*x80))+((x80*x83))); +evalcond[3]=((0.87)+(((0.15)*x81))+((x81*x82))+(((-1.0)*x81*x83))+x86+x85); +evalcond[4]=((0.387)+(((-1.0)*x82*x87))+(((0.3)*x83))+(((-0.261)*x81))+(((-1.74)*x86))+(((-1.0)*pp))+((x83*x87))+(((-0.3)*x82))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +rotationfunction0(solutions); +} +} + +} + +} + +} else +{ +{ +IkReal j1array[1], cj1array[1], sj1array[1]; +bool j1valid[1]={false}; +_nj1 = 1; +IkReal x863=(px*sj0); +IkReal x864=(cj0*py); +IkReal x865=((27.0)*cj2); +IkReal x866=((25.0)*pz); +CheckValue x867 = IKatan2WithCheck(IkReal(((-18.9225)+(((-46.98)*cj2))+(((-29.16)*(cj2*cj2)))+((pz*x866)))),IkReal(((((23.49)*sj2))+((x863*x866))+(((-1.0)*x864*x866))+(((29.16)*cj2*sj2))+(((-3.75)*pz)))),IKFAST_ATAN2_MAGTHRESH); +if(!x867.valid){ +continue; +} +CheckValue x868=IKPowWithIntegerCheck(IKsign(((3.2625)+(((21.75)*x864))+(((-21.75)*x863))+(((-27.0)*pz*sj2))+((x864*x865))+(((-1.0)*x863*x865))+(((4.05)*cj2)))),-1); +if(!x868.valid){ +continue; +} +j1array[0]=((-1.5707963267949)+(x867.value)+(((1.5707963267949)*(x868.value)))); +sj1array[0]=IKsin(j1array[0]); +cj1array[0]=IKcos(j1array[0]); +if( j1array[0] > IKPI ) +{ + j1array[0]-=IK2PI; +} +else if( j1array[0] < -IKPI ) +{ j1array[0]+=IK2PI; +} +j1valid[0] = true; +for(int ij1 = 0; ij1 < 1; ++ij1) +{ +if( !j1valid[ij1] ) +{ + continue; +} +_ij1[0] = ij1; _ij1[1] = -1; +for(int iij1 = ij1+1; iij1 < 1; ++iij1) +{ +if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) +{ + j1valid[iij1]=false; _ij1[1] = iij1; break; +} +} +j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; +{ +IkReal evalcond[5]; +IkReal x869=IKcos(j1); +IkReal x870=IKsin(j1); +IkReal x871=(cj0*py); +IkReal x872=(px*sj0); +IkReal x873=((1.08)*sj2); +IkReal x874=((1.08)*cj2); +IkReal x875=(pz*x869); +IkReal x876=((1.74)*x870); +evalcond[0]=(((x870*x873))+(((0.87)*x869))+pz+((x869*x874))); +evalcond[1]=((0.15)+((x870*x874))+(((-1.0)*x869*x873))+(((-1.0)*x872))+(((0.87)*x870))+x871); +evalcond[2]=((((-1.0)*x869*x871))+(((-0.15)*x869))+((x869*x872))+x873+((pz*x870))); +evalcond[3]=((0.87)+((x870*x871))+(((-1.0)*x870*x872))+(((0.15)*x870))+x874+x875); +evalcond[4]=((0.387)+(((-0.3)*x871))+(((0.3)*x872))+((x872*x876))+(((-1.0)*x871*x876))+(((-0.261)*x870))+(((-1.0)*pp))+(((-1.74)*x875))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +rotationfunction0(solutions); +} +} + +} + +} + +} else +{ +{ +IkReal j1array[1], cj1array[1], sj1array[1]; +bool j1valid[1]={false}; +_nj1 = 1; +IkReal x877=(cj0*py); +IkReal x878=(px*sj0); +IkReal x879=((675.0)*cj2); +IkReal x880=((675.0)*sj2); +CheckValue x881 = IKatan2WithCheck(IkReal(((81.5625)+(((-543.75)*x878))+((pz*x880))+(((543.75)*x877))+(((-1.0)*x878*x879))+((x877*x879))+(((101.25)*cj2)))),IkReal(((((543.75)*pz))+(((-1.0)*x877*x880))+((x878*x880))+(((-101.25)*sj2))+((pz*x879)))),IKFAST_ATAN2_MAGTHRESH); +if(!x881.valid){ +continue; +} +CheckValue x882=IKPowWithIntegerCheck(IKsign(((-1202.0625)+(((-1174.5)*cj2)))),-1); +if(!x882.valid){ +continue; +} +j1array[0]=((-1.5707963267949)+(x881.value)+(((1.5707963267949)*(x882.value)))); +sj1array[0]=IKsin(j1array[0]); +cj1array[0]=IKcos(j1array[0]); +if( j1array[0] > IKPI ) +{ + j1array[0]-=IK2PI; +} +else if( j1array[0] < -IKPI ) +{ j1array[0]+=IK2PI; +} +j1valid[0] = true; +for(int ij1 = 0; ij1 < 1; ++ij1) +{ +if( !j1valid[ij1] ) +{ + continue; +} +_ij1[0] = ij1; _ij1[1] = -1; +for(int iij1 = ij1+1; iij1 < 1; ++iij1) +{ +if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) +{ + j1valid[iij1]=false; _ij1[1] = iij1; break; +} +} +j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; +{ +IkReal evalcond[5]; +IkReal x883=IKcos(j1); +IkReal x884=IKsin(j1); +IkReal x885=(cj0*py); +IkReal x886=(px*sj0); +IkReal x887=((1.08)*sj2); +IkReal x888=((1.08)*cj2); +IkReal x889=(pz*x883); +IkReal x890=((1.74)*x884); +evalcond[0]=(((x883*x888))+pz+(((0.87)*x883))+((x884*x887))); +evalcond[1]=((0.15)+(((-1.0)*x883*x887))+(((-1.0)*x886))+(((0.87)*x884))+x885+((x884*x888))); +evalcond[2]=((((-0.15)*x883))+(((-1.0)*x883*x885))+((pz*x884))+((x883*x886))+x887); +evalcond[3]=((0.87)+(((-1.0)*x884*x886))+(((0.15)*x884))+x889+x888+((x884*x885))); +evalcond[4]=((0.387)+((x886*x890))+(((-1.74)*x889))+(((0.3)*x886))+(((-1.0)*pp))+(((-0.3)*x885))+(((-1.0)*x885*x890))+(((-0.261)*x884))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +rotationfunction0(solutions); +} +} + +} + +} +} +} +} +} + +} + +} +} +return solutions.GetNumSolutions()>0; +} +inline void rotationfunction0(IkSolutionListBase& solutions) { +for(int rotationiter = 0; rotationiter < 1; ++rotationiter) { +IkReal x88=((1.0)*sj0); +IkReal x89=(cj0*r12); +IkReal x90=((1.0)*sj1); +IkReal x91=((1.0)*cj1); +IkReal x92=(cj0*r11); +IkReal x93=(cj0*r10); +IkReal x94=(((cj2*sj1))+(((-1.0)*sj2*x91))); +IkReal x95=(((cj1*sj2))+(((-1.0)*cj2*x90))); +IkReal x96=((((-1.0)*sj2*x90))+(((-1.0)*cj2*x91))); +new_r00=(((r10*sj0))+((cj0*r00))); +new_r01=(((r11*sj0))+((cj0*r01))); +new_r02=(((r12*sj0))+((cj0*r02))); +new_r10=(((r20*x94))+(((-1.0)*r00*x88*x96))+((x93*x96))); +new_r11=(((r21*x94))+((x92*x96))+(((-1.0)*r01*x88*x96))); +new_r12=(((x89*x96))+(((-1.0)*r02*x88*x96))+((r22*x94))); +new_r20=(((r20*x96))+(((-1.0)*r00*x88*x95))+((x93*x95))); +new_r21=(((r21*x96))+((x92*x95))+(((-1.0)*r01*x88*x95))); +new_r22=(((x89*x95))+(((-1.0)*r02*x88*x95))+((r22*x96))); +{ +IkReal j4array[2], cj4array[2], sj4array[2]; +bool j4valid[2]={false}; +_nj4 = 2; +cj4array[0]=new_r22; +if( cj4array[0] >= -1-IKFAST_SINCOS_THRESH && cj4array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j4valid[0] = j4valid[1] = true; + j4array[0] = IKacos(cj4array[0]); + sj4array[0] = IKsin(j4array[0]); + cj4array[1] = cj4array[0]; + j4array[1] = -j4array[0]; + sj4array[1] = -sj4array[0]; +} +else if( isnan(cj4array[0]) ) +{ + // probably any value will work + j4valid[0] = true; + cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0; +} +for(int ij4 = 0; ij4 < 2; ++ij4) +{ +if( !j4valid[ij4] ) +{ + continue; +} +_ij4[0] = ij4; _ij4[1] = -1; +for(int iij4 = ij4+1; iij4 < 2; ++iij4) +{ +if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH ) +{ + j4valid[iij4]=false; _ij4[1] = iij4; break; +} +} +j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4]; + +{ +IkReal j5eval[3]; +j5eval[0]=sj4; +j5eval[1]=IKsign(sj4); +j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[3]; +j3eval[0]=sj4; +j3eval[1]=IKsign(sj4); +j3eval[2]=((IKabs(new_r12))+(IKabs(new_r02))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[2]; +j3eval[0]=new_r02; +j3eval[1]=sj4; +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[5]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +IkReal j5mul = 1; +j5=0; +j3mul=-1.0; +if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(new_r00)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3=IKatan2(((-1.0)*new_r01), new_r00); +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].fmul = j3mul; +vinfos[3].freeind = 0; +vinfos[3].maxsolutions = 0; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].fmul = j5mul; +vinfos[5].freeind = 0; +vinfos[5].maxsolutions = 0; +std::vector vfree(1); +vfree[0] = 5; +solutions.AddSolution(vinfos,vfree); +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +IkReal j5mul = 1; +j5=0; +j3mul=1.0; +if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3=IKatan2(new_r01, ((-1.0)*new_r11)); +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].fmul = j3mul; +vinfos[3].freeind = 0; +vinfos[3].maxsolutions = 0; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].fmul = j5mul; +vinfos[5].freeind = 0; +vinfos[5].maxsolutions = 0; +std::vector vfree(1); +vfree[0] = 5; +solutions.AddSolution(vinfos,vfree); +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +IkReal x97=new_r22*new_r22; +IkReal x98=((16.0)*new_r10); +IkReal x99=((16.0)*new_r01); +IkReal x100=((16.0)*new_r00); +IkReal x101=(new_r11*new_r22); +IkReal x102=((8.0)*new_r00); +IkReal x103=(x97*x98); +IkReal x104=(x97*x99); +j3eval[0]=((IKabs((((new_r22*x102))+(((-8.0)*new_r11)))))+(IKabs(((((32.0)*new_r00))+(((-16.0)*x101))+(((-1.0)*x100*x97)))))+(IKabs((((x102*x97))+(((-8.0)*x101)))))+(IKabs((x104+(((-1.0)*x99)))))+(IKabs(((((-1.0)*x104))+x99)))+(IKabs(((((-32.0)*new_r11*x97))+((new_r22*x100))+(((16.0)*new_r11)))))+(IKabs(((((-1.0)*x103))+x98)))+(IKabs((x103+(((-1.0)*x98)))))); +if( IKabs(j3eval[0]) < 0.0000000100000000 ) +{ +continue; // no branches [j3, j5] + +} else +{ +IkReal op[4+1], zeror[4]; +int numroots; +IkReal j3evalpoly[1]; +IkReal x105=new_r22*new_r22; +IkReal x106=((16.0)*new_r01); +IkReal x107=(new_r00*new_r22); +IkReal x108=(x105*x106); +IkReal x109=((((8.0)*x107))+(((-8.0)*new_r11))); +op[0]=x109; +op[1]=((((-1.0)*x106))+x108); +op[2]=((((-32.0)*new_r11*x105))+(((16.0)*x107))+(((16.0)*new_r11))); +op[3]=((((-1.0)*x108))+x106); +op[4]=x109; +polyroots4(op,zeror,numroots); +IkReal j3array[4], cj3array[4], sj3array[4], tempj3array[1]; +int numsolutions = 0; +for(int ij3 = 0; ij3 < numroots; ++ij3) +{ +IkReal htj3 = zeror[ij3]; +tempj3array[0]=((2.0)*(atan(htj3))); +for(int kj3 = 0; kj3 < 1; ++kj3) +{ +j3array[numsolutions] = tempj3array[kj3]; +if( j3array[numsolutions] > IKPI ) +{ + j3array[numsolutions]-=IK2PI; +} +else if( j3array[numsolutions] < -IKPI ) +{ + j3array[numsolutions]+=IK2PI; +} +sj3array[numsolutions] = IKsin(j3array[numsolutions]); +cj3array[numsolutions] = IKcos(j3array[numsolutions]); +numsolutions++; +} +} +bool j3valid[4]={true,true,true,true}; +_nj3 = 4; +for(int ij3 = 0; ij3 < numsolutions; ++ij3) + { +if( !j3valid[ij3] ) +{ + continue; +} + j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +htj3 = IKtan(j3/2); + +IkReal x110=new_r22*new_r22; +IkReal x111=((16.0)*new_r10); +IkReal x112=(new_r11*new_r22); +IkReal x113=((8.0)*x112); +IkReal x114=(new_r00*x110); +IkReal x115=(x110*x111); +IkReal x116=((8.0)*x114); +j3evalpoly[0]=((((htj3*htj3)*(((((32.0)*new_r00))+(((-16.0)*x114))+(((-16.0)*x112))))))+(((htj3*htj3*htj3)*(((((-1.0)*x115))+x111))))+(((-1.0)*x113))+x116+((htj3*(((((-1.0)*x111))+x115))))+(((htj3*htj3*htj3*htj3)*(((((-1.0)*x113))+x116))))); +if( IKabs(j3evalpoly[0]) > 0.0000001000000000 ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < numsolutions; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +{ +IkReal j5eval[3]; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +IkReal x117=cj3*cj3; +IkReal x118=new_r22*new_r22; +IkReal x119=(new_r22*sj3); +IkReal x120=((((-1.0)*x117))+(((-1.0)*x118))+((x117*x118))); +j5eval[0]=x120; +j5eval[1]=IKsign(x120); +j5eval[2]=((IKabs((((new_r01*x119))+(((-1.0)*cj3*new_r00)))))+(IKabs((((new_r00*x119))+((cj3*new_r01)))))); +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[1]; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +j5eval[0]=new_r22; +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[1]; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +j5eval[0]=cj3; +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[1]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r11), new_r10); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[4]; +IkReal x121=IKsin(j5); +IkReal x122=IKcos(j5); +evalcond[0]=(x121+new_r11); +evalcond[1]=((-1.0)*x121); +evalcond[2]=((-1.0)*x122); +evalcond[3]=((((-1.0)*x122))+new_r10); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[4]; +IkReal x123=IKsin(j5); +IkReal x124=IKcos(j5); +evalcond[0]=((-1.0)*x123); +evalcond[1]=((-1.0)*x124); +evalcond[2]=(x123+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*new_r10))+(((-1.0)*x124))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +IkReal x125=new_r22*new_r22; +CheckValue x126=IKPowWithIntegerCheck(((-1.0)+x125),-1); +if(!x126.valid){ +continue; +} +if(((x125*(x126.value))) < -0.00001) +continue; +IkReal gconst12=IKsqrt((x125*(x126.value))); +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst12)))))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[1]; +IkReal x127=new_r22*new_r22; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))); +cj3=gconst12; +if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH ) + continue; +j3=IKacos(gconst12); +CheckValue x128=IKPowWithIntegerCheck(((-1.0)+x127),-1); +if(!x128.valid){ +continue; +} +if(((x127*(x128.value))) < -0.00001) +continue; +IkReal gconst12=IKsqrt((x127*(x128.value))); +j5eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +CheckValue x129=IKPowWithIntegerCheck(gconst12,-1); +if(!x129.valid){ +continue; +} +if( IKabs(((((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r01)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r00*(x129.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r01))))+IKsqr((new_r00*(x129.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r01))), (new_r00*(x129.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x130=IKsin(j5); +IkReal x131=IKcos(j5); +IkReal x132=((1.0)*x131); +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +IkReal x133=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))); +evalcond[0]=((-1.0)*x130); +evalcond[1]=((-1.0)*x131); +evalcond[2]=(((gconst12*x130))+new_r01); +evalcond[3]=((((-1.0)*gconst12*x132))+new_r00); +evalcond[4]=(((x130*x133))+new_r11); +evalcond[5]=((((-1.0)*x132*x133))+new_r10); +evalcond[6]=(((gconst12*new_r01))+x130+((new_r11*x133))); +evalcond[7]=(((gconst12*new_r00))+(((-1.0)*x132))+((new_r10*x133))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x134 = IKatan2WithCheck(IkReal(((-1.0)*new_r01)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH); +if(!x134.valid){ +continue; +} +CheckValue x135=IKPowWithIntegerCheck(IKsign(gconst12),-1); +if(!x135.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(x134.value)+(((1.5707963267949)*(x135.value)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x136=IKsin(j5); +IkReal x137=IKcos(j5); +IkReal x138=((1.0)*x137); +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +IkReal x139=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))); +evalcond[0]=((-1.0)*x136); +evalcond[1]=((-1.0)*x137); +evalcond[2]=(((gconst12*x136))+new_r01); +evalcond[3]=((((-1.0)*gconst12*x138))+new_r00); +evalcond[4]=(((x136*x139))+new_r11); +evalcond[5]=((((-1.0)*x138*x139))+new_r10); +evalcond[6]=(((gconst12*new_r01))+x136+((new_r11*x139))); +evalcond[7]=(((gconst12*new_r00))+(((-1.0)*x138))+((new_r10*x139))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +IkReal x140=new_r22*new_r22; +CheckValue x141=IKPowWithIntegerCheck(((-1.0)+x140),-1); +if(!x141.valid){ +continue; +} +if(((x140*(x141.value))) < -0.00001) +continue; +IkReal gconst12=IKsqrt((x140*(x141.value))); +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst12)))))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[1]; +IkReal x142=new_r22*new_r22; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))); +cj3=gconst12; +if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH ) + continue; +j3=((-1.0)*(IKacos(gconst12))); +CheckValue x143=IKPowWithIntegerCheck(((-1.0)+x142),-1); +if(!x143.valid){ +continue; +} +if(((x142*(x143.value))) < -0.00001) +continue; +IkReal gconst12=IKsqrt((x142*(x143.value))); +j5eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +CheckValue x144=IKPowWithIntegerCheck(gconst12,-1); +if(!x144.valid){ +continue; +} +if( IKabs((((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r01)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r00*(x144.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r01))))+IKsqr((new_r00*(x144.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2((((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r01))), (new_r00*(x144.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x145=IKsin(j5); +IkReal x146=IKcos(j5); +IkReal x147=((1.0)*x146); +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +IkReal x148=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))); +IkReal x149=((1.0)*x148); +evalcond[0]=((-1.0)*x145); +evalcond[1]=((-1.0)*x146); +evalcond[2]=(((gconst12*x145))+new_r01); +evalcond[3]=((((-1.0)*gconst12*x147))+new_r00); +evalcond[4]=(((x146*x148))+new_r10); +evalcond[5]=((((-1.0)*x145*x149))+new_r11); +evalcond[6]=(((gconst12*new_r01))+(((-1.0)*new_r11*x149))+x145); +evalcond[7]=((((-1.0)*x147))+((gconst12*new_r00))+(((-1.0)*new_r10*x149))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x150 = IKatan2WithCheck(IkReal(((-1.0)*new_r01)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH); +if(!x150.valid){ +continue; +} +CheckValue x151=IKPowWithIntegerCheck(IKsign(gconst12),-1); +if(!x151.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(x150.value)+(((1.5707963267949)*(x151.value)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x152=IKsin(j5); +IkReal x153=IKcos(j5); +IkReal x154=((1.0)*x153); +if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001) +continue; +IkReal x155=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))); +IkReal x156=((1.0)*x155); +evalcond[0]=((-1.0)*x152); +evalcond[1]=((-1.0)*x153); +evalcond[2]=(((gconst12*x152))+new_r01); +evalcond[3]=(new_r00+(((-1.0)*gconst12*x154))); +evalcond[4]=(((x153*x155))+new_r10); +evalcond[5]=((((-1.0)*x152*x156))+new_r11); +evalcond[6]=(((gconst12*new_r01))+x152+(((-1.0)*new_r11*x156))); +evalcond[7]=(((gconst12*new_r00))+(((-1.0)*x154))+(((-1.0)*new_r10*x156))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +IkReal x157=new_r22*new_r22; +CheckValue x158=IKPowWithIntegerCheck(((-1.0)+x157),-1); +if(!x158.valid){ +continue; +} +if(((x157*(x158.value))) < -0.00001) +continue; +IkReal gconst13=((-1.0)*(IKsqrt((x157*(x158.value))))); +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst13)))))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[1]; +IkReal x159=new_r22*new_r22; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))); +cj3=gconst13; +if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH ) + continue; +j3=IKacos(gconst13); +CheckValue x160=IKPowWithIntegerCheck(((-1.0)+x159),-1); +if(!x160.valid){ +continue; +} +if(((x159*(x160.value))) < -0.00001) +continue; +IkReal gconst13=((-1.0)*(IKsqrt((x159*(x160.value))))); +j5eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +CheckValue x161=IKPowWithIntegerCheck(gconst13,-1); +if(!x161.valid){ +continue; +} +if( IKabs(((((-1.0)*gconst13*new_r01))+(((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r00*(x161.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*gconst13*new_r01))+(((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))))+IKsqr((new_r00*(x161.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*gconst13*new_r01))+(((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))), (new_r00*(x161.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x162=IKsin(j5); +IkReal x163=IKcos(j5); +IkReal x164=((1.0)*x163); +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +IkReal x165=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))); +evalcond[0]=((-1.0)*x162); +evalcond[1]=((-1.0)*x163); +evalcond[2]=(new_r01+((gconst13*x162))); +evalcond[3]=(new_r00+(((-1.0)*gconst13*x164))); +evalcond[4]=(((x162*x165))+new_r11); +evalcond[5]=(new_r10+(((-1.0)*x164*x165))); +evalcond[6]=(((new_r11*x165))+x162+((gconst13*new_r01))); +evalcond[7]=((((-1.0)*x164))+((new_r10*x165))+((gconst13*new_r00))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x166 = IKatan2WithCheck(IkReal(((-1.0)*new_r01)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH); +if(!x166.valid){ +continue; +} +CheckValue x167=IKPowWithIntegerCheck(IKsign(gconst13),-1); +if(!x167.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(x166.value)+(((1.5707963267949)*(x167.value)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x168=IKsin(j5); +IkReal x169=IKcos(j5); +IkReal x170=((1.0)*x169); +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +IkReal x171=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))); +evalcond[0]=((-1.0)*x168); +evalcond[1]=((-1.0)*x169); +evalcond[2]=(new_r01+((gconst13*x168))); +evalcond[3]=((((-1.0)*gconst13*x170))+new_r00); +evalcond[4]=(((x168*x171))+new_r11); +evalcond[5]=((((-1.0)*x170*x171))+new_r10); +evalcond[6]=(((new_r11*x171))+x168+((gconst13*new_r01))); +evalcond[7]=(((new_r10*x171))+(((-1.0)*x170))+((gconst13*new_r00))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +IkReal x172=new_r22*new_r22; +CheckValue x173=IKPowWithIntegerCheck(((-1.0)+x172),-1); +if(!x173.valid){ +continue; +} +if(((x172*(x173.value))) < -0.00001) +continue; +IkReal gconst13=((-1.0)*(IKsqrt((x172*(x173.value))))); +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs((cj3+(((-1.0)*gconst13)))))+(IKabs(((1.0)+(IKsign(sj3)))))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[1]; +IkReal x174=new_r22*new_r22; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))); +cj3=gconst13; +if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH ) + continue; +j3=((-1.0)*(IKacos(gconst13))); +CheckValue x175=IKPowWithIntegerCheck(((-1.0)+x174),-1); +if(!x175.valid){ +continue; +} +if(((x174*(x175.value))) < -0.00001) +continue; +IkReal gconst13=((-1.0)*(IKsqrt((x174*(x175.value))))); +j5eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +CheckValue x176=IKPowWithIntegerCheck(gconst13,-1); +if(!x176.valid){ +continue; +} +if( IKabs(((((-1.0)*gconst13*new_r01))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r00*(x176.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*gconst13*new_r01))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))))+IKsqr((new_r00*(x176.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*gconst13*new_r01))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))), (new_r00*(x176.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x177=IKsin(j5); +IkReal x178=IKcos(j5); +IkReal x179=((1.0)*x178); +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +IkReal x180=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))); +IkReal x181=((1.0)*x180); +evalcond[0]=((-1.0)*x177); +evalcond[1]=((-1.0)*x178); +evalcond[2]=(new_r01+((gconst13*x177))); +evalcond[3]=((((-1.0)*gconst13*x179))+new_r00); +evalcond[4]=(((x178*x180))+new_r10); +evalcond[5]=((((-1.0)*x177*x181))+new_r11); +evalcond[6]=(x177+(((-1.0)*new_r11*x181))+((gconst13*new_r01))); +evalcond[7]=((((-1.0)*x179))+((gconst13*new_r00))+(((-1.0)*new_r10*x181))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x182 = IKatan2WithCheck(IkReal(((-1.0)*new_r01)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH); +if(!x182.valid){ +continue; +} +CheckValue x183=IKPowWithIntegerCheck(IKsign(gconst13),-1); +if(!x183.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(x182.value)+(((1.5707963267949)*(x183.value)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x184=IKsin(j5); +IkReal x185=IKcos(j5); +IkReal x186=((1.0)*x185); +if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001) +continue; +IkReal x187=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))); +IkReal x188=((1.0)*x187); +evalcond[0]=((-1.0)*x184); +evalcond[1]=((-1.0)*x185); +evalcond[2]=(((gconst13*x184))+new_r01); +evalcond[3]=((((-1.0)*gconst13*x186))+new_r00); +evalcond[4]=(((x185*x187))+new_r10); +evalcond[5]=((((-1.0)*x184*x188))+new_r11); +evalcond[6]=(x184+(((-1.0)*new_r11*x188))+((gconst13*new_r01))); +evalcond[7]=((((-1.0)*x186))+((gconst13*new_r00))+(((-1.0)*new_r10*x188))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j5] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +IkReal x189=((1.0)*new_r22); +IkReal x190=(cj3*new_r01); +CheckValue x191=IKPowWithIntegerCheck(cj3,-1); +if(!x191.valid){ +continue; +} +if( IKabs(((((-1.0)*x190))+(((-1.0)*new_r11*sj3)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x191.value)*(((((-1.0)*new_r11*x189))+((new_r11*new_r22*(cj3*cj3)))+new_r00+(((-1.0)*sj3*x189*x190)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x190))+(((-1.0)*new_r11*sj3))))+IKsqr(((x191.value)*(((((-1.0)*new_r11*x189))+((new_r11*new_r22*(cj3*cj3)))+new_r00+(((-1.0)*sj3*x189*x190))))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*x190))+(((-1.0)*new_r11*sj3))), ((x191.value)*(((((-1.0)*new_r11*x189))+((new_r11*new_r22*(cj3*cj3)))+new_r00+(((-1.0)*sj3*x189*x190)))))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[10]; +IkReal x192=IKsin(j5); +IkReal x193=IKcos(j5); +IkReal x194=((1.0)*cj3); +IkReal x195=((1.0)*sj3); +IkReal x196=(cj3*new_r10); +IkReal x197=(cj3*new_r11); +IkReal x198=((1.0)*x193); +IkReal x199=(new_r22*x193); +IkReal x200=(sj3*x192); +IkReal x201=(new_r22*x192); +evalcond[0]=(((new_r11*sj3))+x192+((cj3*new_r01))); +evalcond[1]=(((new_r10*sj3))+(((-1.0)*x198))+((cj3*new_r00))); +evalcond[2]=(((sj3*x199))+((cj3*x192))+new_r01); +evalcond[3]=(((new_r22*x200))+new_r00+(((-1.0)*x193*x194))); +evalcond[4]=((((-1.0)*x194*x199))+x200+new_r11); +evalcond[5]=(x196+(((-1.0)*new_r00*x195))+(((-1.0)*x201))); +evalcond[6]=((((-1.0)*new_r22*x198))+x197+(((-1.0)*new_r01*x195))); +evalcond[7]=((((-1.0)*x194*x201))+new_r10+(((-1.0)*x193*x195))); +evalcond[8]=((((-1.0)*new_r00*new_r22*x195))+(((-1.0)*x192))+((new_r22*x196))); +evalcond[9]=((((-1.0)*x198))+((new_r22*x197))+(((-1.0)*new_r01*new_r22*x195))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +IkReal x202=((1.0)*new_r01); +CheckValue x203=IKPowWithIntegerCheck(new_r22,-1); +if(!x203.valid){ +continue; +} +if( IKabs(((((-1.0)*new_r11*sj3))+(((-1.0)*cj3*x202)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x203.value)*((((cj3*new_r11))+(((-1.0)*sj3*x202)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r11*sj3))+(((-1.0)*cj3*x202))))+IKsqr(((x203.value)*((((cj3*new_r11))+(((-1.0)*sj3*x202))))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*new_r11*sj3))+(((-1.0)*cj3*x202))), ((x203.value)*((((cj3*new_r11))+(((-1.0)*sj3*x202)))))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[10]; +IkReal x204=IKsin(j5); +IkReal x205=IKcos(j5); +IkReal x206=((1.0)*cj3); +IkReal x207=((1.0)*sj3); +IkReal x208=(cj3*new_r10); +IkReal x209=(cj3*new_r11); +IkReal x210=((1.0)*x205); +IkReal x211=(new_r22*x205); +IkReal x212=(sj3*x204); +IkReal x213=(new_r22*x204); +evalcond[0]=(((new_r11*sj3))+x204+((cj3*new_r01))); +evalcond[1]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x210))); +evalcond[2]=(((cj3*x204))+((sj3*x211))+new_r01); +evalcond[3]=(((new_r22*x212))+(((-1.0)*x205*x206))+new_r00); +evalcond[4]=((((-1.0)*x206*x211))+x212+new_r11); +evalcond[5]=((((-1.0)*new_r00*x207))+x208+(((-1.0)*x213))); +evalcond[6]=(x209+(((-1.0)*new_r22*x210))+(((-1.0)*new_r01*x207))); +evalcond[7]=((((-1.0)*x206*x213))+(((-1.0)*x205*x207))+new_r10); +evalcond[8]=(((new_r22*x208))+(((-1.0)*new_r00*new_r22*x207))+(((-1.0)*x204))); +evalcond[9]=((((-1.0)*new_r01*new_r22*x207))+((new_r22*x209))+(((-1.0)*x210))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +IkReal x214=cj3*cj3; +IkReal x215=new_r22*new_r22; +IkReal x216=(new_r22*sj3); +CheckValue x217=IKPowWithIntegerCheck(IKsign((((x214*x215))+(((-1.0)*x214))+(((-1.0)*x215)))),-1); +if(!x217.valid){ +continue; +} +CheckValue x218 = IKatan2WithCheck(IkReal((((new_r00*x216))+((cj3*new_r01)))),IkReal(((((-1.0)*cj3*new_r00))+((new_r01*x216)))),IKFAST_ATAN2_MAGTHRESH); +if(!x218.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x217.value)))+(x218.value)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[10]; +IkReal x219=IKsin(j5); +IkReal x220=IKcos(j5); +IkReal x221=((1.0)*cj3); +IkReal x222=((1.0)*sj3); +IkReal x223=(cj3*new_r10); +IkReal x224=(cj3*new_r11); +IkReal x225=((1.0)*x220); +IkReal x226=(new_r22*x220); +IkReal x227=(sj3*x219); +IkReal x228=(new_r22*x219); +evalcond[0]=(((new_r11*sj3))+x219+((cj3*new_r01))); +evalcond[1]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x225))); +evalcond[2]=(((cj3*x219))+((sj3*x226))+new_r01); +evalcond[3]=((((-1.0)*x220*x221))+((new_r22*x227))+new_r00); +evalcond[4]=(x227+(((-1.0)*x221*x226))+new_r11); +evalcond[5]=(x223+(((-1.0)*new_r00*x222))+(((-1.0)*x228))); +evalcond[6]=((((-1.0)*new_r01*x222))+x224+(((-1.0)*new_r22*x225))); +evalcond[7]=((((-1.0)*x220*x222))+(((-1.0)*x221*x228))+new_r10); +evalcond[8]=((((-1.0)*new_r00*new_r22*x222))+(((-1.0)*x219))+((new_r22*x223))); +evalcond[9]=((((-1.0)*new_r01*new_r22*x222))+((new_r22*x224))+(((-1.0)*x225))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + } + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j3, j5] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x230=IKPowWithIntegerCheck(sj4,-1); +if(!x230.valid){ +continue; +} +IkReal x229=x230.value; +CheckValue x231=IKPowWithIntegerCheck(new_r02,-1); +if(!x231.valid){ +continue; +} +if( IKabs((x229*(x231.value)*(((1.0)+(((-1.0)*(cj4*cj4)))+(((-1.0)*(new_r12*new_r12))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r12*x229)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x229*(x231.value)*(((1.0)+(((-1.0)*(cj4*cj4)))+(((-1.0)*(new_r12*new_r12)))))))+IKsqr(((-1.0)*new_r12*x229))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((x229*(x231.value)*(((1.0)+(((-1.0)*(cj4*cj4)))+(((-1.0)*(new_r12*new_r12)))))), ((-1.0)*new_r12*x229)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x232=IKsin(j3); +IkReal x233=IKcos(j3); +IkReal x234=((1.0)*cj4); +IkReal x235=((1.0)*sj4); +IkReal x236=(new_r02*x232); +IkReal x237=(new_r12*x233); +IkReal x238=(sj4*x233); +evalcond[0]=(x238+new_r12); +evalcond[1]=(new_r02+(((-1.0)*x232*x235))); +evalcond[2]=(((new_r02*x233))+((new_r12*x232))); +evalcond[3]=(sj4+x237+(((-1.0)*x236))); +evalcond[4]=(((new_r22*sj4))+((cj4*x237))+(((-1.0)*x234*x236))); +evalcond[5]=(((new_r10*x238))+(((-1.0)*new_r20*x234))+(((-1.0)*new_r00*x232*x235))); +evalcond[6]=((((-1.0)*new_r01*x232*x235))+(((-1.0)*new_r21*x234))+((new_r11*x238))); +evalcond[7]=((1.0)+(((-1.0)*new_r22*x234))+(((-1.0)*x235*x236))+((sj4*x237))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +IkReal j5eval[3]; +j5eval[0]=sj4; +j5eval[1]=IKsign(sj4); +j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[2]; +j5eval[0]=sj4; +j5eval[1]=cj3; +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[3]; +j5eval[0]=sj4; +j5eval[1]=cj4; +j5eval[2]=sj3; +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[5]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +IkReal x239=((1.0)*new_r01); +if( IKabs(((((-1.0)*cj3*x239))+(((-1.0)*new_r00*sj3)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj3*new_r00))+(((-1.0)*sj3*x239)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*cj3*x239))+(((-1.0)*new_r00*sj3))))+IKsqr((((cj3*new_r00))+(((-1.0)*sj3*x239))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*cj3*x239))+(((-1.0)*new_r00*sj3))), (((cj3*new_r00))+(((-1.0)*sj3*x239)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x240=IKsin(j5); +IkReal x241=IKcos(j5); +IkReal x242=((1.0)*sj3); +IkReal x243=(sj3*x240); +IkReal x244=((1.0)*x241); +IkReal x245=((1.0)*x240); +IkReal x246=(cj3*x244); +evalcond[0]=(((new_r11*sj3))+x240+((cj3*new_r01))); +evalcond[1]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x244))); +evalcond[2]=(((sj3*x241))+new_r01+((cj3*x240))); +evalcond[3]=(x243+(((-1.0)*x246))+new_r00); +evalcond[4]=(x243+(((-1.0)*x246))+new_r11); +evalcond[5]=((((-1.0)*new_r00*x242))+((cj3*new_r10))+(((-1.0)*x245))); +evalcond[6]=((((-1.0)*new_r01*x242))+((cj3*new_r11))+(((-1.0)*x244))); +evalcond[7]=((((-1.0)*x241*x242))+(((-1.0)*cj3*x245))+new_r10); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +IkReal x247=((1.0)*cj3); +if( IKabs(((((-1.0)*new_r01*x247))+(((-1.0)*new_r11*sj3)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((new_r01*sj3))+(((-1.0)*new_r11*x247)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r01*x247))+(((-1.0)*new_r11*sj3))))+IKsqr((((new_r01*sj3))+(((-1.0)*new_r11*x247))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*new_r01*x247))+(((-1.0)*new_r11*sj3))), (((new_r01*sj3))+(((-1.0)*new_r11*x247)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x248=IKsin(j5); +IkReal x249=IKcos(j5); +IkReal x250=((1.0)*sj3); +IkReal x251=(cj3*x248); +IkReal x252=((1.0)*x249); +IkReal x253=(x249*x250); +evalcond[0]=(((new_r11*sj3))+x248+((cj3*new_r01))); +evalcond[1]=(x248+((cj3*new_r10))+(((-1.0)*new_r00*x250))); +evalcond[2]=((((-1.0)*new_r01*x250))+x249+((cj3*new_r11))); +evalcond[3]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x252))); +evalcond[4]=(((sj3*x248))+new_r11+((cj3*x249))); +evalcond[5]=(x251+new_r01+(((-1.0)*x253))); +evalcond[6]=(x251+new_r10+(((-1.0)*x253))); +evalcond[7]=((((-1.0)*x248*x250))+(((-1.0)*cj3*x252))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r20, new_r21); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x254=IKsin(j5); +IkReal x255=IKcos(j5); +IkReal x256=((1.0)*x255); +IkReal x257=((1.0)*x254); +evalcond[0]=(new_r20+(((-1.0)*x257))); +evalcond[1]=(new_r21+(((-1.0)*x256))); +evalcond[2]=(((sj3*x254))+new_r11); +evalcond[3]=(new_r01+(((-1.0)*new_r12*x257))); +evalcond[4]=((((-1.0)*cj3*x256))+new_r00); +evalcond[5]=((((-1.0)*sj3*x256))+new_r10); +evalcond[6]=(((new_r11*sj3))+x254+((cj3*new_r01))); +evalcond[7]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x256))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(((-1.0)*new_r20)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20))+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x258=IKsin(j5); +IkReal x259=IKcos(j5); +IkReal x260=((1.0)*x259); +evalcond[0]=(x258+new_r20); +evalcond[1]=(x259+new_r21); +evalcond[2]=(((new_r12*x258))+new_r01); +evalcond[3]=(((sj3*x258))+new_r11); +evalcond[4]=((((-1.0)*cj3*x260))+new_r00); +evalcond[5]=((((-1.0)*sj3*x260))+new_r10); +evalcond[6]=(((new_r11*sj3))+x258+((cj3*new_r01))); +evalcond[7]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x260))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j3))), 6.28318530717959))); +evalcond[1]=new_r02; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(new_r00)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r01), new_r00); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x261=IKsin(j5); +IkReal x262=IKcos(j5); +IkReal x263=((1.0)*cj4); +IkReal x264=((1.0)*x262); +IkReal x265=((1.0)*x261); +evalcond[0]=(x261+new_r01); +evalcond[1]=(new_r00+(((-1.0)*x264))); +evalcond[2]=((((-1.0)*sj4*x265))+new_r20); +evalcond[3]=((((-1.0)*sj4*x264))+new_r21); +evalcond[4]=((((-1.0)*x262*x263))+new_r11); +evalcond[5]=((((-1.0)*x261*x263))+new_r10); +evalcond[6]=(((new_r20*sj4))+((cj4*new_r10))+(((-1.0)*x265))); +evalcond[7]=(((cj4*new_r11))+((new_r21*sj4))+(((-1.0)*x264))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j3)))), 6.28318530717959))); +evalcond[1]=new_r02; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(((-1.0)*new_r00))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r01, ((-1.0)*new_r00)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x266=IKsin(j5); +IkReal x267=IKcos(j5); +IkReal x268=((1.0)*cj4); +IkReal x269=((1.0)*x267); +IkReal x270=((1.0)*x266); +evalcond[0]=(x266+(((-1.0)*new_r01))); +evalcond[1]=(((cj4*x267))+new_r11); +evalcond[2]=((((-1.0)*sj4*x270))+new_r20); +evalcond[3]=((((-1.0)*sj4*x269))+new_r21); +evalcond[4]=((((-1.0)*new_r00))+(((-1.0)*x269))); +evalcond[5]=((((-1.0)*new_r10))+(((-1.0)*x266*x268))); +evalcond[6]=(((new_r20*sj4))+(((-1.0)*new_r10*x268))+(((-1.0)*x270))); +evalcond[7]=((((-1.0)*new_r11*x268))+((new_r21*sj4))+(((-1.0)*x269))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959))); +evalcond[1]=new_r12; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r11), new_r10); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x271=IKcos(j5); +IkReal x272=IKsin(j5); +IkReal x273=((1.0)*cj4); +IkReal x274=((1.0)*x271); +IkReal x275=((1.0)*x272); +evalcond[0]=(x272+new_r11); +evalcond[1]=((((-1.0)*x274))+new_r10); +evalcond[2]=(((cj4*x271))+new_r01); +evalcond[3]=(((cj4*x272))+new_r00); +evalcond[4]=((((-1.0)*new_r02*x275))+new_r20); +evalcond[5]=((((-1.0)*new_r02*x274))+new_r21); +evalcond[6]=(((new_r20*sj4))+(((-1.0)*new_r00*x273))+(((-1.0)*x275))); +evalcond[7]=((((-1.0)*new_r01*x273))+(((-1.0)*x274))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959))); +evalcond[1]=new_r12; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[3]; +sj3=-1.0; +cj3=0; +j3=-1.5707963267949; +j5eval[0]=new_r02; +j5eval[1]=IKsign(new_r02); +j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[1]; +sj3=-1.0; +cj3=0; +j3=-1.5707963267949; +j5eval[0]=new_r02; +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[2]; +sj3=-1.0; +cj3=0; +j3=-1.5707963267949; +j5eval[0]=new_r02; +j5eval[1]=cj4; +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[4]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +evalcond[2]=new_r01; +evalcond[3]=new_r00; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r20, new_r21); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[4]; +IkReal x276=IKsin(j5); +IkReal x277=((1.0)*(IKcos(j5))); +evalcond[0]=((((-1.0)*x276))+new_r20); +evalcond[1]=((((-1.0)*x277))+new_r21); +evalcond[2]=(x276+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*new_r10))+(((-1.0)*x277))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +evalcond[2]=new_r01; +evalcond[3]=new_r00; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r21)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[4]; +IkReal x278=IKsin(j5); +IkReal x279=IKcos(j5); +evalcond[0]=(x278+new_r20); +evalcond[1]=(x279+new_r21); +evalcond[2]=(x278+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x279))+(((-1.0)*new_r10))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=IKabs(new_r02); +evalcond[1]=new_r20; +evalcond[2]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[6]; +IkReal x280=IKsin(j5); +IkReal x281=IKcos(j5); +IkReal x282=((1.0)*cj4); +IkReal x283=((1.0)*x281); +evalcond[0]=(x280+(((-1.0)*new_r11))); +evalcond[1]=((((-1.0)*x281*x282))+new_r01); +evalcond[2]=((((-1.0)*x280*x282))+new_r00); +evalcond[3]=((((-1.0)*new_r10))+(((-1.0)*x283))); +evalcond[4]=(((cj4*new_r00))+(((-1.0)*x280))); +evalcond[5]=(((cj4*new_r01))+(((-1.0)*x283))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[6]; +IkReal x284=IKcos(j5); +IkReal x285=IKsin(j5); +IkReal x286=((-1.0)*x285); +IkReal x287=((-1.0)*x284); +evalcond[0]=x286; +evalcond[1]=x287; +evalcond[2]=(new_r22*x287); +evalcond[3]=(new_r22*x286); +evalcond[4]=(x285+(((-1.0)*new_r11))); +evalcond[5]=((((-1.0)*x284))+(((-1.0)*new_r10))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j5] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x288=IKPowWithIntegerCheck(new_r02,-1); +if(!x288.valid){ +continue; +} +CheckValue x289=IKPowWithIntegerCheck(cj4,-1); +if(!x289.valid){ +continue; +} +if( IKabs(((-1.0)*new_r20*(x288.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x289.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20*(x288.value)))+IKsqr((new_r01*(x289.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r20*(x288.value)), (new_r01*(x289.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x290=IKsin(j5); +IkReal x291=IKcos(j5); +IkReal x292=((1.0)*cj4); +IkReal x293=((1.0)*x291); +evalcond[0]=(((new_r02*x290))+new_r20); +evalcond[1]=(((new_r02*x291))+new_r21); +evalcond[2]=(x290+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x291*x292))+new_r01); +evalcond[4]=((((-1.0)*x290*x292))+new_r00); +evalcond[5]=((((-1.0)*x293))+(((-1.0)*new_r10))); +evalcond[6]=((((-1.0)*x290))+((new_r20*sj4))+((cj4*new_r00))); +evalcond[7]=(((cj4*new_r01))+(((-1.0)*x293))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x294=IKPowWithIntegerCheck(new_r02,-1); +if(!x294.valid){ +continue; +} +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21*(x294.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r21*(x294.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r21*(x294.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x295=IKsin(j5); +IkReal x296=IKcos(j5); +IkReal x297=((1.0)*cj4); +IkReal x298=((1.0)*x296); +evalcond[0]=(((new_r02*x295))+new_r20); +evalcond[1]=(((new_r02*x296))+new_r21); +evalcond[2]=(x295+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x296*x297))+new_r01); +evalcond[4]=((((-1.0)*x295*x297))+new_r00); +evalcond[5]=((((-1.0)*x298))+(((-1.0)*new_r10))); +evalcond[6]=((((-1.0)*x295))+((new_r20*sj4))+((cj4*new_r00))); +evalcond[7]=(((cj4*new_r01))+(((-1.0)*x298))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x299=IKPowWithIntegerCheck(IKsign(new_r02),-1); +if(!x299.valid){ +continue; +} +CheckValue x300 = IKatan2WithCheck(IkReal(((-1.0)*new_r20)),IkReal(((-1.0)*new_r21)),IKFAST_ATAN2_MAGTHRESH); +if(!x300.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x299.value)))+(x300.value)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x301=IKsin(j5); +IkReal x302=IKcos(j5); +IkReal x303=((1.0)*cj4); +IkReal x304=((1.0)*x302); +evalcond[0]=(((new_r02*x301))+new_r20); +evalcond[1]=(((new_r02*x302))+new_r21); +evalcond[2]=(x301+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x302*x303))+new_r01); +evalcond[4]=((((-1.0)*x301*x303))+new_r00); +evalcond[5]=((((-1.0)*new_r10))+(((-1.0)*x304))); +evalcond[6]=(((new_r20*sj4))+((cj4*new_r00))+(((-1.0)*x301))); +evalcond[7]=(((cj4*new_r01))+((new_r21*sj4))+(((-1.0)*x304))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[1]; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +j5eval[0]=1.0; +if( IKabs(j5eval[0]) < 0.0000000100000000 ) +{ +continue; // no branches [j5] + +} else +{ +IkReal op[2+1], zeror[2]; +int numroots; +op[0]=1.0; +op[1]=0; +op[2]=-1.0; +polyroots2(op,zeror,numroots); +IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1]; +int numsolutions = 0; +for(int ij5 = 0; ij5 < numroots; ++ij5) +{ +IkReal htj5 = zeror[ij5]; +tempj5array[0]=((2.0)*(atan(htj5))); +for(int kj5 = 0; kj5 < 1; ++kj5) +{ +j5array[numsolutions] = tempj5array[kj5]; +if( j5array[numsolutions] > IKPI ) +{ + j5array[numsolutions]-=IK2PI; +} +else if( j5array[numsolutions] < -IKPI ) +{ + j5array[numsolutions]+=IK2PI; +} +sj5array[numsolutions] = IKsin(j5array[numsolutions]); +cj5array[numsolutions] = IKcos(j5array[numsolutions]); +numsolutions++; +} +} +bool j5valid[2]={true,true}; +_nj5 = 2; +for(int ij5 = 0; ij5 < numsolutions; ++ij5) + { +if( !j5valid[ij5] ) +{ + continue; +} + j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +htj5 = IKtan(j5/2); + +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} + } + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j5] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} +} +} +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x306=IKPowWithIntegerCheck(sj4,-1); +if(!x306.valid){ +continue; +} +IkReal x305=x306.value; +CheckValue x307=IKPowWithIntegerCheck(cj4,-1); +if(!x307.valid){ +continue; +} +CheckValue x308=IKPowWithIntegerCheck(sj3,-1); +if(!x308.valid){ +continue; +} +if( IKabs((new_r20*x305)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x305*(x307.value)*(x308.value)*(((((-1.0)*new_r01*sj4))+(((-1.0)*cj3*new_r20)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x305))+IKsqr((x305*(x307.value)*(x308.value)*(((((-1.0)*new_r01*sj4))+(((-1.0)*cj3*new_r20))))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2((new_r20*x305), (x305*(x307.value)*(x308.value)*(((((-1.0)*new_r01*sj4))+(((-1.0)*cj3*new_r20)))))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[12]; +IkReal x309=IKsin(j5); +IkReal x310=IKcos(j5); +IkReal x311=(cj4*sj3); +IkReal x312=(cj3*new_r10); +IkReal x313=((1.0)*new_r01); +IkReal x314=(cj3*new_r11); +IkReal x315=((1.0)*new_r00); +IkReal x316=((1.0)*x310); +IkReal x317=(cj4*x309); +IkReal x318=((1.0)*x309); +evalcond[0]=((((-1.0)*sj4*x318))+new_r20); +evalcond[1]=((((-1.0)*sj4*x316))+new_r21); +evalcond[2]=(((new_r11*sj3))+x309+((cj3*new_r01))); +evalcond[3]=(((new_r10*sj3))+(((-1.0)*x316))+((cj3*new_r00))); +evalcond[4]=(((x310*x311))+((cj3*x309))+new_r01); +evalcond[5]=(((x309*x311))+new_r00+(((-1.0)*cj3*x316))); +evalcond[6]=(((sj3*x309))+(((-1.0)*cj3*cj4*x316))+new_r11); +evalcond[7]=((((-1.0)*sj3*x315))+x312+(((-1.0)*x317))); +evalcond[8]=((((-1.0)*sj3*x313))+(((-1.0)*cj4*x316))+x314); +evalcond[9]=((((-1.0)*cj3*x317))+(((-1.0)*sj3*x316))+new_r10); +evalcond[10]=(((new_r20*sj4))+((cj4*x312))+(((-1.0)*x318))+(((-1.0)*x311*x315))); +evalcond[11]=(((cj4*x314))+(((-1.0)*x316))+((new_r21*sj4))+(((-1.0)*x311*x313))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x320=IKPowWithIntegerCheck(sj4,-1); +if(!x320.valid){ +continue; +} +IkReal x319=x320.value; +CheckValue x321=IKPowWithIntegerCheck(cj3,-1); +if(!x321.valid){ +continue; +} +if( IKabs((new_r20*x319)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x319*(x321.value)*((((new_r00*sj4))+((cj4*new_r20*sj3)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x319))+IKsqr((x319*(x321.value)*((((new_r00*sj4))+((cj4*new_r20*sj3))))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2((new_r20*x319), (x319*(x321.value)*((((new_r00*sj4))+((cj4*new_r20*sj3)))))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[12]; +IkReal x322=IKsin(j5); +IkReal x323=IKcos(j5); +IkReal x324=(cj4*sj3); +IkReal x325=(cj3*new_r10); +IkReal x326=((1.0)*new_r01); +IkReal x327=(cj3*new_r11); +IkReal x328=((1.0)*new_r00); +IkReal x329=((1.0)*x323); +IkReal x330=(cj4*x322); +IkReal x331=((1.0)*x322); +evalcond[0]=((((-1.0)*sj4*x331))+new_r20); +evalcond[1]=(new_r21+(((-1.0)*sj4*x329))); +evalcond[2]=(((new_r11*sj3))+x322+((cj3*new_r01))); +evalcond[3]=(((new_r10*sj3))+(((-1.0)*x329))+((cj3*new_r00))); +evalcond[4]=(((x323*x324))+new_r01+((cj3*x322))); +evalcond[5]=(((x322*x324))+(((-1.0)*cj3*x329))+new_r00); +evalcond[6]=(((sj3*x322))+new_r11+(((-1.0)*cj3*cj4*x329))); +evalcond[7]=(x325+(((-1.0)*x330))+(((-1.0)*sj3*x328))); +evalcond[8]=(x327+(((-1.0)*cj4*x329))+(((-1.0)*sj3*x326))); +evalcond[9]=((((-1.0)*cj3*x330))+new_r10+(((-1.0)*sj3*x329))); +evalcond[10]=(((new_r20*sj4))+((cj4*x325))+(((-1.0)*x331))+(((-1.0)*x324*x328))); +evalcond[11]=((((-1.0)*x329))+((cj4*x327))+((new_r21*sj4))+(((-1.0)*x324*x326))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x332=IKPowWithIntegerCheck(IKsign(sj4),-1); +if(!x332.valid){ +continue; +} +CheckValue x333 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); +if(!x333.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x332.value)))+(x333.value)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[12]; +IkReal x334=IKsin(j5); +IkReal x335=IKcos(j5); +IkReal x336=(cj4*sj3); +IkReal x337=(cj3*new_r10); +IkReal x338=((1.0)*new_r01); +IkReal x339=(cj3*new_r11); +IkReal x340=((1.0)*new_r00); +IkReal x341=((1.0)*x335); +IkReal x342=(cj4*x334); +IkReal x343=((1.0)*x334); +evalcond[0]=((((-1.0)*sj4*x343))+new_r20); +evalcond[1]=((((-1.0)*sj4*x341))+new_r21); +evalcond[2]=(((new_r11*sj3))+x334+((cj3*new_r01))); +evalcond[3]=(((new_r10*sj3))+((cj3*new_r00))+(((-1.0)*x341))); +evalcond[4]=(((x335*x336))+((cj3*x334))+new_r01); +evalcond[5]=((((-1.0)*cj3*x341))+((x334*x336))+new_r00); +evalcond[6]=(((sj3*x334))+(((-1.0)*cj3*cj4*x341))+new_r11); +evalcond[7]=(x337+(((-1.0)*sj3*x340))+(((-1.0)*x342))); +evalcond[8]=((((-1.0)*sj3*x338))+(((-1.0)*cj4*x341))+x339); +evalcond[9]=((((-1.0)*cj3*x342))+new_r10+(((-1.0)*sj3*x341))); +evalcond[10]=(((new_r20*sj4))+(((-1.0)*x336*x340))+((cj4*x337))+(((-1.0)*x343))); +evalcond[11]=(((cj4*x339))+((new_r21*sj4))+(((-1.0)*x341))+(((-1.0)*x336*x338))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x344=IKPowWithIntegerCheck(IKsign(sj4),-1); +if(!x344.valid){ +continue; +} +CheckValue x345 = IKatan2WithCheck(IkReal(new_r02),IkReal(((-1.0)*new_r12)),IKFAST_ATAN2_MAGTHRESH); +if(!x345.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x344.value)))+(x345.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x346=IKsin(j3); +IkReal x347=IKcos(j3); +IkReal x348=((1.0)*cj4); +IkReal x349=((1.0)*sj4); +IkReal x350=(new_r02*x346); +IkReal x351=(new_r12*x347); +IkReal x352=(sj4*x347); +evalcond[0]=(x352+new_r12); +evalcond[1]=((((-1.0)*x346*x349))+new_r02); +evalcond[2]=(((new_r02*x347))+((new_r12*x346))); +evalcond[3]=(sj4+(((-1.0)*x350))+x351); +evalcond[4]=((((-1.0)*x348*x350))+((cj4*x351))+((new_r22*sj4))); +evalcond[5]=((((-1.0)*new_r00*x346*x349))+(((-1.0)*new_r20*x348))+((new_r10*x352))); +evalcond[6]=((((-1.0)*new_r01*x346*x349))+(((-1.0)*new_r21*x348))+((new_r11*x352))); +evalcond[7]=((1.0)+((sj4*x351))+(((-1.0)*x349*x350))+(((-1.0)*new_r22*x348))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +IkReal j5eval[3]; +j5eval[0]=sj4; +j5eval[1]=IKsign(sj4); +j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[2]; +j5eval[0]=sj4; +j5eval[1]=cj3; +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[3]; +j5eval[0]=sj4; +j5eval[1]=cj4; +j5eval[2]=sj3; +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[5]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +IkReal x353=((1.0)*new_r01); +if( IKabs(((((-1.0)*cj3*x353))+(((-1.0)*new_r00*sj3)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj3*new_r00))+(((-1.0)*sj3*x353)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*cj3*x353))+(((-1.0)*new_r00*sj3))))+IKsqr((((cj3*new_r00))+(((-1.0)*sj3*x353))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*cj3*x353))+(((-1.0)*new_r00*sj3))), (((cj3*new_r00))+(((-1.0)*sj3*x353)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x354=IKsin(j5); +IkReal x355=IKcos(j5); +IkReal x356=((1.0)*sj3); +IkReal x357=(sj3*x354); +IkReal x358=((1.0)*x355); +IkReal x359=((1.0)*x354); +IkReal x360=(cj3*x358); +evalcond[0]=(((new_r11*sj3))+x354+((cj3*new_r01))); +evalcond[1]=(((new_r10*sj3))+(((-1.0)*x358))+((cj3*new_r00))); +evalcond[2]=(((cj3*x354))+((sj3*x355))+new_r01); +evalcond[3]=((((-1.0)*x360))+x357+new_r00); +evalcond[4]=((((-1.0)*x360))+x357+new_r11); +evalcond[5]=((((-1.0)*x359))+((cj3*new_r10))+(((-1.0)*new_r00*x356))); +evalcond[6]=((((-1.0)*x358))+(((-1.0)*new_r01*x356))+((cj3*new_r11))); +evalcond[7]=((((-1.0)*cj3*x359))+new_r10+(((-1.0)*x355*x356))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +IkReal x361=((1.0)*cj3); +if( IKabs(((((-1.0)*new_r11*sj3))+(((-1.0)*new_r01*x361)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((new_r01*sj3))+(((-1.0)*new_r11*x361)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r11*sj3))+(((-1.0)*new_r01*x361))))+IKsqr((((new_r01*sj3))+(((-1.0)*new_r11*x361))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((((-1.0)*new_r11*sj3))+(((-1.0)*new_r01*x361))), (((new_r01*sj3))+(((-1.0)*new_r11*x361)))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x362=IKsin(j5); +IkReal x363=IKcos(j5); +IkReal x364=((1.0)*sj3); +IkReal x365=(cj3*x362); +IkReal x366=((1.0)*x363); +IkReal x367=(x363*x364); +evalcond[0]=(((new_r11*sj3))+x362+((cj3*new_r01))); +evalcond[1]=((((-1.0)*new_r00*x364))+x362+((cj3*new_r10))); +evalcond[2]=(x363+((cj3*new_r11))+(((-1.0)*new_r01*x364))); +evalcond[3]=(((new_r10*sj3))+(((-1.0)*x366))+((cj3*new_r00))); +evalcond[4]=(((sj3*x362))+new_r11+((cj3*x363))); +evalcond[5]=((((-1.0)*x367))+x365+new_r01); +evalcond[6]=((((-1.0)*x367))+x365+new_r10); +evalcond[7]=((((-1.0)*x362*x364))+new_r00+(((-1.0)*cj3*x366))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r20, new_r21); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x368=IKsin(j5); +IkReal x369=IKcos(j5); +IkReal x370=((1.0)*x369); +IkReal x371=((1.0)*x368); +evalcond[0]=((((-1.0)*x371))+new_r20); +evalcond[1]=((((-1.0)*x370))+new_r21); +evalcond[2]=(((sj3*x368))+new_r11); +evalcond[3]=((((-1.0)*new_r12*x371))+new_r01); +evalcond[4]=((((-1.0)*cj3*x370))+new_r00); +evalcond[5]=((((-1.0)*sj3*x370))+new_r10); +evalcond[6]=(((new_r11*sj3))+x368+((cj3*new_r01))); +evalcond[7]=(((new_r10*sj3))+(((-1.0)*x370))+((cj3*new_r00))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(((-1.0)*new_r20)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20))+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x372=IKsin(j5); +IkReal x373=IKcos(j5); +IkReal x374=((1.0)*x373); +evalcond[0]=(x372+new_r20); +evalcond[1]=(x373+new_r21); +evalcond[2]=(((new_r12*x372))+new_r01); +evalcond[3]=(((sj3*x372))+new_r11); +evalcond[4]=((((-1.0)*cj3*x374))+new_r00); +evalcond[5]=((((-1.0)*sj3*x374))+new_r10); +evalcond[6]=(((new_r11*sj3))+x372+((cj3*new_r01))); +evalcond[7]=(((new_r10*sj3))+(((-1.0)*x374))+((cj3*new_r00))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j3))), 6.28318530717959))); +evalcond[1]=new_r02; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(new_r00)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r01), new_r00); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x375=IKsin(j5); +IkReal x376=IKcos(j5); +IkReal x377=((1.0)*cj4); +IkReal x378=((1.0)*x376); +IkReal x379=((1.0)*x375); +evalcond[0]=(x375+new_r01); +evalcond[1]=((((-1.0)*x378))+new_r00); +evalcond[2]=((((-1.0)*sj4*x379))+new_r20); +evalcond[3]=((((-1.0)*sj4*x378))+new_r21); +evalcond[4]=((((-1.0)*x376*x377))+new_r11); +evalcond[5]=(new_r10+(((-1.0)*x375*x377))); +evalcond[6]=(((new_r20*sj4))+((cj4*new_r10))+(((-1.0)*x379))); +evalcond[7]=(((cj4*new_r11))+(((-1.0)*x378))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j3)))), 6.28318530717959))); +evalcond[1]=new_r02; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(((-1.0)*new_r00))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r01, ((-1.0)*new_r00)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x380=IKsin(j5); +IkReal x381=IKcos(j5); +IkReal x382=((1.0)*cj4); +IkReal x383=((1.0)*x381); +IkReal x384=((1.0)*x380); +evalcond[0]=(x380+(((-1.0)*new_r01))); +evalcond[1]=(new_r11+((cj4*x381))); +evalcond[2]=((((-1.0)*sj4*x384))+new_r20); +evalcond[3]=((((-1.0)*sj4*x383))+new_r21); +evalcond[4]=((((-1.0)*x383))+(((-1.0)*new_r00))); +evalcond[5]=((((-1.0)*x380*x382))+(((-1.0)*new_r10))); +evalcond[6]=((((-1.0)*new_r10*x382))+((new_r20*sj4))+(((-1.0)*x384))); +evalcond[7]=((((-1.0)*new_r11*x382))+(((-1.0)*x383))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959))); +evalcond[1]=new_r12; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r11), new_r10); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x385=IKcos(j5); +IkReal x386=IKsin(j5); +IkReal x387=((1.0)*cj4); +IkReal x388=((1.0)*x385); +IkReal x389=((1.0)*x386); +evalcond[0]=(x386+new_r11); +evalcond[1]=((((-1.0)*x388))+new_r10); +evalcond[2]=(new_r01+((cj4*x385))); +evalcond[3]=(new_r00+((cj4*x386))); +evalcond[4]=((((-1.0)*new_r02*x389))+new_r20); +evalcond[5]=((((-1.0)*new_r02*x388))+new_r21); +evalcond[6]=(((new_r20*sj4))+(((-1.0)*new_r00*x387))+(((-1.0)*x389))); +evalcond[7]=((((-1.0)*new_r01*x387))+(((-1.0)*x388))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959))); +evalcond[1]=new_r12; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[3]; +sj3=-1.0; +cj3=0; +j3=-1.5707963267949; +j5eval[0]=new_r02; +j5eval[1]=IKsign(new_r02); +j5eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[1]; +sj3=-1.0; +cj3=0; +j3=-1.5707963267949; +j5eval[0]=new_r02; +if( IKabs(j5eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j5eval[2]; +sj3=-1.0; +cj3=0; +j3=-1.5707963267949; +j5eval[0]=new_r02; +j5eval[1]=cj4; +if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[4]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +evalcond[2]=new_r01; +evalcond[3]=new_r00; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r20, new_r21); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[4]; +IkReal x390=IKsin(j5); +IkReal x391=((1.0)*(IKcos(j5))); +evalcond[0]=((((-1.0)*x390))+new_r20); +evalcond[1]=((((-1.0)*x391))+new_r21); +evalcond[2]=(x390+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x391))+(((-1.0)*new_r10))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); +evalcond[1]=new_r22; +evalcond[2]=new_r01; +evalcond[3]=new_r00; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r21)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[4]; +IkReal x392=IKsin(j5); +IkReal x393=IKcos(j5); +evalcond[0]=(x392+new_r20); +evalcond[1]=(x393+new_r21); +evalcond[2]=(x392+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x393))+(((-1.0)*new_r10))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=IKabs(new_r02); +evalcond[1]=new_r20; +evalcond[2]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[6]; +IkReal x394=IKsin(j5); +IkReal x395=IKcos(j5); +IkReal x396=((1.0)*cj4); +IkReal x397=((1.0)*x395); +evalcond[0]=(x394+(((-1.0)*new_r11))); +evalcond[1]=((((-1.0)*x395*x396))+new_r01); +evalcond[2]=((((-1.0)*x394*x396))+new_r00); +evalcond[3]=((((-1.0)*x397))+(((-1.0)*new_r10))); +evalcond[4]=((((-1.0)*x394))+((cj4*new_r00))); +evalcond[5]=((((-1.0)*x397))+((cj4*new_r01))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[6]; +IkReal x398=IKcos(j5); +IkReal x399=IKsin(j5); +IkReal x400=((-1.0)*x399); +IkReal x401=((-1.0)*x398); +evalcond[0]=x400; +evalcond[1]=x401; +evalcond[2]=(new_r22*x401); +evalcond[3]=(new_r22*x400); +evalcond[4]=(x399+(((-1.0)*new_r11))); +evalcond[5]=((((-1.0)*x398))+(((-1.0)*new_r10))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j5] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x402=IKPowWithIntegerCheck(new_r02,-1); +if(!x402.valid){ +continue; +} +CheckValue x403=IKPowWithIntegerCheck(cj4,-1); +if(!x403.valid){ +continue; +} +if( IKabs(((-1.0)*new_r20*(x402.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x403.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20*(x402.value)))+IKsqr((new_r01*(x403.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(((-1.0)*new_r20*(x402.value)), (new_r01*(x403.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x404=IKsin(j5); +IkReal x405=IKcos(j5); +IkReal x406=((1.0)*cj4); +IkReal x407=((1.0)*x405); +evalcond[0]=(new_r20+((new_r02*x404))); +evalcond[1]=(new_r21+((new_r02*x405))); +evalcond[2]=(x404+(((-1.0)*new_r11))); +evalcond[3]=(new_r01+(((-1.0)*x405*x406))); +evalcond[4]=((((-1.0)*x404*x406))+new_r00); +evalcond[5]=((((-1.0)*new_r10))+(((-1.0)*x407))); +evalcond[6]=(((new_r20*sj4))+((cj4*new_r00))+(((-1.0)*x404))); +evalcond[7]=(((cj4*new_r01))+((new_r21*sj4))+(((-1.0)*x407))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x408=IKPowWithIntegerCheck(new_r02,-1); +if(!x408.valid){ +continue; +} +if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21*(x408.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r21*(x408.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2(new_r11, ((-1.0)*new_r21*(x408.value))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x409=IKsin(j5); +IkReal x410=IKcos(j5); +IkReal x411=((1.0)*cj4); +IkReal x412=((1.0)*x410); +evalcond[0]=(new_r20+((new_r02*x409))); +evalcond[1]=(new_r21+((new_r02*x410))); +evalcond[2]=(x409+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x410*x411))+new_r01); +evalcond[4]=(new_r00+(((-1.0)*x409*x411))); +evalcond[5]=((((-1.0)*new_r10))+(((-1.0)*x412))); +evalcond[6]=(((new_r20*sj4))+((cj4*new_r00))+(((-1.0)*x409))); +evalcond[7]=(((cj4*new_r01))+((new_r21*sj4))+(((-1.0)*x412))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x413=IKPowWithIntegerCheck(IKsign(new_r02),-1); +if(!x413.valid){ +continue; +} +CheckValue x414 = IKatan2WithCheck(IkReal(((-1.0)*new_r20)),IkReal(((-1.0)*new_r21)),IKFAST_ATAN2_MAGTHRESH); +if(!x414.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x413.value)))+(x414.value)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[8]; +IkReal x415=IKsin(j5); +IkReal x416=IKcos(j5); +IkReal x417=((1.0)*cj4); +IkReal x418=((1.0)*x416); +evalcond[0]=(new_r20+((new_r02*x415))); +evalcond[1]=(new_r21+((new_r02*x416))); +evalcond[2]=(x415+(((-1.0)*new_r11))); +evalcond[3]=((((-1.0)*x416*x417))+new_r01); +evalcond[4]=((((-1.0)*x415*x417))+new_r00); +evalcond[5]=((((-1.0)*new_r10))+(((-1.0)*x418))); +evalcond[6]=(((new_r20*sj4))+((cj4*new_r00))+(((-1.0)*x415))); +evalcond[7]=(((cj4*new_r01))+((new_r21*sj4))+(((-1.0)*x418))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j5eval[1]; +new_r21=0; +new_r20=0; +new_r02=0; +new_r12=0; +j5eval[0]=1.0; +if( IKabs(j5eval[0]) < 0.0000000100000000 ) +{ +continue; // no branches [j5] + +} else +{ +IkReal op[2+1], zeror[2]; +int numroots; +op[0]=1.0; +op[1]=0; +op[2]=-1.0; +polyroots2(op,zeror,numroots); +IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1]; +int numsolutions = 0; +for(int ij5 = 0; ij5 < numroots; ++ij5) +{ +IkReal htj5 = zeror[ij5]; +tempj5array[0]=((2.0)*(atan(htj5))); +for(int kj5 = 0; kj5 < 1; ++kj5) +{ +j5array[numsolutions] = tempj5array[kj5]; +if( j5array[numsolutions] > IKPI ) +{ + j5array[numsolutions]-=IK2PI; +} +else if( j5array[numsolutions] < -IKPI ) +{ + j5array[numsolutions]+=IK2PI; +} +sj5array[numsolutions] = IKsin(j5array[numsolutions]); +cj5array[numsolutions] = IKcos(j5array[numsolutions]); +numsolutions++; +} +} +bool j5valid[2]={true,true}; +_nj5 = 2; +for(int ij5 = 0; ij5 < numsolutions; ++ij5) + { +if( !j5valid[ij5] ) +{ + continue; +} + j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +htj5 = IKtan(j5/2); + +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} + } + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j5] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} +} +} +} +} +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x420=IKPowWithIntegerCheck(sj4,-1); +if(!x420.valid){ +continue; +} +IkReal x419=x420.value; +CheckValue x421=IKPowWithIntegerCheck(cj4,-1); +if(!x421.valid){ +continue; +} +CheckValue x422=IKPowWithIntegerCheck(sj3,-1); +if(!x422.valid){ +continue; +} +if( IKabs((new_r20*x419)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x419*(x421.value)*(x422.value)*(((((-1.0)*new_r01*sj4))+(((-1.0)*cj3*new_r20)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x419))+IKsqr((x419*(x421.value)*(x422.value)*(((((-1.0)*new_r01*sj4))+(((-1.0)*cj3*new_r20))))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2((new_r20*x419), (x419*(x421.value)*(x422.value)*(((((-1.0)*new_r01*sj4))+(((-1.0)*cj3*new_r20)))))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[12]; +IkReal x423=IKsin(j5); +IkReal x424=IKcos(j5); +IkReal x425=(cj4*sj3); +IkReal x426=(cj3*new_r10); +IkReal x427=((1.0)*new_r01); +IkReal x428=(cj3*new_r11); +IkReal x429=((1.0)*new_r00); +IkReal x430=((1.0)*x424); +IkReal x431=(cj4*x423); +IkReal x432=((1.0)*x423); +evalcond[0]=(new_r20+(((-1.0)*sj4*x432))); +evalcond[1]=(new_r21+(((-1.0)*sj4*x430))); +evalcond[2]=(((new_r11*sj3))+x423+((cj3*new_r01))); +evalcond[3]=((((-1.0)*x430))+((new_r10*sj3))+((cj3*new_r00))); +evalcond[4]=(((x424*x425))+((cj3*x423))+new_r01); +evalcond[5]=((((-1.0)*cj3*x430))+((x423*x425))+new_r00); +evalcond[6]=((((-1.0)*cj3*cj4*x430))+((sj3*x423))+new_r11); +evalcond[7]=((((-1.0)*sj3*x429))+(((-1.0)*x431))+x426); +evalcond[8]=((((-1.0)*sj3*x427))+(((-1.0)*cj4*x430))+x428); +evalcond[9]=((((-1.0)*sj3*x430))+(((-1.0)*cj3*x431))+new_r10); +evalcond[10]=((((-1.0)*x432))+((new_r20*sj4))+((cj4*x426))+(((-1.0)*x425*x429))); +evalcond[11]=((((-1.0)*x430))+((cj4*x428))+(((-1.0)*x425*x427))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x434=IKPowWithIntegerCheck(sj4,-1); +if(!x434.valid){ +continue; +} +IkReal x433=x434.value; +CheckValue x435=IKPowWithIntegerCheck(cj3,-1); +if(!x435.valid){ +continue; +} +if( IKabs((new_r20*x433)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x433*(x435.value)*((((new_r00*sj4))+((cj4*new_r20*sj3)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x433))+IKsqr((x433*(x435.value)*((((new_r00*sj4))+((cj4*new_r20*sj3))))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j5array[0]=IKatan2((new_r20*x433), (x433*(x435.value)*((((new_r00*sj4))+((cj4*new_r20*sj3)))))); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[12]; +IkReal x436=IKsin(j5); +IkReal x437=IKcos(j5); +IkReal x438=(cj4*sj3); +IkReal x439=(cj3*new_r10); +IkReal x440=((1.0)*new_r01); +IkReal x441=(cj3*new_r11); +IkReal x442=((1.0)*new_r00); +IkReal x443=((1.0)*x437); +IkReal x444=(cj4*x436); +IkReal x445=((1.0)*x436); +evalcond[0]=((((-1.0)*sj4*x445))+new_r20); +evalcond[1]=((((-1.0)*sj4*x443))+new_r21); +evalcond[2]=(((new_r11*sj3))+x436+((cj3*new_r01))); +evalcond[3]=((((-1.0)*x443))+((new_r10*sj3))+((cj3*new_r00))); +evalcond[4]=(((cj3*x436))+new_r01+((x437*x438))); +evalcond[5]=(((x436*x438))+(((-1.0)*cj3*x443))+new_r00); +evalcond[6]=(((sj3*x436))+(((-1.0)*cj3*cj4*x443))+new_r11); +evalcond[7]=((((-1.0)*sj3*x442))+(((-1.0)*x444))+x439); +evalcond[8]=((((-1.0)*sj3*x440))+(((-1.0)*cj4*x443))+x441); +evalcond[9]=((((-1.0)*sj3*x443))+(((-1.0)*cj3*x444))+new_r10); +evalcond[10]=((((-1.0)*x445))+(((-1.0)*x438*x442))+((new_r20*sj4))+((cj4*x439))); +evalcond[11]=((((-1.0)*x443))+(((-1.0)*x438*x440))+((cj4*x441))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x446=IKPowWithIntegerCheck(IKsign(sj4),-1); +if(!x446.valid){ +continue; +} +CheckValue x447 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); +if(!x447.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x446.value)))+(x447.value)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[12]; +IkReal x448=IKsin(j5); +IkReal x449=IKcos(j5); +IkReal x450=(cj4*sj3); +IkReal x451=(cj3*new_r10); +IkReal x452=((1.0)*new_r01); +IkReal x453=(cj3*new_r11); +IkReal x454=((1.0)*new_r00); +IkReal x455=((1.0)*x449); +IkReal x456=(cj4*x448); +IkReal x457=((1.0)*x448); +evalcond[0]=((((-1.0)*sj4*x457))+new_r20); +evalcond[1]=((((-1.0)*sj4*x455))+new_r21); +evalcond[2]=(((new_r11*sj3))+x448+((cj3*new_r01))); +evalcond[3]=(((new_r10*sj3))+(((-1.0)*x455))+((cj3*new_r00))); +evalcond[4]=(((x449*x450))+((cj3*x448))+new_r01); +evalcond[5]=(((x448*x450))+new_r00+(((-1.0)*cj3*x455))); +evalcond[6]=((((-1.0)*cj3*cj4*x455))+((sj3*x448))+new_r11); +evalcond[7]=((((-1.0)*x456))+(((-1.0)*sj3*x454))+x451); +evalcond[8]=((((-1.0)*cj4*x455))+(((-1.0)*sj3*x452))+x453); +evalcond[9]=((((-1.0)*sj3*x455))+new_r10+(((-1.0)*cj3*x456))); +evalcond[10]=(((new_r20*sj4))+((cj4*x451))+(((-1.0)*x457))+(((-1.0)*x450*x454))); +evalcond[11]=(((cj4*x453))+(((-1.0)*x455))+(((-1.0)*x450*x452))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} +} +} + +} + +} + +} else +{ +{ +IkReal j5array[1], cj5array[1], sj5array[1]; +bool j5valid[1]={false}; +_nj5 = 1; +CheckValue x458=IKPowWithIntegerCheck(IKsign(sj4),-1); +if(!x458.valid){ +continue; +} +CheckValue x459 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); +if(!x459.valid){ +continue; +} +j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x458.value)))+(x459.value)); +sj5array[0]=IKsin(j5array[0]); +cj5array[0]=IKcos(j5array[0]); +if( j5array[0] > IKPI ) +{ + j5array[0]-=IK2PI; +} +else if( j5array[0] < -IKPI ) +{ j5array[0]+=IK2PI; +} +j5valid[0] = true; +for(int ij5 = 0; ij5 < 1; ++ij5) +{ +if( !j5valid[ij5] ) +{ + continue; +} +_ij5[0] = ij5; _ij5[1] = -1; +for(int iij5 = ij5+1; iij5 < 1; ++iij5) +{ +if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) +{ + j5valid[iij5]=false; _ij5[1] = iij5; break; +} +} +j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; +{ +IkReal evalcond[2]; +IkReal x460=((1.0)*sj4); +evalcond[0]=((((-1.0)*x460*(IKsin(j5))))+new_r20); +evalcond[1]=((((-1.0)*x460*(IKcos(j5))))+new_r21); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +IkReal j3eval[3]; +j3eval[0]=sj4; +j3eval[1]=IKsign(sj4); +j3eval[2]=((IKabs(new_r12))+(IKabs(new_r02))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[2]; +j3eval[0]=new_r11; +j3eval[1]=sj4; +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[5]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x461=((1.0)*new_r01); +if( IKabs(((((-1.0)*cj5*x461))+(((-1.0)*new_r00*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*sj5*x461))+((cj5*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*cj5*x461))+(((-1.0)*new_r00*sj5))))+IKsqr(((((-1.0)*sj5*x461))+((cj5*new_r00))))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2(((((-1.0)*cj5*x461))+(((-1.0)*new_r00*sj5))), ((((-1.0)*sj5*x461))+((cj5*new_r00)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x462=IKcos(j3); +IkReal x463=IKsin(j3); +IkReal x464=((1.0)*cj5); +IkReal x465=(sj5*x463); +IkReal x466=(sj5*x462); +IkReal x467=((1.0)*x463); +IkReal x468=(x462*x464); +evalcond[0]=(((new_r11*x463))+sj5+((new_r01*x462))); +evalcond[1]=(((cj5*x463))+x466+new_r01); +evalcond[2]=((((-1.0)*x468))+x465+new_r00); +evalcond[3]=((((-1.0)*x468))+x465+new_r11); +evalcond[4]=(((new_r10*x463))+((new_r00*x462))+(((-1.0)*x464))); +evalcond[5]=((((-1.0)*x463*x464))+(((-1.0)*x466))+new_r10); +evalcond[6]=((((-1.0)*sj5))+((new_r10*x462))+(((-1.0)*new_r00*x467))); +evalcond[7]=(((new_r11*x462))+(((-1.0)*new_r01*x467))+(((-1.0)*x464))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959))); +evalcond[1]=new_r12; +evalcond[2]=new_r02; +evalcond[3]=new_r20; +evalcond[4]=new_r21; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[3]; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +IkReal x469=(((new_r11*sj5))+((cj5*new_r01))); +j3eval[0]=x469; +j3eval[1]=IKsign(x469); +j3eval[2]=((IKabs(((((-1.0)*cj5*sj5))+(((-1.0)*new_r01*new_r11)))))+(IKabs(((-1.0)+(new_r01*new_r01)+(cj5*cj5))))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[3]; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +IkReal x470=((1.0)*sj5); +IkReal x471=(((new_r10*new_r11))+((new_r00*new_r01))); +j3eval[0]=x471; +j3eval[1]=IKsign(x471); +j3eval[2]=((IKabs(((((-1.0)*new_r00*x470))+(((-1.0)*new_r11*x470)))))+(IKabs((((new_r01*sj5))+(((-1.0)*new_r10*x470)))))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[3]; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +IkReal x472=((1.0)*sj5); +IkReal x473=((new_r01*new_r01)+(new_r11*new_r11)); +j3eval[0]=x473; +j3eval[1]=((IKabs((((cj5*new_r01))+(((-1.0)*new_r11*x472)))))+(IKabs(((((-1.0)*new_r01*x472))+(((-1.0)*cj5*new_r11)))))); +j3eval[2]=IKsign(x473); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[1]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((new_r01*new_r01)+(new_r11*new_r11)); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +new_r01=0; +new_r11=0; +j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +continue; // 3 cases reached + +} else +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x475 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); +if(!x475.valid){ +continue; +} +IkReal x474=x475.value; +j3array[0]=((-1.0)*x474); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=((3.14159265358979)+(((-1.0)*x474))); +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[1]; +evalcond[0]=((((-1.0)*new_r00*(IKsin(j3))))+((new_r10*(IKcos(j3))))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j5))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2(new_r01, ((-1.0)*new_r11)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x476=IKcos(j3); +IkReal x477=IKsin(j3); +IkReal x478=((1.0)*x477); +evalcond[0]=(x476+new_r11); +evalcond[1]=((((-1.0)*x478))+new_r01); +evalcond[2]=((((-1.0)*x476))+new_r00); +evalcond[3]=((((-1.0)*x478))+new_r10); +evalcond[4]=(((new_r01*x476))+((new_r11*x477))); +evalcond[5]=((-1.0)+((new_r10*x477))+((new_r00*x476))); +evalcond[6]=(((new_r10*x476))+(((-1.0)*new_r00*x478))); +evalcond[7]=((1.0)+((new_r11*x476))+(((-1.0)*new_r01*x478))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j5)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(((-1.0)*new_r00))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2(((-1.0)*new_r01), ((-1.0)*new_r00)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x479=IKsin(j3); +IkReal x480=IKcos(j3); +IkReal x481=((1.0)*x479); +evalcond[0]=(x479+new_r01); +evalcond[1]=(x480+new_r00); +evalcond[2]=(x479+new_r10); +evalcond[3]=((((-1.0)*x480))+new_r11); +evalcond[4]=(((new_r11*x479))+((new_r01*x480))); +evalcond[5]=((1.0)+((new_r10*x479))+((new_r00*x480))); +evalcond[6]=((((-1.0)*new_r00*x481))+((new_r10*x480))); +evalcond[7]=((-1.0)+(((-1.0)*new_r01*x481))+((new_r11*x480))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +IkReal x483 = ((new_r01*new_r01)+(new_r11*new_r11)); +if(IKabs(x483)==0){ +continue; +} +IkReal x482=pow(x483,-0.5); +CheckValue x484 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x484.valid){ +continue; +} +IkReal gconst6=((-1.0)*(x484.value)); +IkReal gconst7=((-1.0)*new_r01*x482); +IkReal gconst8=(new_r11*x482); +CheckValue x485 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x485.valid){ +continue; +} +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x485.value)+j5)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[3]; +CheckValue x488 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x488.valid){ +continue; +} +IkReal x486=((-1.0)*(x488.value)); +IkReal x487=x482; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x486; +IkReal gconst6=x486; +IkReal gconst7=((-1.0)*new_r01*x487); +IkReal gconst8=(new_r11*x487); +IkReal x489=new_r01*new_r01; +IkReal x490=(new_r00*new_r01); +IkReal x491=(((new_r10*new_r11))+x490); +IkReal x492=x482; +IkReal x493=(new_r01*x492); +j3eval[0]=x491; +j3eval[1]=IKsign(x491); +j3eval[2]=((IKabs(((((-1.0)*x489*x492))+((new_r10*x493)))))+(IKabs((((x490*x492))+((new_r11*x493)))))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[2]; +CheckValue x496 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x496.valid){ +continue; +} +IkReal x494=((-1.0)*(x496.value)); +IkReal x495=x482; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x494; +IkReal gconst6=x494; +IkReal gconst7=((-1.0)*new_r01*x495); +IkReal gconst8=(new_r11*x495); +IkReal x497=((new_r01*new_r01)+(new_r11*new_r11)); +j3eval[0]=x497; +j3eval[1]=IKsign(x497); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x500 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x500.valid){ +continue; +} +IkReal x498=((-1.0)*(x500.value)); +IkReal x499=x482; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x498; +IkReal gconst6=x498; +IkReal gconst7=((-1.0)*new_r01*x499); +IkReal gconst8=(new_r11*x499); +j3eval[0]=((new_r01*new_r01)+(new_r11*new_r11)); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[5]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((gconst7*gconst7)+(gconst8*gconst8)); +evalcond[1]=new_r01; +evalcond[2]=new_r00; +evalcond[3]=new_r11; +evalcond[4]=new_r10; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[4], cj3array[4], sj3array[4]; +bool j3valid[4]={false}; +_nj3 = 4; +j3array[0]=0; +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=1.5707963267949; +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +j3array[2]=3.14159265358979; +sj3array[2]=IKsin(j3array[2]); +cj3array[2]=IKcos(j3array[2]); +j3array[3]=-1.5707963267949; +sj3array[3]=IKsin(j3array[3]); +cj3array[3]=IKcos(j3array[3]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +if( j3array[2] > IKPI ) +{ + j3array[2]-=IK2PI; +} +else if( j3array[2] < -IKPI ) +{ j3array[2]+=IK2PI; +} +j3valid[2] = true; +if( j3array[3] > IKPI ) +{ + j3array[3]-=IK2PI; +} +else if( j3array[3] < -IKPI ) +{ j3array[3]+=IK2PI; +} +j3valid[3] = true; +for(int ij3 = 0; ij3 < 4; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 4; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +CheckValue x502 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); +if(!x502.valid){ +continue; +} +IkReal x501=((-1.0)*(x502.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x501; +new_r11=0; +new_r00=0; +IkReal gconst6=x501; +IkReal x503 = new_r01*new_r01; +if(IKabs(x503)==0){ +continue; +} +IkReal gconst7=((-1.0)*new_r01*(pow(x503,-0.5))); +IkReal gconst8=0; +j3eval[0]=new_r01; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x504=IKPowWithIntegerCheck(gconst7,-1); +if(!x504.valid){ +continue; +} +cj3array[0]=((-1.0)*new_r01*(x504.value)); +if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j3valid[0] = j3valid[1] = true; + j3array[0] = IKacos(cj3array[0]); + sj3array[0] = IKsin(j3array[0]); + cj3array[1] = cj3array[0]; + j3array[1] = -j3array[0]; + sj3array[1] = -sj3array[0]; +} +else if( isnan(cj3array[0]) ) +{ + // probably any value will work + j3valid[0] = true; + cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0; +} +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x505=IKsin(j3); +IkReal x506=IKcos(j3); +IkReal x507=((-1.0)*x505); +evalcond[0]=(new_r10*x505); +evalcond[1]=(gconst7*x507); +evalcond[2]=(new_r01*x507); +evalcond[3]=(gconst7+((new_r01*x506))); +evalcond[4]=(gconst7+((new_r10*x506))); +evalcond[5]=(((gconst7*x506))+new_r10); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} else +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x508=IKPowWithIntegerCheck(new_r01,-1); +if(!x508.valid){ +continue; +} +cj3array[0]=((-1.0)*gconst7*(x508.value)); +if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j3valid[0] = j3valid[1] = true; + j3array[0] = IKacos(cj3array[0]); + sj3array[0] = IKsin(j3array[0]); + cj3array[1] = cj3array[0]; + j3array[1] = -j3array[0]; + sj3array[1] = -sj3array[0]; +} +else if( isnan(cj3array[0]) ) +{ + // probably any value will work + j3valid[0] = true; + cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0; +} +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x509=IKsin(j3); +IkReal x510=IKcos(j3); +IkReal x511=(gconst7*x510); +IkReal x512=((-1.0)*x509); +evalcond[0]=(new_r10*x509); +evalcond[1]=(gconst7*x512); +evalcond[2]=(new_r01*x512); +evalcond[3]=(x511+new_r01); +evalcond[4]=(((new_r10*x510))+gconst7); +evalcond[5]=(x511+new_r10); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); +evalcond[1]=gconst7; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[3]; +CheckValue x514 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x514.valid){ +continue; +} +IkReal x513=((-1.0)*(x514.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x513; +new_r00=0; +new_r10=0; +new_r21=0; +new_r22=0; +IkReal gconst6=x513; +IkReal gconst7=((-1.0)*new_r01); +IkReal gconst8=new_r11; +j3eval[0]=-1.0; +j3eval[1]=-1.0; +j3eval[2]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[3]; +CheckValue x516 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x516.valid){ +continue; +} +IkReal x515=((-1.0)*(x516.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x515; +new_r00=0; +new_r10=0; +new_r21=0; +new_r22=0; +IkReal gconst6=x515; +IkReal gconst7=((-1.0)*new_r01); +IkReal gconst8=new_r11; +j3eval[0]=-1.0; +j3eval[1]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01))))))); +j3eval[2]=-1.0; +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[3]; +CheckValue x518 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x518.valid){ +continue; +} +IkReal x517=((-1.0)*(x518.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x517; +new_r00=0; +new_r10=0; +new_r21=0; +new_r22=0; +IkReal gconst6=x517; +IkReal gconst7=((-1.0)*new_r01); +IkReal gconst8=new_r11; +j3eval[0]=1.0; +j3eval[1]=((((0.5)*(IKabs(((-1.0)+(((2.0)*(new_r01*new_r01))))))))+(IKabs((new_r01*new_r11)))); +j3eval[2]=1.0; +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +continue; // 3 cases reached + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x519=((1.0)*new_r11); +CheckValue x520 = IKatan2WithCheck(IkReal((((gconst8*new_r01))+(((-1.0)*gconst7*x519)))),IkReal(((((-1.0)*gconst7*new_r01))+(((-1.0)*gconst8*x519)))),IKFAST_ATAN2_MAGTHRESH); +if(!x520.valid){ +continue; +} +CheckValue x521=IKPowWithIntegerCheck(IKsign(((new_r01*new_r01)+(new_r11*new_r11))),-1); +if(!x521.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x520.value)+(((1.5707963267949)*(x521.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x522=IKcos(j3); +IkReal x523=IKsin(j3); +IkReal x524=((1.0)*gconst8); +IkReal x525=(gconst7*x522); +IkReal x526=(gconst7*x523); +IkReal x527=(x523*x524); +evalcond[0]=(((new_r01*x522))+gconst7+((new_r11*x523))); +evalcond[1]=(x526+((gconst8*x522))+new_r11); +evalcond[2]=((((-1.0)*x527))+x525); +evalcond[3]=((((-1.0)*x527))+x525+new_r01); +evalcond[4]=((((-1.0)*x526))+(((-1.0)*x522*x524))); +evalcond[5]=(gconst8+((new_r11*x522))+(((-1.0)*new_r01*x523))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x528 = IKatan2WithCheck(IkReal((gconst7*new_r11)),IkReal((gconst8*new_r11)),IKFAST_ATAN2_MAGTHRESH); +if(!x528.valid){ +continue; +} +CheckValue x529=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst8*gconst8)))+(((-1.0)*(gconst7*gconst7))))),-1); +if(!x529.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x528.value)+(((1.5707963267949)*(x529.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x530=IKcos(j3); +IkReal x531=IKsin(j3); +IkReal x532=((1.0)*gconst8); +IkReal x533=(gconst7*x530); +IkReal x534=(gconst7*x531); +IkReal x535=(x531*x532); +evalcond[0]=(((new_r01*x530))+gconst7+((new_r11*x531))); +evalcond[1]=(x534+((gconst8*x530))+new_r11); +evalcond[2]=((((-1.0)*x535))+x533); +evalcond[3]=((((-1.0)*x535))+x533+new_r01); +evalcond[4]=((((-1.0)*x534))+(((-1.0)*x530*x532))); +evalcond[5]=(gconst8+((new_r11*x530))+(((-1.0)*new_r01*x531))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x536 = IKatan2WithCheck(IkReal((gconst7*gconst8)),IkReal(((-1.0)*(gconst7*gconst7))),IKFAST_ATAN2_MAGTHRESH); +if(!x536.valid){ +continue; +} +CheckValue x537=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst8*new_r11))+((gconst7*new_r01)))),-1); +if(!x537.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x536.value)+(((1.5707963267949)*(x537.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x538=IKcos(j3); +IkReal x539=IKsin(j3); +IkReal x540=((1.0)*gconst8); +IkReal x541=(gconst7*x538); +IkReal x542=(gconst7*x539); +IkReal x543=(x539*x540); +evalcond[0]=(((new_r01*x538))+gconst7+((new_r11*x539))); +evalcond[1]=(x542+((gconst8*x538))+new_r11); +evalcond[2]=((((-1.0)*x543))+x541); +evalcond[3]=((((-1.0)*x543))+x541+new_r01); +evalcond[4]=((((-1.0)*x542))+(((-1.0)*x538*x540))); +evalcond[5]=(gconst8+((new_r11*x538))+(((-1.0)*new_r01*x539))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x544=IKPowWithIntegerCheck(gconst8,-1); +if(!x544.valid){ +continue; +} +cj3array[0]=(new_r00*(x544.value)); +if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j3valid[0] = j3valid[1] = true; + j3array[0] = IKacos(cj3array[0]); + sj3array[0] = IKsin(j3array[0]); + cj3array[1] = cj3array[0]; + j3array[1] = -j3array[0]; + sj3array[1] = -sj3array[0]; +} +else if( isnan(cj3array[0]) ) +{ + // probably any value will work + j3valid[0] = true; + cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0; +} +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x545=IKsin(j3); +IkReal x546=IKcos(j3); +IkReal x547=((-1.0)*x545); +evalcond[0]=(new_r11*x545); +evalcond[1]=(gconst8*x547); +evalcond[2]=(new_r00*x547); +evalcond[3]=(((gconst8*x546))+new_r11); +evalcond[4]=(gconst8+((new_r11*x546))); +evalcond[5]=(((new_r00*x546))+(((-1.0)*gconst8))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +CheckValue x549 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x549.valid){ +continue; +} +IkReal x548=((-1.0)*(x549.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x548; +new_r00=0; +new_r01=0; +new_r12=0; +new_r22=0; +IkReal gconst6=x548; +IkReal gconst7=0; +IkReal x550 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); +if(IKabs(x550)==0){ +continue; +} +IkReal gconst8=(new_r11*(pow(x550,-0.5))); +j3eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x552 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x552.valid){ +continue; +} +IkReal x551=((-1.0)*(x552.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x551; +new_r00=0; +new_r01=0; +new_r12=0; +new_r22=0; +IkReal gconst6=x551; +IkReal gconst7=0; +IkReal x553 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); +if(IKabs(x553)==0){ +continue; +} +IkReal gconst8=(new_r11*(pow(x553,-0.5))); +j3eval[0]=new_r11; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x555 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x555.valid){ +continue; +} +IkReal x554=((-1.0)*(x555.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x554; +new_r00=0; +new_r01=0; +new_r12=0; +new_r22=0; +IkReal gconst6=x554; +IkReal gconst7=0; +IkReal x556 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); +if(IKabs(x556)==0){ +continue; +} +IkReal gconst8=(new_r11*(pow(x556,-0.5))); +j3eval[0]=new_r10; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +continue; // 3 cases reached + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x557=IKPowWithIntegerCheck(new_r10,-1); +if(!x557.valid){ +continue; +} +CheckValue x558=IKPowWithIntegerCheck(gconst8,-1); +if(!x558.valid){ +continue; +} +if( IKabs((gconst8*(x557.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11*(x558.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst8*(x557.value)))+IKsqr(((-1.0)*new_r11*(x558.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((gconst8*(x557.value)), ((-1.0)*new_r11*(x558.value))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x559=IKsin(j3); +IkReal x560=IKcos(j3); +IkReal x561=((1.0)*gconst8); +IkReal x562=((-1.0)*gconst8); +evalcond[0]=(new_r11*x559); +evalcond[1]=(new_r10*x560); +evalcond[2]=(x559*x562); +evalcond[3]=(x560*x562); +evalcond[4]=(((gconst8*x560))+new_r11); +evalcond[5]=(gconst8+((new_r11*x560))); +evalcond[6]=((((-1.0)*x559*x561))+new_r10); +evalcond[7]=(((new_r10*x559))+(((-1.0)*x561))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x563=IKPowWithIntegerCheck(gconst8,-1); +if(!x563.valid){ +continue; +} +CheckValue x564=IKPowWithIntegerCheck(new_r11,-1); +if(!x564.valid){ +continue; +} +if( IKabs((new_r10*(x563.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst8*(x564.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x563.value)))+IKsqr(((-1.0)*gconst8*(x564.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((new_r10*(x563.value)), ((-1.0)*gconst8*(x564.value))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x565=IKsin(j3); +IkReal x566=IKcos(j3); +IkReal x567=((1.0)*gconst8); +IkReal x568=((-1.0)*gconst8); +evalcond[0]=(new_r11*x565); +evalcond[1]=(new_r10*x566); +evalcond[2]=(x565*x568); +evalcond[3]=(x566*x568); +evalcond[4]=(((gconst8*x566))+new_r11); +evalcond[5]=(gconst8+((new_r11*x566))); +evalcond[6]=(new_r10+(((-1.0)*x565*x567))); +evalcond[7]=(((new_r10*x565))+(((-1.0)*x567))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x569 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); +if(!x569.valid){ +continue; +} +CheckValue x570=IKPowWithIntegerCheck(IKsign(gconst8),-1); +if(!x570.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x569.value)+(((1.5707963267949)*(x570.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x571=IKsin(j3); +IkReal x572=IKcos(j3); +IkReal x573=((1.0)*gconst8); +IkReal x574=((-1.0)*gconst8); +evalcond[0]=(new_r11*x571); +evalcond[1]=(new_r10*x572); +evalcond[2]=(x571*x574); +evalcond[3]=(x572*x574); +evalcond[4]=(((gconst8*x572))+new_r11); +evalcond[5]=(((new_r11*x572))+gconst8); +evalcond[6]=((((-1.0)*x571*x573))+new_r10); +evalcond[7]=(((new_r10*x571))+(((-1.0)*x573))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=IKabs(new_r01); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +CheckValue x576 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x576.valid){ +continue; +} +IkReal x575=((-1.0)*(x576.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x575; +new_r01=0; +IkReal gconst6=x575; +IkReal gconst7=0; +IkReal x577 = new_r11*new_r11; +if(IKabs(x577)==0){ +continue; +} +IkReal gconst8=(new_r11*(pow(x577,-0.5))); +j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x579 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x579.valid){ +continue; +} +IkReal x578=((-1.0)*(x579.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x578; +new_r01=0; +IkReal gconst6=x578; +IkReal gconst7=0; +IkReal x580 = new_r11*new_r11; +if(IKabs(x580)==0){ +continue; +} +IkReal gconst8=(new_r11*(pow(x580,-0.5))); +j3eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x582 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x582.valid){ +continue; +} +IkReal x581=((-1.0)*(x582.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst7; +cj5=gconst8; +j5=x581; +new_r01=0; +IkReal gconst6=x581; +IkReal gconst7=0; +IkReal x583 = new_r11*new_r11; +if(IKabs(x583)==0){ +continue; +} +IkReal gconst8=(new_r11*(pow(x583,-0.5))); +j3eval[0]=new_r11; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +continue; // 3 cases reached + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x584=IKPowWithIntegerCheck(gconst8,-1); +if(!x584.valid){ +continue; +} +CheckValue x585=IKPowWithIntegerCheck(new_r11,-1); +if(!x585.valid){ +continue; +} +if( IKabs((new_r10*(x584.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst8*(x585.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x584.value)))+IKsqr(((-1.0)*gconst8*(x585.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((new_r10*(x584.value)), ((-1.0)*gconst8*(x585.value))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x586=IKsin(j3); +IkReal x587=IKcos(j3); +IkReal x588=((1.0)*gconst8); +evalcond[0]=(new_r11*x586); +evalcond[1]=((-1.0)*gconst8*x586); +evalcond[2]=(((gconst8*x587))+new_r11); +evalcond[3]=(gconst8+((new_r11*x587))); +evalcond[4]=((((-1.0)*x587*x588))+new_r00); +evalcond[5]=((((-1.0)*x586*x588))+new_r10); +evalcond[6]=((((-1.0)*new_r00*x586))+((new_r10*x587))); +evalcond[7]=(((new_r00*x587))+(((-1.0)*x588))+((new_r10*x586))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x589 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); +if(!x589.valid){ +continue; +} +CheckValue x590=IKPowWithIntegerCheck(IKsign(gconst8),-1); +if(!x590.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x589.value)+(((1.5707963267949)*(x590.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x591=IKsin(j3); +IkReal x592=IKcos(j3); +IkReal x593=((1.0)*gconst8); +evalcond[0]=(new_r11*x591); +evalcond[1]=((-1.0)*gconst8*x591); +evalcond[2]=(((gconst8*x592))+new_r11); +evalcond[3]=(((new_r11*x592))+gconst8); +evalcond[4]=((((-1.0)*x592*x593))+new_r00); +evalcond[5]=(new_r10+(((-1.0)*x591*x593))); +evalcond[6]=(((new_r10*x592))+(((-1.0)*new_r00*x591))); +evalcond[7]=(((new_r10*x591))+((new_r00*x592))+(((-1.0)*x593))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x594=IKPowWithIntegerCheck(IKsign(gconst8),-1); +if(!x594.valid){ +continue; +} +CheckValue x595 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH); +if(!x595.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x594.value)))+(x595.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x596=IKsin(j3); +IkReal x597=IKcos(j3); +IkReal x598=((1.0)*gconst8); +evalcond[0]=(new_r11*x596); +evalcond[1]=((-1.0)*gconst8*x596); +evalcond[2]=(((gconst8*x597))+new_r11); +evalcond[3]=(((new_r11*x597))+gconst8); +evalcond[4]=((((-1.0)*x597*x598))+new_r00); +evalcond[5]=((((-1.0)*x596*x598))+new_r10); +evalcond[6]=(((new_r10*x597))+(((-1.0)*new_r00*x596))); +evalcond[7]=(((new_r10*x596))+((new_r00*x597))+(((-1.0)*x598))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j3] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} +} +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x599=((1.0)*new_r11); +CheckValue x600=IKPowWithIntegerCheck(IKsign(((gconst7*gconst7)+(gconst8*gconst8))),-1); +if(!x600.valid){ +continue; +} +CheckValue x601 = IKatan2WithCheck(IkReal((((gconst8*new_r01))+(((-1.0)*gconst7*x599)))),IkReal(((((-1.0)*gconst7*new_r01))+(((-1.0)*gconst8*x599)))),IKFAST_ATAN2_MAGTHRESH); +if(!x601.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x600.value)))+(x601.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x602=IKcos(j3); +IkReal x603=IKsin(j3); +IkReal x604=((1.0)*gconst8); +IkReal x605=(gconst7*x602); +IkReal x606=(gconst7*x603); +IkReal x607=((1.0)*x603); +IkReal x608=(x603*x604); +evalcond[0]=(gconst7+((new_r11*x603))+((new_r01*x602))); +evalcond[1]=(((gconst8*x602))+x606+new_r11); +evalcond[2]=(x605+(((-1.0)*x608))+new_r01); +evalcond[3]=(gconst7+((new_r10*x602))+(((-1.0)*new_r00*x607))); +evalcond[4]=(gconst8+((new_r11*x602))+(((-1.0)*new_r01*x607))); +evalcond[5]=(x605+(((-1.0)*x608))+new_r10); +evalcond[6]=(((new_r10*x603))+((new_r00*x602))+(((-1.0)*x604))); +evalcond[7]=((((-1.0)*x602*x604))+(((-1.0)*x606))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x609=((1.0)*new_r11); +CheckValue x610 = IKatan2WithCheck(IkReal((((gconst8*new_r01))+(((-1.0)*gconst7*x609)))),IkReal(((((-1.0)*gconst7*new_r01))+(((-1.0)*gconst8*x609)))),IKFAST_ATAN2_MAGTHRESH); +if(!x610.valid){ +continue; +} +CheckValue x611=IKPowWithIntegerCheck(IKsign(((new_r01*new_r01)+(new_r11*new_r11))),-1); +if(!x611.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x610.value)+(((1.5707963267949)*(x611.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x612=IKcos(j3); +IkReal x613=IKsin(j3); +IkReal x614=((1.0)*gconst8); +IkReal x615=(gconst7*x612); +IkReal x616=(gconst7*x613); +IkReal x617=((1.0)*x613); +IkReal x618=(x613*x614); +evalcond[0]=(gconst7+((new_r11*x613))+((new_r01*x612))); +evalcond[1]=(((gconst8*x612))+x616+new_r11); +evalcond[2]=((((-1.0)*x618))+x615+new_r01); +evalcond[3]=(gconst7+((new_r10*x612))+(((-1.0)*new_r00*x617))); +evalcond[4]=(gconst8+((new_r11*x612))+(((-1.0)*new_r01*x617))); +evalcond[5]=((((-1.0)*x618))+x615+new_r10); +evalcond[6]=(((new_r10*x613))+(((-1.0)*x614))+((new_r00*x612))); +evalcond[7]=((((-1.0)*x612*x614))+(((-1.0)*x616))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x619=((1.0)*gconst7); +CheckValue x620 = IKatan2WithCheck(IkReal(((((-1.0)*new_r10*x619))+((gconst7*new_r01)))),IkReal(((((-1.0)*new_r11*x619))+(((-1.0)*new_r00*x619)))),IKFAST_ATAN2_MAGTHRESH); +if(!x620.valid){ +continue; +} +CheckValue x621=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); +if(!x621.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x620.value)+(((1.5707963267949)*(x621.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x622=IKcos(j3); +IkReal x623=IKsin(j3); +IkReal x624=((1.0)*gconst8); +IkReal x625=(gconst7*x622); +IkReal x626=(gconst7*x623); +IkReal x627=((1.0)*x623); +IkReal x628=(x623*x624); +evalcond[0]=(gconst7+((new_r01*x622))+((new_r11*x623))); +evalcond[1]=(x626+((gconst8*x622))+new_r11); +evalcond[2]=((((-1.0)*x628))+x625+new_r01); +evalcond[3]=((((-1.0)*new_r00*x627))+gconst7+((new_r10*x622))); +evalcond[4]=((((-1.0)*new_r01*x627))+gconst8+((new_r11*x622))); +evalcond[5]=((((-1.0)*x628))+x625+new_r10); +evalcond[6]=((((-1.0)*x624))+((new_r00*x622))+((new_r10*x623))); +evalcond[7]=((((-1.0)*x622*x624))+(((-1.0)*x626))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +IkReal x630 = ((new_r01*new_r01)+(new_r11*new_r11)); +if(IKabs(x630)==0){ +continue; +} +IkReal x629=pow(x630,-0.5); +CheckValue x631 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x631.valid){ +continue; +} +IkReal gconst9=((3.14159265358979)+(((-1.0)*(x631.value)))); +IkReal gconst10=((1.0)*new_r01*x629); +IkReal gconst11=((-1.0)*new_r11*x629); +CheckValue x632 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x632.valid){ +continue; +} +evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x632.value)+j5)))), 6.28318530717959))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[3]; +CheckValue x635 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x635.valid){ +continue; +} +IkReal x633=((1.0)*(x635.value)); +IkReal x634=x629; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x633))); +IkReal gconst9=((3.14159265358979)+(((-1.0)*x633))); +IkReal gconst10=((1.0)*new_r01*x634); +IkReal gconst11=((-1.0)*new_r11*x634); +IkReal x636=new_r01*new_r01; +IkReal x637=(((new_r10*new_r11))+((new_r00*new_r01))); +IkReal x638=x629; +IkReal x639=((1.0)*new_r01*x638); +j3eval[0]=x637; +j3eval[1]=((IKabs(((((-1.0)*new_r00*x639))+(((-1.0)*new_r11*x639)))))+(IKabs((((x636*x638))+(((-1.0)*new_r10*x639)))))); +j3eval[2]=IKsign(x637); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[2]; +CheckValue x642 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x642.valid){ +continue; +} +IkReal x640=((1.0)*(x642.value)); +IkReal x641=x629; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x640))); +IkReal gconst9=((3.14159265358979)+(((-1.0)*x640))); +IkReal gconst10=((1.0)*new_r01*x641); +IkReal gconst11=((-1.0)*new_r11*x641); +IkReal x643=((new_r01*new_r01)+(new_r11*new_r11)); +j3eval[0]=x643; +j3eval[1]=IKsign(x643); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x646 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x646.valid){ +continue; +} +IkReal x644=((1.0)*(x646.value)); +IkReal x645=x629; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x644))); +IkReal gconst9=((3.14159265358979)+(((-1.0)*x644))); +IkReal gconst10=((1.0)*new_r01*x645); +IkReal gconst11=((-1.0)*new_r11*x645); +j3eval[0]=((new_r01*new_r01)+(new_r11*new_r11)); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal evalcond[5]; +bool bgotonextstatement = true; +do +{ +evalcond[0]=((gconst10*gconst10)+(gconst11*gconst11)); +evalcond[1]=new_r01; +evalcond[2]=new_r00; +evalcond[3]=new_r11; +evalcond[4]=new_r10; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[4], cj3array[4], sj3array[4]; +bool j3valid[4]={false}; +_nj3 = 4; +j3array[0]=0; +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=1.5707963267949; +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +j3array[2]=3.14159265358979; +sj3array[2]=IKsin(j3array[2]); +cj3array[2]=IKcos(j3array[2]); +j3array[3]=-1.5707963267949; +sj3array[3]=IKsin(j3array[3]); +cj3array[3]=IKcos(j3array[3]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +if( j3array[2] > IKPI ) +{ + j3array[2]-=IK2PI; +} +else if( j3array[2] < -IKPI ) +{ j3array[2]+=IK2PI; +} +j3valid[2] = true; +if( j3array[3] > IKPI ) +{ + j3array[3]-=IK2PI; +} +else if( j3array[3] < -IKPI ) +{ j3array[3]+=IK2PI; +} +j3valid[3] = true; +for(int ij3 = 0; ij3 < 4; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 4; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +CheckValue x648 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); +if(!x648.valid){ +continue; +} +IkReal x647=((1.0)*(x648.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x647))); +new_r11=0; +new_r00=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x647))); +IkReal x649 = new_r01*new_r01; +if(IKabs(x649)==0){ +continue; +} +IkReal gconst10=((1.0)*new_r01*(pow(x649,-0.5))); +IkReal gconst11=0; +j3eval[0]=new_r01; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x650=IKPowWithIntegerCheck(gconst10,-1); +if(!x650.valid){ +continue; +} +cj3array[0]=((-1.0)*new_r01*(x650.value)); +if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j3valid[0] = j3valid[1] = true; + j3array[0] = IKacos(cj3array[0]); + sj3array[0] = IKsin(j3array[0]); + cj3array[1] = cj3array[0]; + j3array[1] = -j3array[0]; + sj3array[1] = -sj3array[0]; +} +else if( isnan(cj3array[0]) ) +{ + // probably any value will work + j3valid[0] = true; + cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0; +} +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x651=IKsin(j3); +IkReal x652=IKcos(j3); +IkReal x653=((-1.0)*x651); +evalcond[0]=(new_r10*x651); +evalcond[1]=(gconst10*x653); +evalcond[2]=(new_r01*x653); +evalcond[3]=(gconst10+((new_r01*x652))); +evalcond[4]=(gconst10+((new_r10*x652))); +evalcond[5]=(((gconst10*x652))+new_r10); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} else +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x654=IKPowWithIntegerCheck(new_r01,-1); +if(!x654.valid){ +continue; +} +cj3array[0]=((-1.0)*gconst10*(x654.value)); +if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j3valid[0] = j3valid[1] = true; + j3array[0] = IKacos(cj3array[0]); + sj3array[0] = IKsin(j3array[0]); + cj3array[1] = cj3array[0]; + j3array[1] = -j3array[0]; + sj3array[1] = -sj3array[0]; +} +else if( isnan(cj3array[0]) ) +{ + // probably any value will work + j3valid[0] = true; + cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0; +} +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x655=IKsin(j3); +IkReal x656=IKcos(j3); +IkReal x657=(gconst10*x656); +IkReal x658=((-1.0)*x655); +evalcond[0]=(new_r10*x655); +evalcond[1]=(gconst10*x658); +evalcond[2]=(new_r01*x658); +evalcond[3]=(x657+new_r01); +evalcond[4]=(gconst10+((new_r10*x656))); +evalcond[5]=(x657+new_r10); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); +evalcond[1]=gconst10; +if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[4]; +CheckValue x660 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x660.valid){ +continue; +} +IkReal x659=((1.0)*(x660.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x659))); +new_r00=0; +new_r10=0; +new_r21=0; +new_r22=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x659))); +IkReal gconst10=((1.0)*new_r01); +IkReal gconst11=((-1.0)*new_r11); +j3eval[0]=1.0; +j3eval[1]=1.0; +j3eval[2]=new_r01; +j3eval[3]=1.0; +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 || IKabs(j3eval[3]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[3]; +CheckValue x662 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x662.valid){ +continue; +} +IkReal x661=((1.0)*(x662.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x661))); +new_r00=0; +new_r10=0; +new_r21=0; +new_r22=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x661))); +IkReal gconst10=((1.0)*new_r01); +IkReal gconst11=((-1.0)*new_r11); +j3eval[0]=-1.0; +j3eval[1]=-1.0; +j3eval[2]=((IKabs(((-1.0)+(new_r01*new_r01))))+(IKabs(((1.0)*new_r01*new_r11)))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[3]; +CheckValue x664 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x664.valid){ +continue; +} +IkReal x663=((1.0)*(x664.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x663))); +new_r00=0; +new_r10=0; +new_r21=0; +new_r22=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x663))); +IkReal gconst10=((1.0)*new_r01); +IkReal gconst11=((-1.0)*new_r11); +j3eval[0]=1.0; +j3eval[1]=1.0; +j3eval[2]=((IKabs(((2.0)*new_r01*new_r11)))+(IKabs(((1.0)+(((-2.0)*(new_r01*new_r01))))))); +if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 ) +{ +continue; // 3 cases reached + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x665=((1.0)*new_r11); +CheckValue x666 = IKatan2WithCheck(IkReal(((((-1.0)*gconst10*x665))+((gconst11*new_r01)))),IkReal(((((-1.0)*gconst11*x665))+(((-1.0)*gconst10*new_r01)))),IKFAST_ATAN2_MAGTHRESH); +if(!x666.valid){ +continue; +} +CheckValue x667=IKPowWithIntegerCheck(IKsign(((new_r01*new_r01)+(new_r11*new_r11))),-1); +if(!x667.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x666.value)+(((1.5707963267949)*(x667.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x668=IKcos(j3); +IkReal x669=IKsin(j3); +IkReal x670=(gconst10*x668); +IkReal x671=(gconst10*x669); +IkReal x672=(gconst11*x668); +IkReal x673=((1.0)*x669); +IkReal x674=(gconst11*x673); +evalcond[0]=(gconst10+((new_r11*x669))+((new_r01*x668))); +evalcond[1]=(x672+x671+new_r11); +evalcond[2]=(x670+(((-1.0)*x674))); +evalcond[3]=(x670+new_r01+(((-1.0)*x674))); +evalcond[4]=((((-1.0)*x671))+(((-1.0)*x672))); +evalcond[5]=((((-1.0)*new_r01*x673))+gconst11+((new_r11*x668))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x675=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst11*gconst11)))+(((-1.0)*(gconst10*gconst10))))),-1); +if(!x675.valid){ +continue; +} +CheckValue x676 = IKatan2WithCheck(IkReal((gconst10*new_r11)),IkReal((gconst11*new_r11)),IKFAST_ATAN2_MAGTHRESH); +if(!x676.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x675.value)))+(x676.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x677=IKcos(j3); +IkReal x678=IKsin(j3); +IkReal x679=(gconst10*x677); +IkReal x680=(gconst10*x678); +IkReal x681=(gconst11*x677); +IkReal x682=((1.0)*x678); +IkReal x683=(gconst11*x682); +evalcond[0]=(((new_r11*x678))+((new_r01*x677))+gconst10); +evalcond[1]=(x681+x680+new_r11); +evalcond[2]=((((-1.0)*x683))+x679); +evalcond[3]=((((-1.0)*x683))+x679+new_r01); +evalcond[4]=((((-1.0)*x681))+(((-1.0)*x680))); +evalcond[5]=(((new_r11*x677))+(((-1.0)*new_r01*x682))+gconst11); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x684=IKPowWithIntegerCheck(IKsign((((gconst10*new_r01))+(((-1.0)*gconst11*new_r11)))),-1); +if(!x684.valid){ +continue; +} +CheckValue x685 = IKatan2WithCheck(IkReal((gconst10*gconst11)),IkReal(((-1.0)*(gconst10*gconst10))),IKFAST_ATAN2_MAGTHRESH); +if(!x685.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x684.value)))+(x685.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x686=IKcos(j3); +IkReal x687=IKsin(j3); +IkReal x688=(gconst10*x686); +IkReal x689=(gconst10*x687); +IkReal x690=(gconst11*x686); +IkReal x691=((1.0)*x687); +IkReal x692=(gconst11*x691); +evalcond[0]=(gconst10+((new_r01*x686))+((new_r11*x687))); +evalcond[1]=(x689+x690+new_r11); +evalcond[2]=(x688+(((-1.0)*x692))); +evalcond[3]=(x688+(((-1.0)*x692))+new_r01); +evalcond[4]=((((-1.0)*x689))+(((-1.0)*x690))); +evalcond[5]=((((-1.0)*new_r01*x691))+gconst11+((new_r11*x686))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x693=IKPowWithIntegerCheck(gconst11,-1); +if(!x693.valid){ +continue; +} +cj3array[0]=(new_r00*(x693.value)); +if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH ) +{ + j3valid[0] = j3valid[1] = true; + j3array[0] = IKacos(cj3array[0]); + sj3array[0] = IKsin(j3array[0]); + cj3array[1] = cj3array[0]; + j3array[1] = -j3array[0]; + sj3array[1] = -sj3array[0]; +} +else if( isnan(cj3array[0]) ) +{ + // probably any value will work + j3valid[0] = true; + cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0; +} +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[6]; +IkReal x694=IKsin(j3); +IkReal x695=IKcos(j3); +IkReal x696=((-1.0)*x694); +evalcond[0]=(new_r11*x694); +evalcond[1]=(gconst11*x696); +evalcond[2]=(new_r00*x696); +evalcond[3]=(((gconst11*x695))+new_r11); +evalcond[4]=(gconst11+((new_r11*x695))); +evalcond[5]=(((new_r00*x695))+(((-1.0)*gconst11))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +CheckValue x698 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x698.valid){ +continue; +} +IkReal x697=((1.0)*(x698.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x697))); +new_r00=0; +new_r01=0; +new_r12=0; +new_r22=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x697))); +IkReal gconst10=0; +IkReal x699 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); +if(IKabs(x699)==0){ +continue; +} +IkReal gconst11=((-1.0)*new_r11*(pow(x699,-0.5))); +j3eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x701 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x701.valid){ +continue; +} +IkReal x700=((1.0)*(x701.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x700))); +new_r00=0; +new_r01=0; +new_r12=0; +new_r22=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x700))); +IkReal gconst10=0; +IkReal x702 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); +if(IKabs(x702)==0){ +continue; +} +IkReal gconst11=((-1.0)*new_r11*(pow(x702,-0.5))); +j3eval[0]=new_r11; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x704 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x704.valid){ +continue; +} +IkReal x703=((1.0)*(x704.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x703))); +new_r00=0; +new_r01=0; +new_r12=0; +new_r22=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x703))); +IkReal gconst10=0; +IkReal x705 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); +if(IKabs(x705)==0){ +continue; +} +IkReal gconst11=((-1.0)*new_r11*(pow(x705,-0.5))); +j3eval[0]=new_r10; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +continue; // 3 cases reached + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x706=IKPowWithIntegerCheck(new_r10,-1); +if(!x706.valid){ +continue; +} +CheckValue x707=IKPowWithIntegerCheck(gconst11,-1); +if(!x707.valid){ +continue; +} +if( IKabs((gconst11*(x706.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11*(x707.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst11*(x706.value)))+IKsqr(((-1.0)*new_r11*(x707.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((gconst11*(x706.value)), ((-1.0)*new_r11*(x707.value))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x708=IKsin(j3); +IkReal x709=IKcos(j3); +IkReal x710=(gconst11*x709); +IkReal x711=(gconst11*x708); +evalcond[0]=(new_r11*x708); +evalcond[1]=(new_r10*x709); +evalcond[2]=((-1.0)*x711); +evalcond[3]=((-1.0)*x710); +evalcond[4]=(x710+new_r11); +evalcond[5]=(gconst11+((new_r11*x709))); +evalcond[6]=((((-1.0)*x711))+new_r10); +evalcond[7]=((((-1.0)*gconst11))+((new_r10*x708))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x712=IKPowWithIntegerCheck(gconst11,-1); +if(!x712.valid){ +continue; +} +CheckValue x713=IKPowWithIntegerCheck(new_r11,-1); +if(!x713.valid){ +continue; +} +if( IKabs((new_r10*(x712.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst11*(x713.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x712.value)))+IKsqr(((-1.0)*gconst11*(x713.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((new_r10*(x712.value)), ((-1.0)*gconst11*(x713.value))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x714=IKsin(j3); +IkReal x715=IKcos(j3); +IkReal x716=(gconst11*x715); +IkReal x717=(gconst11*x714); +evalcond[0]=(new_r11*x714); +evalcond[1]=(new_r10*x715); +evalcond[2]=((-1.0)*x717); +evalcond[3]=((-1.0)*x716); +evalcond[4]=(x716+new_r11); +evalcond[5]=(gconst11+((new_r11*x715))); +evalcond[6]=((((-1.0)*x717))+new_r10); +evalcond[7]=((((-1.0)*gconst11))+((new_r10*x714))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x718=IKPowWithIntegerCheck(IKsign(gconst11),-1); +if(!x718.valid){ +continue; +} +CheckValue x719 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); +if(!x719.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x718.value)))+(x719.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x720=IKsin(j3); +IkReal x721=IKcos(j3); +IkReal x722=(gconst11*x721); +IkReal x723=(gconst11*x720); +evalcond[0]=(new_r11*x720); +evalcond[1]=(new_r10*x721); +evalcond[2]=((-1.0)*x723); +evalcond[3]=((-1.0)*x722); +evalcond[4]=(x722+new_r11); +evalcond[5]=(gconst11+((new_r11*x721))); +evalcond[6]=((((-1.0)*x723))+new_r10); +evalcond[7]=((((-1.0)*gconst11))+((new_r10*x720))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=IKabs(new_r01); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +CheckValue x725 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x725.valid){ +continue; +} +IkReal x724=((1.0)*(x725.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x724))); +new_r01=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x724))); +IkReal gconst10=0; +IkReal x726 = new_r11*new_r11; +if(IKabs(x726)==0){ +continue; +} +IkReal gconst11=((-1.0)*new_r11*(pow(x726,-0.5))); +j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x728 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x728.valid){ +continue; +} +IkReal x727=((1.0)*(x728.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x727))); +new_r01=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x727))); +IkReal gconst10=0; +IkReal x729 = new_r11*new_r11; +if(IKabs(x729)==0){ +continue; +} +IkReal gconst11=((-1.0)*new_r11*(pow(x729,-0.5))); +j3eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +CheckValue x731 = IKatan2WithCheck(IkReal(0),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x731.valid){ +continue; +} +IkReal x730=((1.0)*(x731.value)); +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +sj5=gconst10; +cj5=gconst11; +j5=((3.14159265)+(((-1.0)*x730))); +new_r01=0; +IkReal gconst9=((3.14159265358979)+(((-1.0)*x730))); +IkReal gconst10=0; +IkReal x732 = new_r11*new_r11; +if(IKabs(x732)==0){ +continue; +} +IkReal gconst11=((-1.0)*new_r11*(pow(x732,-0.5))); +j3eval[0]=new_r11; +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +continue; // 3 cases reached + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x733=IKPowWithIntegerCheck(gconst11,-1); +if(!x733.valid){ +continue; +} +CheckValue x734=IKPowWithIntegerCheck(new_r11,-1); +if(!x734.valid){ +continue; +} +if( IKabs((new_r10*(x733.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst11*(x734.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x733.value)))+IKsqr(((-1.0)*gconst11*(x734.value)))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((new_r10*(x733.value)), ((-1.0)*gconst11*(x734.value))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x735=IKsin(j3); +IkReal x736=IKcos(j3); +IkReal x737=(gconst11*x736); +IkReal x738=((1.0)*x735); +evalcond[0]=(new_r11*x735); +evalcond[1]=((-1.0)*gconst11*x735); +evalcond[2]=(x737+new_r11); +evalcond[3]=(gconst11+((new_r11*x736))); +evalcond[4]=((((-1.0)*x737))+new_r00); +evalcond[5]=((((-1.0)*gconst11*x738))+new_r10); +evalcond[6]=((((-1.0)*new_r00*x738))+((new_r10*x736))); +evalcond[7]=(((new_r00*x736))+(((-1.0)*gconst11))+((new_r10*x735))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x739=IKPowWithIntegerCheck(IKsign(gconst11),-1); +if(!x739.valid){ +continue; +} +CheckValue x740 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); +if(!x740.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x739.value)))+(x740.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x741=IKsin(j3); +IkReal x742=IKcos(j3); +IkReal x743=(gconst11*x742); +IkReal x744=((1.0)*x741); +evalcond[0]=(new_r11*x741); +evalcond[1]=((-1.0)*gconst11*x741); +evalcond[2]=(x743+new_r11); +evalcond[3]=(gconst11+((new_r11*x742))); +evalcond[4]=((((-1.0)*x743))+new_r00); +evalcond[5]=((((-1.0)*gconst11*x744))+new_r10); +evalcond[6]=((((-1.0)*new_r00*x744))+((new_r10*x742))); +evalcond[7]=(((new_r10*x741))+((new_r00*x742))+(((-1.0)*gconst11))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x745=IKPowWithIntegerCheck(IKsign(gconst11),-1); +if(!x745.valid){ +continue; +} +CheckValue x746 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH); +if(!x746.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x745.value)))+(x746.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x747=IKsin(j3); +IkReal x748=IKcos(j3); +IkReal x749=(gconst11*x748); +IkReal x750=((1.0)*x747); +evalcond[0]=(new_r11*x747); +evalcond[1]=((-1.0)*gconst11*x747); +evalcond[2]=(x749+new_r11); +evalcond[3]=(gconst11+((new_r11*x748))); +evalcond[4]=((((-1.0)*x749))+new_r00); +evalcond[5]=((((-1.0)*gconst11*x750))+new_r10); +evalcond[6]=((((-1.0)*new_r00*x750))+((new_r10*x748))); +evalcond[7]=(((new_r10*x747))+((new_r00*x748))+(((-1.0)*gconst11))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j3] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} +} +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x751=((1.0)*new_r11); +CheckValue x752 = IKatan2WithCheck(IkReal((((gconst11*new_r01))+(((-1.0)*gconst10*x751)))),IkReal(((((-1.0)*gconst11*x751))+(((-1.0)*gconst10*new_r01)))),IKFAST_ATAN2_MAGTHRESH); +if(!x752.valid){ +continue; +} +CheckValue x753=IKPowWithIntegerCheck(IKsign(((gconst10*gconst10)+(gconst11*gconst11))),-1); +if(!x753.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x752.value)+(((1.5707963267949)*(x753.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x754=IKcos(j3); +IkReal x755=IKsin(j3); +IkReal x756=(gconst10*x754); +IkReal x757=(gconst11*x754); +IkReal x758=(gconst10*x755); +IkReal x759=((1.0)*x755); +IkReal x760=(gconst11*x759); +evalcond[0]=(gconst10+((new_r11*x755))+((new_r01*x754))); +evalcond[1]=(x757+x758+new_r11); +evalcond[2]=((((-1.0)*x760))+x756+new_r01); +evalcond[3]=((((-1.0)*new_r00*x759))+gconst10+((new_r10*x754))); +evalcond[4]=((((-1.0)*new_r01*x759))+gconst11+((new_r11*x754))); +evalcond[5]=((((-1.0)*x760))+x756+new_r10); +evalcond[6]=(((new_r00*x754))+((new_r10*x755))+(((-1.0)*gconst11))); +evalcond[7]=((((-1.0)*x758))+(((-1.0)*x757))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x761=((1.0)*new_r11); +CheckValue x762=IKPowWithIntegerCheck(IKsign(((new_r01*new_r01)+(new_r11*new_r11))),-1); +if(!x762.valid){ +continue; +} +CheckValue x763 = IKatan2WithCheck(IkReal((((gconst11*new_r01))+(((-1.0)*gconst10*x761)))),IkReal(((((-1.0)*gconst11*x761))+(((-1.0)*gconst10*new_r01)))),IKFAST_ATAN2_MAGTHRESH); +if(!x763.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x762.value)))+(x763.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x764=IKcos(j3); +IkReal x765=IKsin(j3); +IkReal x766=(gconst10*x764); +IkReal x767=(gconst11*x764); +IkReal x768=(gconst10*x765); +IkReal x769=((1.0)*x765); +IkReal x770=(gconst11*x769); +evalcond[0]=(((new_r11*x765))+gconst10+((new_r01*x764))); +evalcond[1]=(x768+x767+new_r11); +evalcond[2]=(x766+(((-1.0)*x770))+new_r01); +evalcond[3]=(((new_r10*x764))+(((-1.0)*new_r00*x769))+gconst10); +evalcond[4]=(((new_r11*x764))+gconst11+(((-1.0)*new_r01*x769))); +evalcond[5]=(x766+(((-1.0)*x770))+new_r10); +evalcond[6]=(((new_r10*x765))+((new_r00*x764))+(((-1.0)*gconst11))); +evalcond[7]=((((-1.0)*x767))+(((-1.0)*x768))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x771=((1.0)*gconst10); +CheckValue x772 = IKatan2WithCheck(IkReal(((((-1.0)*new_r10*x771))+((gconst10*new_r01)))),IkReal(((((-1.0)*new_r00*x771))+(((-1.0)*new_r11*x771)))),IKFAST_ATAN2_MAGTHRESH); +if(!x772.valid){ +continue; +} +CheckValue x773=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); +if(!x773.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x772.value)+(((1.5707963267949)*(x773.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x774=IKcos(j3); +IkReal x775=IKsin(j3); +IkReal x776=(gconst10*x774); +IkReal x777=(gconst11*x774); +IkReal x778=(gconst10*x775); +IkReal x779=((1.0)*x775); +IkReal x780=(gconst11*x779); +evalcond[0]=(gconst10+((new_r11*x775))+((new_r01*x774))); +evalcond[1]=(x777+x778+new_r11); +evalcond[2]=((((-1.0)*x780))+x776+new_r01); +evalcond[3]=((((-1.0)*new_r00*x779))+gconst10+((new_r10*x774))); +evalcond[4]=((((-1.0)*new_r01*x779))+gconst11+((new_r11*x774))); +evalcond[5]=((((-1.0)*x780))+x776+new_r10); +evalcond[6]=(((new_r00*x774))+((new_r10*x775))+(((-1.0)*gconst11))); +evalcond[7]=(new_r00+(((-1.0)*x778))+(((-1.0)*x777))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +sj4=0; +cj4=-1.0; +j4=3.14159265358979; +new_r11=0; +new_r01=0; +new_r22=0; +new_r20=0; +j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +continue; // no branches [j3] + +} else +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x782 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); +if(!x782.valid){ +continue; +} +IkReal x781=x782.value; +j3array[0]=((-1.0)*x781); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=((3.14159265358979)+(((-1.0)*x781))); +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[1]; +evalcond[0]=((((-1.0)*new_r00*(IKsin(j3))))+((new_r10*(IKcos(j3))))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j3] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} +} +} +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x783=((1.0)*sj5); +CheckValue x784 = IKatan2WithCheck(IkReal((((cj5*new_r01))+(((-1.0)*new_r11*x783)))),IkReal(((((-1.0)*new_r01*x783))+(((-1.0)*cj5*new_r11)))),IKFAST_ATAN2_MAGTHRESH); +if(!x784.valid){ +continue; +} +CheckValue x785=IKPowWithIntegerCheck(IKsign(((new_r01*new_r01)+(new_r11*new_r11))),-1); +if(!x785.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x784.value)+(((1.5707963267949)*(x785.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x786=IKsin(j3); +IkReal x787=IKcos(j3); +IkReal x788=((1.0)*cj5); +IkReal x789=(sj5*x787); +IkReal x790=(sj5*x786); +IkReal x791=((1.0)*x786); +IkReal x792=(x786*x788); +evalcond[0]=(sj5+((new_r11*x786))+((new_r01*x787))); +evalcond[1]=(((cj5*x787))+x790+new_r11); +evalcond[2]=((((-1.0)*x792))+x789+new_r01); +evalcond[3]=(sj5+((new_r10*x787))+(((-1.0)*new_r00*x791))); +evalcond[4]=((((-1.0)*new_r01*x791))+cj5+((new_r11*x787))); +evalcond[5]=((((-1.0)*x792))+x789+new_r10); +evalcond[6]=(((new_r10*x786))+(((-1.0)*x788))+((new_r00*x787))); +evalcond[7]=((((-1.0)*x787*x788))+(((-1.0)*x790))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +IkReal x793=((1.0)*sj5); +CheckValue x794 = IKatan2WithCheck(IkReal((((new_r01*sj5))+(((-1.0)*new_r10*x793)))),IkReal(((((-1.0)*new_r11*x793))+(((-1.0)*new_r00*x793)))),IKFAST_ATAN2_MAGTHRESH); +if(!x794.valid){ +continue; +} +CheckValue x795=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); +if(!x795.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x794.value)+(((1.5707963267949)*(x795.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x796=IKsin(j3); +IkReal x797=IKcos(j3); +IkReal x798=((1.0)*cj5); +IkReal x799=(sj5*x797); +IkReal x800=(sj5*x796); +IkReal x801=((1.0)*x796); +IkReal x802=(x796*x798); +evalcond[0]=(sj5+((new_r11*x796))+((new_r01*x797))); +evalcond[1]=(((cj5*x797))+new_r11+x800); +evalcond[2]=(x799+new_r01+(((-1.0)*x802))); +evalcond[3]=(sj5+((new_r10*x797))+(((-1.0)*new_r00*x801))); +evalcond[4]=((((-1.0)*new_r01*x801))+cj5+((new_r11*x797))); +evalcond[5]=(x799+new_r10+(((-1.0)*x802))); +evalcond[6]=((((-1.0)*x798))+((new_r10*x796))+((new_r00*x797))); +evalcond[7]=((((-1.0)*x800))+(((-1.0)*x797*x798))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x803 = IKatan2WithCheck(IkReal(((-1.0)+(new_r01*new_r01)+(cj5*cj5))),IkReal(((((-1.0)*cj5*sj5))+(((-1.0)*new_r01*new_r11)))),IKFAST_ATAN2_MAGTHRESH); +if(!x803.valid){ +continue; +} +CheckValue x804=IKPowWithIntegerCheck(IKsign((((new_r11*sj5))+((cj5*new_r01)))),-1); +if(!x804.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(x803.value)+(((1.5707963267949)*(x804.value)))); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[8]; +IkReal x805=IKsin(j3); +IkReal x806=IKcos(j3); +IkReal x807=((1.0)*cj5); +IkReal x808=(sj5*x806); +IkReal x809=(sj5*x805); +IkReal x810=((1.0)*x805); +IkReal x811=(x805*x807); +evalcond[0]=(sj5+((new_r11*x805))+((new_r01*x806))); +evalcond[1]=(((cj5*x806))+new_r11+x809); +evalcond[2]=((((-1.0)*x811))+new_r01+x808); +evalcond[3]=(sj5+(((-1.0)*new_r00*x810))+((new_r10*x806))); +evalcond[4]=(cj5+(((-1.0)*new_r01*x810))+((new_r11*x806))); +evalcond[5]=((((-1.0)*x811))+new_r10+x808); +evalcond[6]=(((new_r00*x806))+((new_r10*x805))+(((-1.0)*x807))); +evalcond[7]=((((-1.0)*x809))+(((-1.0)*x806*x807))+new_r00); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02))); +if( IKabs(evalcond[0]) < 0.0000050000000000 ) +{ +bgotonextstatement=false; +{ +IkReal j3eval[1]; +new_r02=0; +new_r12=0; +new_r20=0; +new_r21=0; +j3eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +new_r02=0; +new_r12=0; +new_r20=0; +new_r21=0; +j3eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +{ +IkReal j3eval[1]; +new_r02=0; +new_r12=0; +new_r20=0; +new_r21=0; +j3eval[0]=((IKabs((new_r10*new_r22)))+(IKabs((new_r00*new_r22)))); +if( IKabs(j3eval[0]) < 0.0000010000000000 ) +{ +continue; // no branches [j3] + +} else +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x813 = IKatan2WithCheck(IkReal((new_r10*new_r22)),IkReal(((-1.0)*new_r00*new_r22)),IKFAST_ATAN2_MAGTHRESH); +if(!x813.valid){ +continue; +} +IkReal x812=x813.value; +j3array[0]=((-1.0)*x812); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=((3.14159265358979)+(((-1.0)*x812))); +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[5]; +IkReal x814=IKsin(j3); +IkReal x815=IKcos(j3); +IkReal x816=(new_r11*x815); +IkReal x817=((1.0)*x814); +evalcond[0]=(((new_r11*x814))+((new_r01*x815))); +evalcond[1]=(((new_r00*x815))+((new_r10*x814))); +evalcond[2]=(((new_r10*x815))+(((-1.0)*new_r00*x817))); +evalcond[3]=((((-1.0)*new_r01*x817))+x816); +evalcond[4]=(((new_r22*x816))+(((-1.0)*new_r01*new_r22*x817))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x819 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); +if(!x819.valid){ +continue; +} +IkReal x818=x819.value; +j3array[0]=((-1.0)*x818); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=((3.14159265358979)+(((-1.0)*x818))); +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[5]; +IkReal x820=IKcos(j3); +IkReal x821=IKsin(j3); +IkReal x822=(new_r11*x820); +IkReal x823=(new_r10*x820); +IkReal x824=((1.0)*x821); +evalcond[0]=(((new_r01*x820))+((new_r11*x821))); +evalcond[1]=((((-1.0)*new_r00*x824))+x823); +evalcond[2]=((((-1.0)*new_r01*x824))+x822); +evalcond[3]=((((-1.0)*new_r00*new_r22*x824))+((new_r22*x823))); +evalcond[4]=(((new_r22*x822))+(((-1.0)*new_r01*new_r22*x824))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[2], cj3array[2], sj3array[2]; +bool j3valid[2]={false}; +_nj3 = 2; +CheckValue x826 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); +if(!x826.valid){ +continue; +} +IkReal x825=x826.value; +j3array[0]=((-1.0)*x825); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +j3array[1]=((3.14159265358979)+(((-1.0)*x825))); +sj3array[1]=IKsin(j3array[1]); +cj3array[1]=IKcos(j3array[1]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +if( j3array[1] > IKPI ) +{ + j3array[1]-=IK2PI; +} +else if( j3array[1] < -IKPI ) +{ j3array[1]+=IK2PI; +} +j3valid[1] = true; +for(int ij3 = 0; ij3 < 2; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 2; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[5]; +IkReal x827=IKcos(j3); +IkReal x828=IKsin(j3); +IkReal x829=(new_r11*x827); +IkReal x830=(new_r10*x827); +IkReal x831=((1.0)*x828); +evalcond[0]=(((new_r10*x828))+((new_r00*x827))); +evalcond[1]=(x830+(((-1.0)*new_r00*x831))); +evalcond[2]=((((-1.0)*new_r01*x831))+x829); +evalcond[3]=((((-1.0)*new_r00*new_r22*x831))+((new_r22*x830))); +evalcond[4]=(((new_r22*x829))+(((-1.0)*new_r01*new_r22*x831))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} +} while(0); +if( bgotonextstatement ) +{ +bool bgotonextstatement = true; +do +{ +if( 1 ) +{ +bgotonextstatement=false; +continue; // branch miss [j3] + +} +} while(0); +if( bgotonextstatement ) +{ +} +} +} +} +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x833=IKPowWithIntegerCheck(sj4,-1); +if(!x833.valid){ +continue; +} +IkReal x832=x833.value; +CheckValue x834=IKPowWithIntegerCheck(new_r11,-1); +if(!x834.valid){ +continue; +} +if( IKabs((x832*(x834.value)*((((new_r01*new_r12))+(((-1.0)*sj4*sj5)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r12*x832)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x832*(x834.value)*((((new_r01*new_r12))+(((-1.0)*sj4*sj5))))))+IKsqr(((-1.0)*new_r12*x832))-1) <= IKFAST_SINCOS_THRESH ) + continue; +j3array[0]=IKatan2((x832*(x834.value)*((((new_r01*new_r12))+(((-1.0)*sj4*sj5))))), ((-1.0)*new_r12*x832)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[18]; +IkReal x835=IKsin(j3); +IkReal x836=IKcos(j3); +IkReal x837=((1.0)*cj5); +IkReal x838=((1.0)*cj4); +IkReal x839=(new_r11*x836); +IkReal x840=(sj5*x836); +IkReal x841=(cj4*x836); +IkReal x842=(sj4*x836); +IkReal x843=(new_r00*x835); +IkReal x844=(cj4*x835); +IkReal x845=(new_r01*x835); +IkReal x846=(new_r02*x835); +IkReal x847=((1.0)*sj4*x835); +evalcond[0]=(new_r12+x842); +evalcond[1]=((((-1.0)*x847))+new_r02); +evalcond[2]=(((new_r12*x835))+((new_r02*x836))); +evalcond[3]=(((new_r11*x835))+sj5+((new_r01*x836))); +evalcond[4]=(sj4+((new_r12*x836))+(((-1.0)*x846))); +evalcond[5]=(((cj5*x844))+new_r01+x840); +evalcond[6]=(((new_r00*x836))+(((-1.0)*x837))+((new_r10*x835))); +evalcond[7]=((((-1.0)*x836*x837))+((sj5*x844))+new_r00); +evalcond[8]=((((-1.0)*x837*x841))+((sj5*x835))+new_r11); +evalcond[9]=((((-1.0)*x835*x837))+(((-1.0)*x838*x840))+new_r10); +evalcond[10]=((((-1.0)*x843))+(((-1.0)*sj5*x838))+((new_r10*x836))); +evalcond[11]=((((-1.0)*cj4*x837))+(((-1.0)*x845))+x839); +evalcond[12]=(((new_r12*x841))+((new_r22*sj4))+(((-1.0)*x838*x846))); +evalcond[13]=(((new_r10*x842))+(((-1.0)*sj4*x843))+(((-1.0)*new_r20*x838))); +evalcond[14]=(((sj4*x839))+(((-1.0)*sj4*x845))+(((-1.0)*new_r21*x838))); +evalcond[15]=((1.0)+(((-1.0)*new_r22*x838))+((new_r12*x842))+(((-1.0)*sj4*x846))); +evalcond[16]=(((new_r10*x841))+(((-1.0)*sj5))+((new_r20*sj4))+(((-1.0)*x838*x843))); +evalcond[17]=(((cj4*x839))+(((-1.0)*x837))+(((-1.0)*x838*x845))+((new_r21*sj4))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} + +} else +{ +{ +IkReal j3array[1], cj3array[1], sj3array[1]; +bool j3valid[1]={false}; +_nj3 = 1; +CheckValue x848=IKPowWithIntegerCheck(IKsign(sj4),-1); +if(!x848.valid){ +continue; +} +CheckValue x849 = IKatan2WithCheck(IkReal(new_r02),IkReal(((-1.0)*new_r12)),IKFAST_ATAN2_MAGTHRESH); +if(!x849.valid){ +continue; +} +j3array[0]=((-1.5707963267949)+(((1.5707963267949)*(x848.value)))+(x849.value)); +sj3array[0]=IKsin(j3array[0]); +cj3array[0]=IKcos(j3array[0]); +if( j3array[0] > IKPI ) +{ + j3array[0]-=IK2PI; +} +else if( j3array[0] < -IKPI ) +{ j3array[0]+=IK2PI; +} +j3valid[0] = true; +for(int ij3 = 0; ij3 < 1; ++ij3) +{ +if( !j3valid[ij3] ) +{ + continue; +} +_ij3[0] = ij3; _ij3[1] = -1; +for(int iij3 = ij3+1; iij3 < 1; ++iij3) +{ +if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) +{ + j3valid[iij3]=false; _ij3[1] = iij3; break; +} +} +j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; +{ +IkReal evalcond[18]; +IkReal x850=IKsin(j3); +IkReal x851=IKcos(j3); +IkReal x852=((1.0)*cj5); +IkReal x853=((1.0)*cj4); +IkReal x854=(new_r11*x851); +IkReal x855=(sj5*x851); +IkReal x856=(cj4*x851); +IkReal x857=(sj4*x851); +IkReal x858=(new_r00*x850); +IkReal x859=(cj4*x850); +IkReal x860=(new_r01*x850); +IkReal x861=(new_r02*x850); +IkReal x862=((1.0)*sj4*x850); +evalcond[0]=(new_r12+x857); +evalcond[1]=((((-1.0)*x862))+new_r02); +evalcond[2]=(((new_r12*x850))+((new_r02*x851))); +evalcond[3]=(sj5+((new_r11*x850))+((new_r01*x851))); +evalcond[4]=(sj4+(((-1.0)*x861))+((new_r12*x851))); +evalcond[5]=(new_r01+x855+((cj5*x859))); +evalcond[6]=((((-1.0)*x852))+((new_r10*x850))+((new_r00*x851))); +evalcond[7]=(((sj5*x859))+new_r00+(((-1.0)*x851*x852))); +evalcond[8]=(((sj5*x850))+(((-1.0)*x852*x856))+new_r11); +evalcond[9]=((((-1.0)*x853*x855))+(((-1.0)*x850*x852))+new_r10); +evalcond[10]=((((-1.0)*x858))+(((-1.0)*sj5*x853))+((new_r10*x851))); +evalcond[11]=((((-1.0)*x860))+x854+(((-1.0)*cj4*x852))); +evalcond[12]=((((-1.0)*x853*x861))+((new_r22*sj4))+((new_r12*x856))); +evalcond[13]=((((-1.0)*sj4*x858))+(((-1.0)*new_r20*x853))+((new_r10*x857))); +evalcond[14]=((((-1.0)*new_r21*x853))+((sj4*x854))+(((-1.0)*sj4*x860))); +evalcond[15]=((1.0)+((new_r12*x857))+(((-1.0)*new_r22*x853))+(((-1.0)*sj4*x861))); +evalcond[16]=((((-1.0)*sj5))+(((-1.0)*x853*x858))+((new_r20*sj4))+((new_r10*x856))); +evalcond[17]=((((-1.0)*x852))+(((-1.0)*x853*x860))+((new_r21*sj4))+((cj4*x854))); +if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH ) +{ +continue; +} +} + +{ +std::vector > vinfos(6); +vinfos[0].jointtype = 1; +vinfos[0].foffset = j0; +vinfos[0].indices[0] = _ij0[0]; +vinfos[0].indices[1] = _ij0[1]; +vinfos[0].maxsolutions = _nj0; +vinfos[1].jointtype = 1; +vinfos[1].foffset = j1; +vinfos[1].indices[0] = _ij1[0]; +vinfos[1].indices[1] = _ij1[1]; +vinfos[1].maxsolutions = _nj1; +vinfos[2].jointtype = 1; +vinfos[2].foffset = j2; +vinfos[2].indices[0] = _ij2[0]; +vinfos[2].indices[1] = _ij2[1]; +vinfos[2].maxsolutions = _nj2; +vinfos[3].jointtype = 1; +vinfos[3].foffset = j3; +vinfos[3].indices[0] = _ij3[0]; +vinfos[3].indices[1] = _ij3[1]; +vinfos[3].maxsolutions = _nj3; +vinfos[4].jointtype = 1; +vinfos[4].foffset = j4; +vinfos[4].indices[0] = _ij4[0]; +vinfos[4].indices[1] = _ij4[1]; +vinfos[4].maxsolutions = _nj4; +vinfos[5].jointtype = 1; +vinfos[5].foffset = j5; +vinfos[5].indices[0] = _ij5[0]; +vinfos[5].indices[1] = _ij5[1]; +vinfos[5].maxsolutions = _nj5; +std::vector vfree(0); +solutions.AddSolution(vinfos,vfree); +} +} +} + +} + +} +} +} + +} + +} +} +} +} +}static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots) +{ + using std::complex; + if( rawcoeffs[0] == 0 ) { + // solve with one reduced degree + polyroots2(&rawcoeffs[1], &rawroots[0], numroots); + return; + } + IKFAST_ASSERT(rawcoeffs[0] != 0); + const IkReal tol = 128.0*std::numeric_limits::epsilon(); + const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); + complex coeffs[3]; + const int maxsteps = 110; + for(int i = 0; i < 3; ++i) { + coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); + } + complex roots[3]; + IkReal err[3]; + roots[0] = complex(1,0); + roots[1] = complex(0.4,0.9); // any complex number not a root of unity works + err[0] = 1.0; + err[1] = 1.0; + for(int i = 2; i < 3; ++i) { + roots[i] = roots[i-1]*roots[1]; + err[i] = 1.0; + } + for(int step = 0; step < maxsteps; ++step) { + bool changed = false; + for(int i = 0; i < 3; ++i) { + if ( err[i] >= tol ) { + changed = true; + // evaluate + complex x = roots[i] + coeffs[0]; + for(int j = 1; j < 3; ++j) { + x = roots[i] * x + coeffs[j]; + } + for(int j = 0; j < 3; ++j) { + if( i != j ) { + if( roots[i] != roots[j] ) { + x /= (roots[i] - roots[j]); + } + } + } + roots[i] -= x; + err[i] = abs(x); + } + } + if( !changed ) { + break; + } + } + + numroots = 0; + bool visited[3] = {false}; + for(int i = 0; i < 3; ++i) { + if( !visited[i] ) { + // might be a multiple root, in which case it will have more error than the other roots + // find any neighboring roots, and take the average + complex newroot=roots[i]; + int n = 1; + for(int j = i+1; j < 3; ++j) { + // care about error in real much more than imaginary + if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { + newroot += roots[j]; + n += 1; + visited[j] = true; + } + } + if( n > 1 ) { + newroot /= n; + } + // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt + if( IKabs(imag(newroot)) < tolsqrt ) { + rawroots[numroots++] = real(newroot); + } + } + } +} +static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) { + IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2]; + if( det < 0 ) { + numroots=0; + } + else if( det == 0 ) { + rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0]; + numroots = 1; + } + else { + det = IKsqrt(det); + rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]); + rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]); + numroots = 2; + } +} +static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots) +{ + using std::complex; + if( rawcoeffs[0] == 0 ) { + // solve with one reduced degree + polyroots3(&rawcoeffs[1], &rawroots[0], numroots); + return; + } + IKFAST_ASSERT(rawcoeffs[0] != 0); + const IkReal tol = 128.0*std::numeric_limits::epsilon(); + const IkReal tolsqrt = sqrt(std::numeric_limits::epsilon()); + complex coeffs[4]; + const int maxsteps = 110; + for(int i = 0; i < 4; ++i) { + coeffs[i] = complex(rawcoeffs[i+1]/rawcoeffs[0]); + } + complex roots[4]; + IkReal err[4]; + roots[0] = complex(1,0); + roots[1] = complex(0.4,0.9); // any complex number not a root of unity works + err[0] = 1.0; + err[1] = 1.0; + for(int i = 2; i < 4; ++i) { + roots[i] = roots[i-1]*roots[1]; + err[i] = 1.0; + } + for(int step = 0; step < maxsteps; ++step) { + bool changed = false; + for(int i = 0; i < 4; ++i) { + if ( err[i] >= tol ) { + changed = true; + // evaluate + complex x = roots[i] + coeffs[0]; + for(int j = 1; j < 4; ++j) { + x = roots[i] * x + coeffs[j]; + } + for(int j = 0; j < 4; ++j) { + if( i != j ) { + if( roots[i] != roots[j] ) { + x /= (roots[i] - roots[j]); + } + } + } + roots[i] -= x; + err[i] = abs(x); + } + } + if( !changed ) { + break; + } + } + + numroots = 0; + bool visited[4] = {false}; + for(int i = 0; i < 4; ++i) { + if( !visited[i] ) { + // might be a multiple root, in which case it will have more error than the other roots + // find any neighboring roots, and take the average + complex newroot=roots[i]; + int n = 1; + for(int j = i+1; j < 4; ++j) { + // care about error in real much more than imaginary + if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { + newroot += roots[j]; + n += 1; + visited[j] = true; + } + } + if( n > 1 ) { + newroot /= n; + } + // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt + if( IKabs(imag(newroot)) < tolsqrt ) { + rawroots[numroots++] = real(newroot); + } + } + } +} +}; + + +/// solves the inverse kinematics equations. +/// \param pfree is an array specifying the free joints of the chain. +IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions) { +IKSolver solver; +return solver.ComputeIk(eetrans,eerot,pfree,solutions); +} + +IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase& solutions, void* pOpenRAVEManip) { +IKSolver solver; +return solver.ComputeIk(eetrans,eerot,pfree,solutions); +} + +IKFAST_API const char* GetKinematicsHash() { return ""; } + +IKFAST_API const char* GetIkFastVersion() { return "0x1000004a"; } + +#ifdef IKFAST_NAMESPACE +} // end namespace +#endif + +#ifndef IKFAST_NO_MAIN +#include +#include +#ifdef IKFAST_NAMESPACE +using namespace IKFAST_NAMESPACE; +#endif +int main(int argc, char** argv) +{ + if( argc != 12+GetNumFreeParameters()+1 ) { + printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n" + "Returns the ik solutions given the transformation of the end effector specified by\n" + "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n" + "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters()); + return 1; + } + + IkSolutionList solutions; + std::vector vfree(GetNumFreeParameters()); + IkReal eerot[9],eetrans[3]; + eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]); + eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]); + eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]); + for(std::size_t i = 0; i < vfree.size(); ++i) + vfree[i] = atof(argv[13+i]); + bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions); + + if( !bSuccess ) { + fprintf(stderr,"Failed to get ik solution\n"); + return -1; + } + + printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions()); + std::vector solvalues(GetNumJoints()); + for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) { + const IkSolutionBase& sol = solutions.GetSolution(i); + printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size()); + std::vector vsolfree(sol.GetFree().size()); + sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL); + for( std::size_t j = 0; j < solvalues.size(); ++j) + printf("%.15f, ", solvalues[j]); + printf("\n"); + } + return 0; +} + +#endif From fdd6b8603f15e7a172fc4889e87d690a9c26988b Mon Sep 17 00:00:00 2001 From: ohno_atsushi Date: Mon, 2 Oct 2023 15:33:53 +0900 Subject: [PATCH 2/3] Readme Corrections rs030n --- README.md | 1 + docs/ConnectingRealRobot-ja.md | 1 + docs/ConnectingRealRobot.md | 1 + docs/README-ja.md | 1 + 4 files changed, 4 insertions(+) diff --git a/README.md b/README.md index 096a7cd..2d11490 100644 --- a/README.md +++ b/README.md @@ -54,6 +54,7 @@ Refer to [docs/ConnectingRealRobot.md](docs/ConnectingRealRobot.md) * rs013n * rs020n * rs025n + * rs030n * rs80n ## Notes diff --git a/docs/ConnectingRealRobot-ja.md b/docs/ConnectingRealRobot-ja.md index 80ee0bd..a5f9926 100644 --- a/docs/ConnectingRealRobot-ja.md +++ b/docs/ConnectingRealRobot-ja.md @@ -14,6 +14,7 @@ |rs013n|||✓||✓|| |rs020n|✓||✓|||| |rs025n||||✓||| +|rs030n||||✓||| |rs080n||✓||✓||| ### 1.2 サポートしているASバージョン diff --git a/docs/ConnectingRealRobot.md b/docs/ConnectingRealRobot.md index c7eeb37..b6e9845 100644 --- a/docs/ConnectingRealRobot.md +++ b/docs/ConnectingRealRobot.md @@ -13,6 +13,7 @@ Controllers with ”✓” are available. |rs013n|||✓||✓|| |rs020n|✓||✓|||| |rs025n||||✓||| +|rs030n||||✓||| |rs080n||✓||✓||| ### 1.2 Supported AS version diff --git a/docs/README-ja.md b/docs/README-ja.md index 8c51e62..9c39c8a 100644 --- a/docs/README-ja.md +++ b/docs/README-ja.md @@ -54,6 +54,7 @@ roslaunch ***_moveit_config moveit_planning_execution.launch * rs013n * rs020n * rs025n + * rs030n * rs80n ## ノート From 04fd063e15c33595d56af8757b7dcb5c360f67e5 Mon Sep 17 00:00:00 2001 From: ohno_atsushi Date: Fri, 6 Oct 2023 13:19:41 +0900 Subject: [PATCH 3/3] Correction of rs030n_macro.xacro&package.xml --- khi_rs030n_moveit_config/package.xml | 2 +- khi_rs_description/urdf/rs030n_macro.xacro | 266 ++++++++++++++++++++- 2 files changed, 255 insertions(+), 13 deletions(-) diff --git a/khi_rs030n_moveit_config/package.xml b/khi_rs030n_moveit_config/package.xml index 4ded01a..12f4273 100644 --- a/khi_rs030n_moveit_config/package.xml +++ b/khi_rs030n_moveit_config/package.xml @@ -1,7 +1,7 @@ khi_rs030n_moveit_config - 0.3.0 + 1.4.0 An automatically generated package with all the configuration and launch files for using the khi_rs030n with the MoveIt Motion Planning Framework diff --git a/khi_rs_description/urdf/rs030n_macro.xacro b/khi_rs_description/urdf/rs030n_macro.xacro index dfa8f88..a2a84e1 100644 --- a/khi_rs_description/urdf/rs030n_macro.xacro +++ b/khi_rs_description/urdf/rs030n_macro.xacro @@ -1,17 +1,259 @@ - - - + + + - - + + - + + + + - + + + - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

=&o+Y@vM3~(S6}G8-X-=@e-QEDlkJnvu7KkdbR;Fa*7t?pq(t&gKum>U9AIRE)d+}Nx1jBxRd$XxvMDc zNMj?ACNEw>b2YdRM0_B)#glOFcgMj_CSI+@YP{7oW#kks(&UAa(=UlAN^31ZoBd&t zn!k5qdBsBeTJFVZMQH^@foDV2`q?#kCzbYt=tVmxq}{uvvy}t1E~^98S%pf-IQX85 zb{2MGTU9vGVcs}3DsxUr@VyAF$Vdh0)7J)F~uat_+##Hj^p zlM{6%LA?aMsAq7R&M7i~bE3ke%7%4XsLImvJX8AIPT-lMWcdXFqZa-G;eU9_cp!T5 z(_1OcK8LG2^UwTk06f=~yja@lO%zL)%=IzscMUE4JY-7a=lncmm>n2F7StdD)AYGn zrZfWzxcVNgBsIvwy-YWpqrq4|RTMts! zICr0pZ?%UtYR#Iq5&XPx>z4#fFDwC|2Z>up+k+EGCPv z+QW+=8a1qTih&>t&ll75xfzGmucQW9xEE?zeazC}1X(zNY5LsMuzI`HAPe_G4Qd;2 zf-IcCG<`0KK=>E_3zQnX4XhDtt7%DC{{*@)uU`>FOXomqzLFZ&EMxT&^S3834r?AW z>&ixu#Vot~*DC09Q^T5fr3P7$pfqY&^RcDD39@hk)AYHiVXX#IgDl(&HLP{T(%=MH zIDu*U+|;mEHK{=s?u8om+T{dUIDu*UTxwYV1iIJ`K#sc@P8+xSu8EigorsPlAp+C0 zGq_JNCmnBsypW)rq<7%^xMf`*;6HA`G?YL3WOf^&5W!AImvL}{((V#ris#GH@@(~( z3Dh9VF9_Atuu7$IFHG|j->sZH2&N(TaGant#ex4HsIkbs2-@3u6J+6~!nD;kW~l;A z&eY%pc_Bfcqp$ndpzs7t^Q6m2-F+ISnRcImX%SM#P1N-w_(`78zpoZZCz8T^qEkA_ z-z#Mr&y>c`WvOsQlYcRJc@t$}oqYrAEFgh&x-sTOX(Z^3UsHn<+!7Okw4$Vh{ow%E zFQ5h|D2-lt9y*>wZ)$LYTVf(i4Vc|D+=rqDCn$|xbmFS1!3l1Oi7+*=o-lgU-~^@7 zi)!7}-~_kCM3@?oH)ikE9(YzQo;;2D@|rgNEkfZIPEgv^cnSMyKQj)6PHDz`DUDuq zg0dM0C%7dh!qkA(--Y{7EFUK*jb8K{0j35gxFsgS)QAPwH$i5aPH;<1gsB0o=feE)4{MahGo{gsYTDF@iQry5Z4y-> zj>pjMsDY)zlc3Q;X(X_O_zMHx1h>RQAPw*Q^e^Co>jJ642}+|E)-?WFfvLd>Zi$I7 zHLPADH8??O^uiv4zgA#saDrQ6B1{ddw@VF9P#V3cZA=YLa7#>tse$c4tw=SBdEp3- zsclSuPXhDe1f@+4Yxa?G;Os;FiqhzXGm*QlIKeG35vGPUi%JbnP#V2(Ms>G2C%7dh z!qi9x^ZHP$UvYxc=!GkTyYF&>TVf(i4V(|L6|tT}7S z&m=d`Cy$iplhaw{vP2sGi+?;{_nG9sAOh_KKlj`u=nQoD2DTXo>ICw9F(%rbxj(N9 zkuyS;it^%wJB@_-XYR_l#hv!v^&w*teAmYbY#S<}B@qL`z1%rr3qE=8uN_Lh#~7td z5qRgHe;b!hi;P!dj@T7;!6rCN+%1djq5f z5vWI}QzAh$e5)9U=|JqZ2=3M3Sarv)x~kN06VHJ7*7B%vYiw7kK?G{hd6uX_w5fr_ zHH+Y0hi*hUmhH+XHS9!-Pp6Ev!y8HsB2a@)z(ftAO^ud7Y_tgO)p$cXHDOC1so^HD zuI67lXO!MiUTP458gynRY7lK|%mbpBMR2dM{gu?M8(!(&M8gl4jpCKFNev=UgU-oB zf@pYe0!oEMNsHiK>p%Ldr3UCy!%biu7wTO%zKFO|g9y~1lQmI;XtQ5k0V1wu65MO? zk}>Kb#}uhyCkouUWqh1)LFM^knojaW4WiB7o)3tZ7Qwx$hKHy(x|fg|ZUTGz*X4JO zyHSg!1`()1XMdsw(Quw65TAfJWD(qJ-jVH4V-js1C$yAbME@ zSvY}d_h~&yJiB<^m{&ZGKn+fi7k++g{%Uo^wHu)E8xZe+2(}2a@O&{%=lB8P^w%7# z_ZS)0PmvleQXf!rI%~+7VvpOcw$55a)*+pk24_HI@1*q`vC^nNWT}n7e8~&bbT%3M zTES_5t!K*>#>Gx6ya@8bINAlDQA@4ptito!BAv8?$2*9iSjWs!%g%eHvtE$sxVoZv z=MxNsb3V+8-AjqCK^JWV_ri3~(Bh)d_~}3tYTijZ@+pUScEFn;FN}jugo5*4ANXrG zW}h>@#PXFIREwBziZz?m{AH8NdZSublxl4|X?a7UjKB_6Yy{>@=iG5xQ8duVQRks3 zJ+-~q@*-j%Z7)8Zn-RfjMR~o#Un`aQ zm=X7FcUdZ45^8gMsV)!gq%CM4ZseLUMiSJ{=tTsNNl|Ji=%n>65^UU^yiXF;&gey_ zy&-)u-CebE<3MPS=lA`!wL>NvbE?}3?uBW0FZtWiN&A+to{@0cDXBsEq6VGBhQx}t zAJnJwCxgb(o&MV8w#|&T2~NqLNEWWaO9;P4+M$y+wgaT8UYij7`e94K>2DW)d}W&yzjTP4peoNqhHTpg!x_9WR2sxE`EY)5l-ycF9jo z{^Fq|T3RQ(p+@%adBl%rv!w>aR`x+*>^TbVL$-{y6ZxiYPE> zh>XKMmy})OueHoEOFYlHT@rN05|-po|2ks##FmmET2c1o?xdYnrim3tcX$!xg{2~G zMVY_ZUn>;6Q7jvA@)lDLQGt!HIQ`CI)&DP zEJ@JmIhb$G*6l=sBa@^?IZF@5;5UCQ%ICW1_|x3`aDu#0gGvim1!rIk_Pj5e%@`%u zJDOingXUeX2Pg2q@z=HdGbryTpisHdx2Ie)Y&q4LpEc09g z`i?k$?wqt!yTpQpHpgRzmErKkVFA)N|s1bJZ`xq1tAd7Nz!M@85(T&xmh zoNrJ=s?+;?m@mCWheXyxkvPyMyuV#V1aCVl^Wr6;Hn*4RJnR|fKhG(aB)TXG>J8{c1dj=Rp#t^{=PnL( zJYM=h64cJO9=K1%fHSx zrf%OR33`JZHJUxE?i{;wwbURz=!vjrSU7gPQEc#DFM_;KgR~W8#VCJmSGmnb{!Q~G zL1PUyXbf^ac*lJ}CoMeb3Zq2QrCtP;3N@&-Frr}3aC!GRBk?{V2|j;_H*cK1lFXNJ zxaX2GuxFUl`liu+{tq4VqW4{~BqIak>OW3~N`h$kH4oS`98P}C_*TRGCOId_3v(iE zMOgrQhImCE7#%nFl^XP(C~CYdmsk&I7a}!CPf-@bo}u)kyGDv)6TJxX;-!Vt#bD1+ z=;uS@-NaAwI)mQfM2)#466s~11xpRmgE0tuhPVqK7{hw0ws&87sZfJT3+Jlo{#u1o z_l)-&=gO6n-hD)3Oyk)4;t4@ggY*<-HS8G_40!FVrZouBs?gA~npr z6G7u=)obE|MUaK(i)nhF!X!pdyez7>&mlE9L0+hFxd;3nUT87Um;f3RfT&^-Wa0T@ zn%-7Xlwct0RXZ<&XP1>4oFFgM$a|@%$knYDX#5{#X91SQ@;&~w#lXf6P{bAkQQmiF z?8a^dQS1OzR1^_RQfvjgyRXf=yS8|-#nx+gC$|4{_GRQOsNdh8=X#%c-g7>4VrFNy zW)|DLD-glSgpkmBu`JdCS=+qI*i-CD`{ue0N(e2qG4@$0)_bKl*ueI1B7~68da*24 zT3LylmE)Q3EKl7AC4?5*u-%iF4RFT2EYL;{ApDXEA))nRS*&BTX1A}`Ay%#d%$}q! zs)fJ5sGET${ftO%kN!ZEO(ukd5?B_i1g&1(FKA)fChOQo3895H?mIq^^QN1h9LF<4 z2nnqh%VG_twFRR(?_!(pN9u7d|^jaVGxp{gM(xQyN zZ?NyfGJ4tqv7+=)#ltI@ckfkFCxnC&Sk6Ab57WBEz<%Ki*A$eq?j6Txek`HVx~LYG z2VL*YSnxQoQEkU|)7}+hwD*^Lr-?)Oj)YzH#d1Y?4G=XaZHbHW^3~D@?9vG#q0wUb zcHAo2r_u)?DqTr$c8~Yb?56EaLkKOj@xZ)Vo)!2Rh)n||i&JJV&HF%-P6!FD7t30w zt@5TfrC=1T;at)D^`56TIR0xILTI6le_gi8d1FcgG4r*P#j#jRt?T$A8kNv`vAlbR zMILs)0T4N!wl(i=(Om0$wOATLXkks0?kMuy>y3f9b=KVyl&z+g@X2*bLK``X-`p74I#A9#*@&DtW?XHK#ZKU!7{+TgF3O-Se+0OS}&IW4b92y z9^ls<8~Q5dJ)2Bw!I;1_gwR48ErWBh8s2k(_}X)y3bFZ} z=K*1JFTp$^rlj(0Us^(F>2a(o!p_!1BC*eL%gRTKoJZs zldqcF4Y(?g7&YD+2O)$O+K93^vZnWD1F?BQqGiD&Pj>0(7@ZIjS}&Ft7pTHM-kT0Y zhSm?w&7@$qHF0zrLTI6l77@;@Ux#QQ{L=gnp8t4goM_M<=P(Y*ykbjfM~TbtGu?S z%=_f1l!g#mXu~0-1KTIL0-TrQ@-j_T;T&5bt0-mg^`4!9twn@3=-f{i- z9ow5}2%&{Gjz#ul9Re-@Ar;H1)O7aa&W*O|gpkmBvHb3OFE;Jv4*{Y9k+fvgLI9*P{MwIL*_ ziJ?j38QAzu~*_h8R&`AS+t+ zrk)>~E0IG(9QyhwN(e2qLEr4RzS)K>N+=<;@ORNG4K~scLJNuHwLrhgF0~=FkVsyk z^gjrpg@jmR_IIy@77}zV*`Fg9T1X_XO8K)_de0DRSBQ;2x1dhYRY_va*B|513895H z#A>d;6G96Ku{P`PgwR4lj7onegccHFRQfw1w2%--*WU@Dg@iaZ(-M)an$~!4ZZIsYw6`b&j!g}8MH{`znO6;A?76{#EQDVdnL4x z5NqZBP6#a|#LBn76G96KF-rWM5L!qi_hSY25bCEY&Rqkwo&CzQX8S9dt0py+?|3+{ zfF(oC9@Fc~EA!d2s^eud|I%2#`r47fU7TqJ)gy1mYRjB68zhv#@}@lv<%z|R_%dpc zlK<=g?c9U&X$YZp+_$-T{LPl~4EORtM74XQtRFZ?^9ef2sD##wO6z5bz>&3D|{*JP99wZiA zoVUMu{fFvIc-E4d5L!F-ls0FW>@7dMT^R@$pCal+xu7=VadS>3v|hdJ&|7{TTm^_R ztr~0U*__&4=S8eto9}M*Gxn2t&$6txU838ozJ2ANjT~8-X){ejns$+gtS_5P>;fWF zHTcFLkx-&vP@t)Dq0aKVs4_rg%5A4@-d|rUd@|ZVP_6RwznhM%bC*|4LK``Omi2SiT)u#3Xw0bj#7znCm>{nl6cB&nL*gIp0p_fpC_E5Ng zRgr6^I+?ZqCZA*7X4#r%T<9;K>+fX9+u6&@Oa~5im#?hGUV=m|Af5q1B{b7Chmxe6 z&8Ag6QcKI5c-KHsEx(C2=6+%Al0<3z>FrA0)fBEN94Dlkpo&(;M}Y z5B8`4ajXa8T=iG#7$B&GW}4%SF8fbKurUpY zlR&Hhf=Vbsa|mxIl$oS{b1-S8pV}J;szr}Y=!rm-EN#*<0YN2{pgEMJ>EHWlriTmE z_vXdy(BX@9lHy0o&o?+4jzQXE;Ej~XKHBT;b5%BZtAU_eG;h!oPxsc=Zj4lGWC}Eer4aINnuz)c&Z> zzF*HkP%S!E!n+?1Bh?~P3u#KdhK5m;60~J;9u$8e8eJcedfkL|eJ!q=Nd61KYfq|$ zWuZk^+6ch9QwUw>MOWwH8WXV!<`)5l5Kbkj3G3Pu;+0PH^e!034*Of+e8jM_6n}r% zpbDPHrNr@z5E8oLRIK3o--K8tHqO6}<%OlrZ*0)DE8m{9P%rE~Z^C+M4vmph2_;^( zgFO`z{NvJkMG2~fzl)6gvJryW#d>c$Hq`w^4@CkNAREHpjvcP`bC6@?20(37Clye5m2zU zxge+(JvNPm&4WyeI6i2P`Ev_Wf@D9a4f^}OO9`rlYgB)Kd{BaF(J}bX zky9-?=Kq>ThR*5Nva_AqcAV=NX3*R7!}mW{!god`)spLB1Et{AXyz7mO=-V# zmg>Gfnl-)fNg42RmKrcKn)MuVO_?(tzh1ZKRxo#8X>Zv$>Ai(&nZlyk^?%{;(EzY_qlxR>fnpK#bNqtZ)Mx`{o_xf}sZxmUZ%~{cfPYG?!X;=fB&N=s6w(W7|C_-gFI=nia=PbgbjyqOwmw_GhX zHe+>hRZ7D-b@XU%^Q@Vd+$=HQOtk zwe9SxejmRg6|u}|6n84pM!j84HWKlntXei%{jqkfN@+>jxn~s55n59{S=?QnO|+_B z2xIq#S6BPDN=-}|=FbP*uc~gX8ek-jhO$N7YpE0RZBQvKN$)HJc#oq+Ox^iKwepY% zwl&u^B`S8ky5>PR+dk;6k~MyVn*M7j+xGUVQt~CfRqRoB0B^S;bpN&m0Cs!VCY1-P)>dU)yY@&E3>@>t76^mrvK3UY&pVz2H zqRDAr{_ycl%gjwX3;M%MkuK+qmzprvM&#`9yRuPUBdJ(Q(IqM7~Z>}tEv+3NV%X)LKrel^&3j!MTa zcz<`xc+LkOR-SLnu28MWnbTNwSRU2mVN5C_bDtm{Q8AmkJ=)Dc*nNs(U!97p4|mN` zDGlGQi3sAaN@r1*_Ajqct&^50R-u1!_1cZtR7BVA<9PQ%PHK+vjs~KfYZM!Q+fh9{ zZmvpc_{wpWaXe&T1=V3wb%kmrorz=)C!N$5FBYUC?i2~+XXFOz#v3IK#LUi-EN^fX zwRZ1$Dy88Kh%IAytJrSpmcsoNs@0@h1e+nbs?GY&PemMBFqZdBY^6pvOR`X{(t9J= z@r>2gxXO!C5xI&5@Gb{OspTHEg)h>k)Z3|UICJRD)fbavR7y+Iy^{gF(_kO<)STQ3 z)uJP(k;vC+6dz~`R}(_(83;OOP#RtX_&JK_>@!9E9-K>|T68=&5)V%X@p+N0m8dTt z6*@!G-q+ycG&aZlMrpDTzwdngO%NaM+DJJQ_)4K#WmimN6*6X23*~_M!$7Pm7sNfY zY*sEc|6(9$@1wLNHS-PPV;om2s|UVNs8+6m)7a^@xzuq77pq31i`zK<#q*8Q`qFm; zL3U~% zIhIzYE{HT}(OJewjDWMgI;G&9z=hEUg0=^x;ST+Qk-S*u2*sm%q#?V8+0rnpy&de& z?`J=u1pYJKK+x2uq2diUGJnm_uFhZdodCtiu&?;z7}PyWt%~ZdSWDQ z1o`sLlV&QFoVObYno&x_yUwM@^9%7mXobPtpaArx*km>m~ z>;oAzkl$EdR`Gv))^JWuwI~hO&b5R2%-pk-i5=4!u50NzBb|fc>TYrXpZ27qI=fAN$=g#tq>y##jIhD47vCSRfEx>IX+bY`GHimYlGcq0R;EFzQELY;9 zmH%vvHt5)HBpg5xAbSt=AyFW5@@$VQ)_v2&&bFMX*P9&*His z#g*RC&=Xr-%wtM=WbBDli}p%MS{CfX&o;4(%Wb>gaC}f=m|G;v;@ilQoJaQ})D@`Y$Nc5zOnSXKPu?W51ZJpR@E+LcE1w9vY! z7XE%aIJYuyB7T8**R@ENbDO`me(rzr)d#cK*zEJ=^$jI6miv{PDVO^YZRx}2u;nvj zWY>@%Cb%91!WM{4Ku}3);?c%g^8Cc<@V-y=S7v^GMMdp^{UQT_w9vwpNMctdNh%4% zeIOnKK_#h)ls%ntT#sbT(m=aEtN=$(3XYf&*K|Nz70W|nR#<$C_fwJXY(FN>^IBVo zJQ3n(2*h(Bs3bM9`^sX=#h89Tlm)N+TiR&3*PUaOz_QRnZ&UVFvj-voh=M>+Noqo@ z!k46j;MLLgEw!(sZ1gzVk1A#M``4t$A!0(h=GhA7lhw`ORUU|30pcwXR6?_Wzo$g* z0A96epGzBd^?)9SsEcZ$w<&wKl>wp^5JP~VlGH>>!K<(${k3~#Ht2DbuG38pUmK^#A!0&$Ur7&nUug@(u?C14K)eEi zN-z#eq(oj0yqa0mK})y8$3P%0w9wm>z4WRA5dp-z?LK-OLXw(DiTo0Hwe$F3EwD$Lu!tcGSE^H!%=M3oVQz zWxu}iK(qs56cALBnh^0x(hcxx`XXP=JlI>0<7JgFd6YvHJq{5Q(*3rC%iRxDN$ywC zKrkSv1mmDYO5_#6tB(1~Y4@j;G!RG&E%Y{J7eS1?84%}zppw)?O5{5rj+nW_wa4qq z>v4#=54{pGAuZ-BcqbZQlAG!T}TTp^fqNy!^jY9b|acup2lWYu?8w3jExRW#W;c4IdC?d7;;QNPOg`}D*8nb|IbY<;dK z2&#o;p=Bhx&V_Tpm@3+>{gw4O>cxpTIiXZ*J*FXVVGXCfyNp@zb4!p*mG=P~$4`eb zU;C=sUByZW3C1A^EYG=@AU~-)7>JeL(QNeHe459ohPn+(2rabXyXS^HlT8LfzBh$Q zK?O8t)k+8ntryEB<8R2VM@4G;~(RN-OdLq^aBQfohH=9&MfwQFzTlTPL$9#C>Oa&Awp#+x2x@36! zb7EH(Gh_@;tRAapRMbVauxx$pGeE_QW9dm>j@7MYeL zQz+vh$KI$vF1|4k*!#qedz6N~UVzy0xdPAs`J}$TpxBv$#)P!kJqvbE0q=d*DrD4B}(Q8@3pT2zLgm-%X5fP%+trfl5_feC~M#6W&8a8g`Kwh-Nc>Sog zS=o!-$*$;HbFTJeRl8o)%YugWwT-$n_k8}mO?1~ZgwQf(_qJ_a-g%W1KmT~Y-X1~= zqZK=U86%&X$HW`=tjy~^-kOFG`7y?kuxvGpiS^{|@@l$Qg%5kM=A*Odbo7SqY{7;+ zdRfE-aWwW|^$!o^map5=5JC&%5E+3L@m=ci5+6$OrIE5eUI{JqUF?!ZW0IsL5p{S4 z=L&pzn>uL-5jkxeI0nO4v7aqka~F@Vx>tt-y0F^+R@QxATcHz^-?!gkBx%)abHARY`F2xULPU;n zh>XCuGdr$i58jx#yCG+Bn3Zf zz+)GEV14&r*S!*27>C%Ykj4aG8ZTLkSM|uwmrlEvh7kJ>VjLnP@MLt(GWLCWHvVH% z6WuGdbv>5u>}1{dQXd#w@^p$JCQ0hPsXw!i&Ch@GrfCQfImRI}0<%G{hWz-Ab1ZTF zH{C0tg}#ej9cfIkSJ*&UBi!}_`#dkBe&t085jn;oG6MSnWM0a$*1pd2*6XT!)o80L z+g)e6?tAPw7nXO7wJc(iq>DEPvF3SSuw#|Fry+zE#vw8SyUMR^$Twuzz;fE>(7h5` z=)2hUlEwsc)T^3&yoLU?v>C&-|23lA|^PZ zcGTpO=So)Pk$oCMXki>8BXCb<=0cXGQ!VBl>#KV;c(()F?zvEpV@)P|_O8JKLriej z;MFkJ@p)^uwf=}SgoqsD5E+3z&(<~M>)+Tj?{g(|uY?xHA@(q(F~L1Dh-2!Ifh_lq zifITDImRI}0_Sk+V%ej2X8GL{t5#4z*(on;T<--hOT*tNh@)Fv3|rA+js&68Qm+Pg}#fuacNAj?>QXj>keg?Hw~5DkfD-oY0eTTE9 z-e(r8%ko*rM4^RViCwIzhmv#}&N3p^5VhN0N8Kw*h&YV7`UYo~6Gxv=Uu4Rv6XKc! z>lJ6=)E*pBa7K2FZ&EitFPw%DUZD+P8=il_x#)ZU3+nK)*>yr(4^SIO2-}j>VO=Eq zvSEZ)&o7sLMmGFfteh<%O1~p4?hYd{tm{I#dW}f9{%`=|ClI}Wpc2d|B~tDoC${B$ zebaJU?NZ0|z9i~GT4W@r3`7+m3U%+O^(^pFkDL-h z3q5rDZ>^kvQBEN4t&L<(Ky*qbgoM_MYMLm_Xi{(4onK?$LSHm;3X zCO?Z$g!X6+UU48gCKEzJ>&3Ed)}^v*!X+TwftXr%sHT}F>ozDMw9tlVC)gY&nK+P4 z2nnqh%cA$d%-Mr;AD^PyiMQeUHK*7&AKO{%r*F(v$j#ckeY4WqJ3AvmwTzKVNp<}A?v!mz+%bE0&GY8@G=$JXd!oNd z(&(Rc_*kz(TEzp_`_!TZsSPAV?}6_$tZ?JG6Uu3Ooy@uokzMLLjY*Pzo;UNMZEduE z(s{!bJ@v#G2j2N{vY7e450$je-J{r`#G|q)V5N$!Cd!}dN3w!G`{ZiZ;LStn#G_Yk zA8VTVvare;l~4l9`3~-tFJ!>ygRAG?+5hHASzf$I{WOHo>RTd$HJHCqu5^YD7;8Uxkvz^5pQSE7 zG09Z2bauY&ZYPaOXuVi2b~aY-sv)@dmrbDl3V)gZ{u#9 zZBlCe$LyE))2M{ji{<{lVY1^TB;t$Lj0^3%mpwV>lZFsl7ixtv`OSFw>;~McxM+N! zspr);a-$8w8rF5Ie?htQy6tMz_sMMOnG&*P{dT=IySUVsU3zZ^Vt?1{=I=@Q<;Lf& zgpg1I@Abu0s4hR5g@n`e;&IWh?#gwBjMr@lf@*oJoWjn0X(2nfB9Y;=*>qXnrNsWQ z65V{RnvYc3uA)|C?R(~s##XO{xA1=ZmdmDQ-TqY`C{{v9D1r8#j>s+t#iEUuQ#b4{ z)A_Q+{fRMhszqahmEKpbnogA5tLFdDM~|cI`O79byY-D|@r)jG`1;ipv;QZ|?kV@O zrZ?MnsJkEf>V%NcXY^;GJs#yBYmP`jVpP{B`@2Sksc!p683?Ks>NS=9b9$S(^ETYk zy1q|4v&FTxwkEEcMxU9ZCzfs1Eq7ejsq{HFj3r(l_jxsN(R_~8)To3KSiW*=uI1z) zeB#bC?yj@vdowMfaq%>S(4tSqVF%2Ujm&FTwbbm77uKkR){Esbo+m859hQNO_PLxb z2TpX;n%>Wth7elx$vCX~-5qH@KX#1v{Zk*kk5+WgtGLvjsnVy@Xk+xAtjcS@d0?Y% zj*sT1rN(OPS!bOP5=zkL+>%r}ezs-ADSz!t;9LViwdk{SxQx0##ys)KFzsl&wG6F$ z-1=e(8WNyxPl#e8H)c|LoDR}!+Bqz{(x>qR@TyZ>1yi4)V53@$P6!Dljx?Ue4h3gZ zR$d7KB4pmexG>+b+K{Fl3hmg;wXfY{pWxhY5Q)|$D1^=_1qP~znGa8|qTNsH_?6o?L&m&QrCytMJFlXR~H zLA7#Bh-5ZVuPoPEj07U=VKqzfi9y;8J6pZgBG2Ym%B+u0(}JR9VVAUf7W0E|cVw_8XYs}n23ZJ zU4fYV-gIeee|34cF}e*QK`k+M(V8SFV&%a&|HKFChXZ{yI;tTd#z*>oktAJdpUZsX z>?bw*{+_xGp@qb}4Nh_U{5GmaA|dd5T<>$XTH_HNH2NM9)uOZ{HF;Cjyt_jY&BfGG zw;}39Eioq2nqd9MLoKetM@Oyulllf5l%S(4^u+YhW;Yuz?dF^$y=RCq3W*)(-&#Ho zTc{ext2T*aEfW?F)P^-Yr_wQlYEc^ATyD6&3Dd$0X_FkV2OEaBa}1;Q>ZRHPjO0qj6+-wz;Oc%?oeMKKm0!C6vIj7-L|+ z*SBU~Xm3Rx*Kn@Bm$!IUglDW`e{wvN70->}niB{Kh-pAjNor!pIxiM7B8wtPb8bbl zlIQ*Tt22oP0%@UzUWw;;@caXa50ppw)?O5_@NwVgHR+a~1D;}CTrEws?vLQ68S%E!@0U5I=&5KDoelGH>> zKRFawy-oib7h{H{4%U81W zdK{uIq=goG+sUZ_E4K`7905WGVl5C>)7wMrr;lEVn2_$> z$;8fet_n7q0`YWq3El$;DoIVGME)Q4E4$wOynNU|AT6}e+b`M8?8!2;aV42Z1cFLZ z6Dg5@f${29f;}($WSAa@`1SyLC1OJQ^}>!7F)D8Q#4^TRjf(od)zu z#Dug*a4XjK%qtkFKSAU(fOrQ4m82#_eDIb9#PMS5Af8lvu7N;WXrZ^AO|98H^J}nC z1&Fsm`~ZSVQWGhWJ3}1#GCFYwld~R&_@)JVC1OJQ$Cr+5VZJ?J10(;K!HK_hbJo2Q zlGH>>d`wt{>`_Afk0YlVH^?v z_F$dvqYXUH-vLq7uZ13mkfbI=d~gK`Uge%$foF=ns-KsLa}o4P#Dugsf3VKyUuRX| z7h$c?2I@yr>?BAZQjaj+CqqN%$+3j@ zNKOxK&APvQsegf?^r*({uqB_qv+@lt%ayj?gIpyOSkMWo)wqbAJnenf-xDFfBTn_Y zU}mFB>V%+C@7M0FA?Ov=qW0JtFLPi^7Z@1`k;bdnc4oGDN>$y)pNTswV&#!z2kKf0 zKZ4~gEBff=O!4`dS}*uFHmKGq*V1ft*S`NBgy-kx^8RwYbVAU-;t0VKMo!o&ZCB!cFNC^7xHpJfg zNC^5D5rQR@P#a>$fBaq0zX&X(A?)9FV$-8{=`ASev;@@>UoJo!|2IN>PXP%*|J{c8 z$^#OD{yWi5>M7?Kuv3pi(7%WfEMZ+V4l&l^?}GkCU?B}bM{PkHh!Cvn^qVj_$GWn* zC*mt8`1^AfD1SFi{>|7<3GvkyBm`}+p?gIM@x>S<1pRkHe8&a}LI0hI9y(Jl+dotv zeFUAB5Lv`}#kWAPoTfbx)#IRq_(BP#|87HkH$}Jc>&qvp=O}7Je9Z+3LI2%`Xf-4R zotAjp!I|CEn(MQSnEQ|rbK>8LL$xl~+1|@Y{~|)LgmqCHL!0)qJYHq}9+RMd5m-n= zOvr07dknJ@g8n;E{onj@H@lvCOoIM9A?8=~R?r3_1SR4dRah2ZpTe@}W50+HETtxd z7XB{YZTLlCK_|}dO2;}p57&KflIyLUbLnKg{O7X_N(e2q@yRw5+gKyYcwVB%L46m; z#Bbx!-9w2up0O;xU4&)P$8^PCU#Osx)Wn~AB5ebD?(^IB&~rtjty6M`9JIn$&y_e+ zOY0RS4pcoM2ic6)2|=eNs1~J<%>GZ_x!`waeN>CKU<&cgZXjRRcOx4Y8Ng}=M6fr0 z=~?8l7_}2T2cFU|5A!?}tH!m9U%@Q5O0R3W8)r112NTe81K71j4iLyl69ya#cX%NUBD~zRq7$N z4c9m|Jb1VE-&w*nMK+xaWA$V0*sZ3^)J7}9+3U6WS;^fi)G4rAQ%R>HY{yG{+Bft@ zXWk}0Js;esBD(>Sfei{V7uzK&rH#Y_M-SejwZx}Hw^C@mb4o_A3jujq?kcNw8`Xn~ zz_^HaId4tq%I!{O=AHAtHe+2vLhGe9!5gMId+@D&-?7P$xJv6CSOeNd%EK;iU8CEW zT(2;z_7vY|hvS8#!tGeDCHOwW>WtlZdCM!-wc0R)gxaGu0TI}PPrR^|?K`HawB83h!&!l@IoYO6 z8}yp;OwP-W+};Q_?tbpd7cPru7kzdZBxpl;LTiHENYpO;L{ueK-8G$tTJig`ut6bP zbUM@MoUCHxW;NfdFjjDVHg=&7z5%i8QxE=l%rLfY-hG1vX+cmA;Z1V2E3YWeVM`9* zHq?uR@ZCu8^F8^IE-ht;8cAyRr=iT|U`Ez#menia;f;3Ttjy`G?Cu$i+&8g1?=v_z zo65hbR6=7i#u2}%Ctn^~mOb6|)IdtaH5hDDOiop!Ym>tzHOHT&%gXGJ|Tvj`KmpxUe_zkbkL-hb+oN+q=YY0FB|tk6FE zbijJK*txp~f@e)yfRv>Grf@8>X!@5L9bSfk>A1 zayB-{6W^vvdODb|n&!d$ZC9&QLWvFwB3NrVCkuFu#M61c+;Jo9=J?N013|S4HjZSy zHs@f)qgMm5IfpNAVjsmeWgDVW2_@RZN3cP8bFm#IaTKlf-G>jGy_2=HnWRvHYJGzp zq3YeXWs?iy*xtICA2$bVX7B!;tWXIhu1$+zpjuz% zMX*exCcayYD4&S^FdbY#0r^8C{e^Qf-RVzmuXp608yu)H+S{D#MYi}%qT&% z=+Oo5I`8Sv&(1u^TI6WLsDu*qSb-hiw+8VY6*J0@I%HCh-j8Irc1tY(hgIsOtx+r> z{JH$G)-pB8BZ}?5@leh!VdRnjjN=d2OqO>h7BEOCQMb}Gwk+wayz?6#=bM8A_}&W6 z<_+gZ8VIU&I6dr=x8j~$cr3mlWHWdSAM*XSdDgc+DwR+|-4n$geK{e^RWVm1*ZcEQ zWlPkVvUQ$;pjwTl!*j~Ew`KkY`&GFsBX}wHDo(n#P^A(|Wa$;jHW$1uzZir4s!{xK zE^j!x|B&|z13|SGLvOzs^+~Rjh{s_1(S!M`MvpB1{o++Bp+w&8;jHkIXL2(I$Mzy^ z2k;K3B}-Da%LamK?X4Hi7LI=-Kii4pRhgAR+-ZL{7O-!YDW>f-)_(0(d3&|Rh8CO+ zd&NCXcU!Jg6nAeuntwcxFZV_M% ztR||aE zKNKpVgz;ST>Cg_m#wlCguC8(BhgzFL3m$zR&~p@e_5p8l zoEgB|6gp>$d6;M*s8-Db5o}9BMt0*Tjy{K+2l7*uV$7d%Tu`Zm67=i?X3j@GeBQCv z^8Ql04FuJShc~c?24-dxBXBVtIK20r%|a!Vpyv{jR_mAHZ256pw(=*=22HyT;W^IlRem1ba4(U{w+%_U|J+ zZ~u9w58s<*vQpY~Po)xi%+sS;k{V1L%zZp;mATK48wjcu{Q}OABh$0!QFzpz@fgh6 z@(RjM9uPD)aQUqI>BP*-d7tbu)Ss+)BqFK=B$p(UI(X7MFdESr5*79YUE(RL1 zO9^E}BrBUQGrN`puW>T_j^b|j+pwK|Y8eQsMf(Dr`{WPcE32E>xU1z2y@V3!p|^KD zl#$Keg1uzl&LDn2DjmBxsj5utqFS_1!#hRA#`AwOKa+EYmz1f55`*(cvBOd6S#TM= zy6bl-h>u!fCtr&Dp-_Tq(W4o@ig-PU^RrI!*}Y#BDxn0uvV?CaRE6D*moiJ^frAXk zIn|=066^=CY7DoTWgj>7aBsutLy7sDBH6djKjm*v@#?Pmk`cUMgo_fjZlQsoT6A=k zq;0S_?t!L>mP2>u8Aee`G_DcJ>ZkiA59@`a=)7A)xKrhDrI>?eAgC6dC14l9c|QDH zY$@f$&J_gi&eH3xn>}!7M;6bpKU&XU%PiTZfy6A=r&;nuh^Y;aqD{>>w+dBWuw!<8_#L9g3k=DhC17nLz9 zySD8%T%S{dW&!RF_731h*Ls`Z2aGllRLgj0V)Jf)Zu8%FOYFqChWiYZpsguMmeFH) zlN{Ylqt5p=5LAoyF-Z!5Zx6Vd&dA-O4#C=nlzSw!x6^A}_-^0cAYQs&Mpk@$Mwv<| zL61ksZr4B_9aDx?3^{Ees207(m89JrM)SnLb}Y-jl8j0yLB|z%cQ9}i53A6HRa;!i zKu|4uRSfST=lA7vGfZPI{0721Bq>+bl%V4y-0OQZh|gOwmsNikZXl=@9kt<{VPALt zuCR{n;~qFIX*@glWLI(=ln@e1U|IZbwebzw;(2m= z2np3f8_8dnPqsk`A)y48#qU-d&`Y@JS3*LyXcp2EA}5r&u@yj04|C@l;q=aH6l5?ezoakD~(dtKSat?n(2norLPK)2I zHj-OVw;?1XySk0!zL0E#5<)@=EQ{Z*Hj;ayZbL|@7R`EEg0=^x#qT;10{@49A%0=(~hq^Du4O1 zPXE4haJfz_>#7>;==)rjl53i(H59L_;Zw@+Lq(N<#kk6$5{%u%oR`*yburY09@Jrgl29{IesB*|p8?$kx{MvE7 z!8+BVS&$^>aZR-h*)nmr%Uf7@3)RhcTsO9?Q4N;;`IW^g>;zLZI+&!7& zr0Nhy9Uy+%Wa5Q@pb|=ScbZ|Ue9r^+F?9jL@pwVab*{|seOPWFs8+U1*G$!$_hJQx zRs$mGSV64`5OqH;XH-Ioiq1bxLw9+xAx~=p;cd4|t-iT0Uo$+^Kv1n*TPm1aID4~< zMV*0I4MYVX0)U_rN^}`k*IaRYZ??KA+E{olx4QStXx_xNgMpx00ZWFOpA`0H!#!&N zQRh=l?d;M;@cn|){6|u8Q-!r%SYJymhTjmMHo7x=GsTrvaou66lhBQgajXMG_*rKy z;?y+eo1r475=!9L!4reKuzPdefS9x3jhfCWfz6C=W+156sa!^^VLi}*@wcl!N$DUuj+XqHmtxMc{=D6d9;V7b+ru`V&0|*Zwo^OA_sDu(U>#$p>C978SMkU_6 zPI^uWszv)TybqU5_y9pAl%QFcr2n*NwM&mSykU@$pjx!&OVUjsIs?%N2r8ij&AKFA zs(V$b9p}OS%kza%f@)!Qcfa>yUQ4kj-u3g+zU3{&jy`;B7^&&;L3^bn6&lf7tK6^) z+w(NhKu|53X=wASeKh}a{w&n}kb$6DbhMMC7mfq8IfEv!Njo+f2&zR#S4j%mUqmhQ z&lTpdy${C-fAsFk4!FvU_NyIxN}I2j>&jY0nj!K&qe`2bpMK5;eduiP-&W-MYw2%eFs4=~(rhL4q@< zAh3^lwslwd?PL0!)WDJls%_)QLTeL!cAx+-L3jSOkZA9b&9*Ij&iZKpo2qi z`E_s=J#RZsPnYl2sKqdj43oX(hqo&O@pV~Il>;#v2r9vhQeu(!3^{Qc&b5}Nch!Bz zPN}Wk-3% zT6)|3J73=Y6ysP4*|i(-R`IAAsQ30Qo!`nMvozAPi*2yfu8E%Ae`mdw@3wCU#JnDo z`msbh_1LpOJy$}4*%gFqRcG^Xpa;e_20}Y;QSCNfQ>ykFVj!s2r*<#&Ha}aw5fI9X zqH1rK*6REXqjj&QZ#^sbnpjWwN_dEw?rL*RPJg~G5Q`uV3lK|zpc3?o62e<}G72r| zlFO_3+87;Vp0mHavhR1;jlds3bM9j=htQH^aW06zA{8x$U`__7flw23mLW>@c@P!J< zRY>AYHL>|{J-hu6ZIyFIoAvC9Ok+$n+_uRz?xI)N9-cs)1A(BM|PLzAZ;#@01cFmvntIbLd z*0U={9L$x-G{z*x6>EDG2BI+#RFaxVX^$O$w3X$oVI4sM+1-P_2rfM?Ad6wq%6wVD>vFN58@vsgoF}U7Qb7Gk>3kxQT5z)8$v?0bQ{U%E59LR{jV9Rm&p66QwLAB6E%Kegh;a*ysQAgyvN!DXfNGO42rC?KbJsqBf53TQ| z-1pwiH#bCw`S*!P~`DLJ1rn>$5uSyf2>nyu5Bv z&t$zUZyhqkKu|3_9?`b-Os3_kqU!o>)0q0mI@jh5Z^oKjww}p|s~4m_JesjZW$S^B zZ$KzO>;!^J&?`!$T;qIdaaVmaKZM;G(ZfI>Ewpef>HJ?)_O1-J`A#4n0`UO|DoIVG z+%MVm)>(U1tu;%xz&h88x{wxHv~6JT9UwARZ_O^mTIX8P&Z&u%7CZ)#=Pliwg}<<# z^@&!)$VJ}J!<6=D1H^lW=4?6;RFaxV$?g}3{LBbfb}fA`1A(;ALJx~Rt<8q?#dEkM zAWkO}RFawy8G-c%5PANDe9XSF^{h|Sg|yJZT%{a?8-U0Igd-4Cl9~`Xl%(7}@2U-M zzK~aLwaypB0tLgVr0*^t_nw0)U=+Cy15Lb<& zjO~mqh`(d||Cyj#*n&u4`~R7sTG)a}VEg}>pjz01NMQT_nV?!Yt095UDgI1QEo?y~ ztan(fjCEHaksoXis)a3xg!O*Op9rdjEr^75j!JHGO|&^m&<54Q7EHOK7dAwj3xaB4 z`-|UUMb&Ig$#(>Hv+n%H>{q6W8P6u~j?Hg4%Zz`JWNM={(0`Yt=eIJcUjl-(KKWbA zRD$)2bJ1q|E19b%HI(moV0+Ydh*m$?jMVlQSZ5%p*5a4*Om*rtNw%?i?Eua1#RBzG z?%DcThB$A(zrrUjq+>r_tF~RD+pE5P<)4l4e0Tk+0a|~D1#0AnSq5V0{l#&OANuPA zrD09noz~i`rJ3Pb&ICs5qFT`dFYIqRp=+{NpH4K_Cfe9)(`!sL5LByQP@t)Dq0aKV zs50Qy?bz~~$DG>Qx2LTcl~7`5mo;u9*0oBu(XD84Ep%K1EyHMc13|T}Uc6%(^rMB` zAi6ZzcYIJBfxsh5T(?mg?&**4)0&4>R@^G&zum^Y5z{V|e zdez@~r8OtXSG-6Fd(=Z5Nvv}@7J7OYjAMuWEkhp#s-k@AQR`*9PHIZ7C_yE^Bdj*Q!h34Z ztnDFDLX=VK+mjY*N}E%HN`6OJZMeYObJeZ=N}_})qn3!=+8&gklHUak$t3wpZi$FnFS zfmyii*f9Ax7jL|vH7fZXVT}V@@G1ODO$Zvbur*&;>LlBs1eN@bu-b5hzS|hu9c@rT zlu?Ve6THbm2rBs}!pQH2^@E3w=#m1l0iGuL-@z1%UTBDmB)`@k+zbC%~3CBm8_MlohdhgVU zp^v`)g`iq+MP?*IerJPfiE?M#&3}o5YKh)sB@PYWWO)cX6?7OknNd$t$FcKZ6M0ws zM~GudGSNDj5E4qXFM345-z(+*1jH!QU}f;$ntU?+LmPsiTKN0s`gP^%Ht&Gg>o!=K z0NTFEgpg2T(C#BT(b(fX5Yv5^DSL}fW<4j5(rpNWYM~8trdsm%^>2Xq2*fZT`X>`Y zLWwG`j_Aa;^yt<5=Ka-2kgGMhGcel2>GAP-NO~3HEBsGxXpdt+JOyGg5L7~m32id# z#Ea<#fyj2CxHb!-_K4qMAgI>)&lyyVZ^G(aKz!GVYfFIW4g{4@Vt0nDI+6L99S}vT zcGfOHX@V-qm%rO%VBr;zcN+>}y0=o`nbJX5J{SF5L7}5ni1F^ zuF`b1KSVxuURh2Fs&!>iqMoZ+ZE!a50b)QhK_!%+IfQ3-Ef1@)kgNQ%H>U*Ex|`#o zo~u0>lEB7dAf5w}2M8*m1kIr&ji?c#;ONssn!xBxM)O8zAGi+(1debWfuIsf(2T%3 z;oDWzi4ggbq^g_}REy3&uv-rheSx?R1eH*NW(4|fq>t(Yksr?LXCSDSaaM~2VkretL0&xt8%|K8ICC22esT2Kr z;60gh6U%EQ;%oB6o*|49RO@*C8v3ku=lcjC<^$0lhVa z;XIkK3R?{X)yjLfhCZu({ReGS24Wr%?m$opC88$O(uw-Z(Z<`L$?6e^T(QKO>Dj$F z3&XSi6*FD*$afc?0K_dI;(;ik#G0vu5-;=B(g~ztcbMZfwLTE}^rLNMN>DAYA+CDl zMZSgr@fZj%Acg`#CI64Dw~ni-`QE<|ASkHV0g9j~wqhX)dyPma3W_KoEs6z-V56cm zcK2;}cXQ4f8@s#fw&S*2pBX;i^SFke{>966z0d5KJ#+27Cn>S@{r`ynrQx|@DEAOK z?`t!`}iY?-PWd96gi^F=mmH1YYQ`J9xbKs4Y85TOWxd7o>A(FYj zaMb%2Hc<%g_c@UK-4xs2+JuxAZ~CvNYGcOe+@^((;a8reLeYoCF|zJ z%@wv|$jVgkbGN~=O}2}x+M6>|s}*;=W!KJQI907ZkOp0%Y%rlpL1OIt5J<|Kn%iF+ zp%4p7WI#euYkYHS8&X=Q3-O5r`#pPeC%sGNRQ2s@I+RPbLH)gg#KTEjVY0rVzOqfC zLaZ;F37Wk%wjZ?(DXr5jJGB$$o(s^QY(IcgRsRPWaBYbV`i(3|giU%6$!EstZ#c#% z#1P9YXx-QvcYfZAlomb0c3+`H<0bkk^P)Lb^|+Y{uec3*{#TH=6I78o{NAHyYyB0X z#Ir1@>}8FYJ8eZui+-`WmDt=}m-K1%+jFX#XUKx}w`_27>w*MaZNfr_Khi%a=Asba zHf6(rF4p*a(iWt&PPe;jbJn!Cso`vLV@_4=GqWN2lMP-UQjqAM+n)LSV{W*8+*To4 zh2+5F?$+qAWiwJ*r!#l!$nbatLtB&boT}Q^&4CleY;n-!f`rZVX!fyXc|*+3FGz`l zVmIA(LDpEvun8$G<|krz_TPruhK7chNL58P=Rh@kTlAP#kO<2u3U$tAxw$S#;oEAZ zf$gp9hWBN+<4Cs*SabWj;oZq?IJ#sSygX=%ryOPbNPk)!y6^1g)+{H5Q&q)!88Gjf zDR#M5kXT&l6nwY((6Vt}oI>1m5_`5kxNZplv=u3>(_PQp1n(dAcJH+!kyF+6dYO>* z&=fn0x~mc+6W+j-w%uFgwC%1Cn%wvNwJFa3E>0jOv^ZVT{en&Iq4TMD?(@3&3Z{ug8QeJouRg4Sb7i#M_cjo6nn zG5YoBs?^=N-?L!k7gJmxz7>bzim`&Ir5LE9sx#U2p%%CT762Kwt+9hEjn z%St7BZG8`2+gH#Js~V#a)K@4ip6B6j;9TCT+)?ejD_%nHfl5?dvlWWeS(h7JAyFZy zKT=w!`!`|}Y{?mtTWy=_iL_>@L~xm|VEt*_z99Dzii=X8r?mJUtYQsS|4VWoH#$Y} zcG@OXqM_w9Ej~2Tt(`2u|v zi?50^P+BD(+xxQp)0^e?jj5ufLFO=!-34N z+MH@zke;xs({*$5V$Xi1x_uf`ozn;qz% z)TSPs=*DV~QCyS~zCF{yLeSkJwuyXXl^Y0an{9FnGz?b=s(L&=1NKb*s{L115;uiY zN7SC>mUC2fYN}H2$A4{4L3H3Ox4rr}#dj$YaZmK@P57!sq{?&LA8tDb=3{2L?K;#~ zA*f0{$NkawBJ9-AaV;LdWLn4MX%&CYieD>gqDRm;x8I^B(g-EgeC)b!!d9G_ z<<@9^ghEi2dR5NjLfHE&Zf=fMt(23L<*CZXcVBu6yiV6w>%?Z|TDZlIF2iYr67&jn zy0RPH*|zrSZoSRxD+E=k=Q}&TuFZCCp6RxGDC3PTWWnmOU$x)|TaeavdSW0pR1-S+sYX;2ldF=7YhpsH+)Z;;!_L#q4G8l#p~SJ9&0%?x%+6)lRk zB1=evo`cO`Owu-_ZAHu$Sz!Tdr>u8R-IKy;gc3*HGhkS_8R#0w7L{6RAn5;llzUe{ zTp_56wiPkQOSGt>-R#}jzBo=Jlu&d2WZz+Mo;s_@_zI# zREz~rXsewD=;3WM~`ceUd*LWxdW zvca*Q83fmt--BnXc(L=_dg<2-r=|o|QAZU|=ii~McOyH^=Y~0_5lYZqmBiP?$oA~T zc5{QHU8Q`dHaapT=b_M-`RM6 zTQ+z<>wukGW{7?v|v+ncSKaRBcXZ3{F)iQAKNU{=dESmg3(L5%7(fUWy9PxPiTg`lbq z;%tJxJ-pC0M)s<)V+jmDPQ)uQ2?{|~^8$0AZA%Xvc3bw`4NFX59xEne^E(58Mkw*{ zP!7cE88%!nR1k}AB``mWff#dRyh2db#^4;NR8K=pOcF$t&j1#;tUoS(JPv4t5^Im= zK;^`ixUR`SLAcH6$6kGjz?%b?Dg;%P>XZZRZ@6OR@B~5p_U_NRJS&55`)!3}uN>Ik zp($2a8IJ?@=RolOrZ_o10Rx+goX>2CHG}&KV*cd5Y)NxxOl*NbBb4YZzVxP@Y=G;6 z;sx@5h}5b6UzYU| z#Fy(mS-HIHhP(T3C~pI5PhcyqA_ zn^Ak6A#BdS3PDxsRYi|nui54Ho9r|3)|ym!*DMtK`e)+lUSptw zeF#SHk}WEB{s(RE?A|~(01Dk6>=)Fa@+Ii+l+Q8Z|{Mr7u3PDvTE{uVo znO)EnWs3@OxUOmE8}Vf|U6{3hDolCT9upc4!e*Ii;5fz)yO$e`J$k1?r42s#y`-#H zTY{Hpqn0({pM9G#8lgn9rD+f}#|MvlNaFjERoc(_m3hAbzA8afy9cKN8{GPb!p&b(i*d7#R=j~)eG9DDaHBI4V@K&s(ja{fv%#4X8!V? zYmMt@x~iA)YE~cCc33JL6#IrBXwVY_R;R)3f16{Eq*#0|uF85`V{CFSMi7slFVGs5 zIfI7mzKljFQ9np9e#WmH>$^(+P{1XZ~WNrm|n>tI^PXhGPuT{2f5-ycrwo@L^8t!^I4H}*3 zirpq=BCW?_FIKyLFuHdve|zyL&cAstS&^1*n6Y_+w|42Ci9D)AT7JrshfXzLPZTDT`c_vp%;r+Y9Op~Uj* z=@7Za17k|b=f|%e1L0(V6)(Q0gF;Z1+G>xu4}crnthoKw4va=9@k;b^4?E+IYmUoy zemrdeOo(`ci`>H$f~sf>7Go^q`hipV|1ebxV>CjEUgy%`N7E9qj7BKY@@P7IXx$i>jFVn6?Pnk88Mhe!ZQM^GsEW3E zoo?jNo{-se34UzTkI@Jv4(ik4MQlAhpCi2_bbC+e_@fVAoGH#AATC2yYO4)Nivhob zahSMgAfpjV1nfW;eToQ%-5jeKS-csET@w*t2GHB%B#n7MIo(ql(0r zC~;-KXy*YA*s-2;INv?pU~!8i!&U!eg`g_xeB$(>j$z>7Fv3u6NwVUJl=v>{)f-n^ z++5&`Ej;AZW5STsz&k@Zf|gKgPp zwCmYhA*hPFggEV{&t4c{(;bIg?#*a~5}l8WktQ!EOnxN&DzVr;xb9g3b5F)A1XWR& z5dH0|c0rfcrLk4levC#avG;TaeCyzV*S<@?+FfD~)Ona{7!{JB5LBhQ&-#!ZkUKNm zut+z6(Fi3H#7OM;5L^7XSf&v>sxV8N)s7e6xd5o+y#A5_Ca;6Bee*1&E+O{pe`n5) z&2G=z9A5x5LW%V5nZVX`#vALUU%hxzghlMsc)j~)6@sd$ONcM}z{1Sr2=E2f&jF24 z;^Wp#@x%~&8O@aQ!k><}WZG`gU+Jo2l%Oi=5;~pV!@{h?l?I#*)iD~Ogzj-B%$eQ} z8+get`nutkY`_Cs9x<=HLQoZT39$#=titR`naX_im-0-Bkl*e8I}?6g^TPSri6V^( zQAOBDOG}=2wx&W*6?F;WqE?03n37ifKdV}dMkw*0X%?8owZbz``pNszu`nCb`yG~# zX{r!ZMO{Ml&_6O~9jAW4sGUt2jZos_k4*5~Jp+q@t%&wCr`%2K4M2X;!Bk1 zd@d7)U#p8FlI1(xxi>myQY--RL$E?n6?F;WiNAlss+=x3<8lb25lXB$nh9&mIiZD_ z^u)une}UhLBB&n{t`Jm3T|#WPH02wVd|V7$4US+mLWu>(GGU{a1BOe{euoo2 z*@i0~Q3^p-s{6$A&oCrrlEEZ6n$ZX)%;tuuhD1@RSE+N)!U#Z1* z-K@;ly}kp~aVW7xjJ?e1>x-TPhKV#5Hm$>aI#_Y%;)NI`sEWFT*kv=R7OQ-xC||d> z5Tg-F7+z$-yK|n{|CsEv^mDGwbp9W3ce}C*K~>Zx#4ei$YqBZ!pK$<|Wi&#G^{=zw z#3+U-F7li6l36X*=HgXMY~-L2R7G7v>^s=siRIqAf#1$LFdCu6;U`(J=T1vJXeQs` zKBhRa=fV5Xd21bopepJT;{EDCb!IWqfPF{TWi&#GYuB@2iHQroa+U9JyLVM*k2)^E z-MgA71XWR&5Ho8oRb$WQEJhH%OCyvRd@KvH-a4blZTSw@=}0x!>eL9_+s#cOsEWFT z*t2Gp1ADYJ75`n~&S-=ZUw37}!hv;h=3V&?*J7sw`|RS5mzH@b1XWR&5N~8@Ran2U z*4U_&C!-NctY4o6ldsi4lRnZDHy)|N`X>A`v~TO95L887LX7ZEtjyx(6~eg}+AtcS zM3oI$@V$`(?i(&Wadu@p=DvEY0ebo>1XZc-^ZBzan;SCCko2J)qY+BTIbM4v+G4TN zG7Z=Bo~%QZ9e-HN8>r*7Sepd{?svv+C9;vagy@I!_GJHKfXkXS7oyy zbx#1cTPOXhQm!{EKBP2v@tmX(R7G7vJO{6OvD~p`_$>V-pb<)(=$Q@e4*B88YokRP zx3>APcpq~<&taEBP!)9v(HoWM&5E72;5+Sh1C3B3dww>ov22T9j}8}UyjbVMuC#cG z;ZC;{f~u%Xi2VR`-Ym8DfB50D|v^^oOqsK~>Zx z#NIotyx8fd7jb#mcc2kU{I@F`&h!M_uh0MH9O=a>9Nvw$zZ7PapepJTVvg|5)@=OQ zTr_!AgwY5k?8T^M?28uYFh{<_b$Q;J&04nzI~^6fW)ml)D(VvAySAbS`}fN->}yhn z(Fi46mSw}Nrp<80W%&-byo3jPR)k* ze$KdbjO>SdVa{0Hpb%`fqpCts6?F;mwSC;3{VLTBi_UapG(ripG1)NxTOD-Cl%9Ct ziaT5J%Ml+wtEmuFMO{Mlmt?hMFHGuT(9hb8Mkoxecu7Tr<%J)RRza=Z5`mZ4_ zx1K^!6?F;mH8ISUO(^%?@ZdoMMkAC67in~;;D9|VO5eTq#+8+LlVe!e*jXW{N_C$( zr(M{)p3@B<+cai0LJ2uvwC*x7{~gA(o2@ei>Ns=^n!1FX@f*gvpVRTn zmrQ|1C_zV;bvmEt5$xf5C(an85lYbUXwe40N3!S*23$CDokCC*bqTS%aaIKL zPB@5bHg5nLp#&XW7JV|dk?ie>RXFJmEL=~LnCZTNaj6XPE=LJ2y$Ec*I> zhqIEVGw}TKYYIVC)Fs5)rQ|R+uG(BoZG97Hgc9nw^NH**HoeGbJeU4lA*hPFgjmmc zqATm3nu-1oUjdC!f{tM8bnb_{vW`)~xV6tWg`g_x5~2_JS}=PtCk9K6{RK2a2|DI2 z%IZuo8@#>&j&(1@C_z=!CB%2_(k|@G=@wY@m<6K|O3*QH;Uycpu;*_Iqg{-ZLQoZT z39-M=fI!yaYbiWjy*Q&0N~q(`FBS)~dY*ZPD-k6Wf~u%X2p5eHV4J>QHN@91&1i%Y zbevnv12_@D4%&!Qb(@w^2&z)u=UrY0HgxJ#gUgk2j7BIyN8fe2{aFdjZKyYHo4gR{ ztOq(ffz}xD#JL>D0#|w9>6q<6Bb1=`U*yBCH|sa_pkeWWD?sNL&^ZCL6vQ0iYrnPE z9YguhQD%&eLDG>wb;Mm?+fS=pIf(mu7iTm=iO!CxP_ALus z_jE?Tr(>0QQsS$qUOcOH>^P=wdFW16TN1M&V^Jq;?lrCe@#9e(yBTv5uLez0h@$(m zpxMtZST%A2Qd+!O&Wd9R2ToxMTCTw(eBbv|KiPUDz2f-k(%}Sl|}NKFmFXV@{TJqr`!+ zS&--$jQ?Jlij)>l=k0x2=#O(azR6rSsv27;8{U2Fj1wCaB!ax-m`&d^IH>!kTuQ8- zkp-c5gYedz8Axfd%G4u{ogQ%pFF)FlOH~g`Wkcu^k;b!v#Bj4Xb}{)Z9-kGZr$o^` zSrA(+2$MU_MoNoWdgJ1mYw2TX7xk}R&Vf6U+YyJB`v=PeWW&KGfp~iQ95fd*>+JJ7 z;q+<$h!!<3HJb}Ej=D7E#}F@t)VDH3ldPbxsH zXgE;&J$*E9v}v103BQ>sFxD;#-R-6zrFFVB5%;x9)kgChvwStG+WB}4oV19-gmY61 z5Di-m(gtRY;Tc~2-6>ISQVQI0j>3~`rXi(uy3rFKXi+AkdE1k52C5pcBn75EjKtba zW)>hK?B{ERO~>%PLt7fCs@L~1V6!_CTh}Z|JUOvgYiE_hpE;N#C4QYwfz~dO=(lG! zQd+E|zjRt#-*^;%JH;BQ%H1Iq-tLb;He^l#;@;q7Ez@NLPYUd)5UUu>SIY zkkaA=u3qz?+<2 zuc&AmD$%=s9Q5<-&wr-PRpu1YHbKYk#k`F2NpQ%iKhGUA8>q@|TpGAw7zXvoL6sQx zs}F2{I*^B#>!uL2O;B2#Y~3jVzVm@RxkV&U)zXe>;L|Vy!#a*fl~~fe54gV`$`4st zDFkg3looC9Z9L>29?H9h6#=R$B-Vd8)QrRz6DFZb*iG*PL4}ifNIy-Z1Z@+P7GtR& z`$Cfs!}$jnH;t-7Y|?;_ip03{Q&A;+cl3qMCdu5tcLM_@Xbq>dIL%{yAGlO1nZNp3 z&p=g0tEWLBF;C5@!c0_&((~h?{+*$m6}3>>0j=Sb7H^hzePBYRVO(czuGH$hHfit$ zB5**LIj9l|O%fn*#Xx@6Jz61X4X3o2huoBO`or{sODk@on3ZUtU7Zcs>Jc52f)Ov2VZnk ztWP5I>}c(yW5uFBvF>4DhVIS*-%5>-Lrj1t! zTH7ftW`D*WfKAw)d(<6|R3+naio> z?A4J#{wTaBP*u0J8Q^!kD=vAGgDTPFwHfQuDujE@sI3sR_EB1#w>`8Fd-OY)XIj+) zs_M``13uRb!}06Kqe_(XHDf(mhVk+?=QK*t+DB=z$L|_5*1d2ThmbQGRlW4gfIely zv2X4qREb)J%-FdD;XLMLF@>PDkJ4gyv6^PA=EiXT;9^mYs^&D!02K9V#>J_q64{l^ z*zVoo{K_c{10`tfqqL}3Ix|-4SU9(;VPT-EBP;_x*@ol$7c)>LPE0mqgY3fiqLrr< zg4RAti{A65X6$-!7_WKmq=BkzdS-xm^DrFpV>YV9sPIB;-G^ZQi`7wTHLZP=*6A7_ zGGkiT5I*s6ZKaMTF3*6Sxn0ra=R8!2Iw|ICJ`3blCHgA_t?iT+y-{K;_`}ISK528m zd=EFaiC1EV(Cm$(x9#x)REdp!YOv&!8h2dYLK&l{wU3U4iM4&}YB0xT8c$m43RE?5 zdM51d8iJ9{$D&GD#8hYF{5*Kt&cX^oYagY>8u#hdnNuAP{?@86P*u&~Ovu^P70*8y zk1DZtp(DF=!jnIDSfx>d);>y$*;L$-Ro?2!&&00OsA`hf1EB28P~3ZUl2}#qCq2=7 z-qMk+Ebq-nqH~);c-KnaYT_y~87>e62O+}S>qdBrIWxe_1 zXE*hfptX~W$22%^Jb$;gb%FFzSQ;LMSLxlT1{&orRC0e)!F7q z5018$N*$dwF%zD(55YMb=b=i3F08?tdu#k)L#7b4wo_W1!`q<-yD>rIV@flms%$YM zCAfVMR!>=gDiM6sgVjCg$d`PxP{xF5?W1EaI$iV;50-kxk%#vw3{>?rGz(6x2*M?k z#-d8}J>7~eneW8Ce;w8+L2DnS#X9n+G^8 za;F5XeG0AXIEAsN`)l)!s}{LaRl>iSFwnj$p1nL3Rl;p7V?FX}^AbN-=qW*KAEm|V z*%KKXaIiMt@3T@*RkOtWw6yCXxOnFbREhI<8N*|>_`4H>43wa?kJ93u`W0i1_tfIm z9R?ey>Rh=jC~Xpg??UWX4M$dS#;#rP-@A6_uRjy(N#OjruG1+PX zszl2Hp{($HbMAR?sYYuxt$noLS9}{(3uP8&7QF1~l^RvizFw7hklK~qKUbJ1c8pgD zTKgz1c8&1p%EIav;eEd(YE(u0dR1cenGn`4-jb)qSt|sseUuh+YnOyD%Pp4t(6Uk* zRneYXl_(q=!diE+;sL9hxKo1GK1z!-i#vs|I*C?1a9eYCs-iu&DzU;pgf$y%#c%p{ z(NlufK1z#u8Q~%9NR$;{JttUCRkY_;CH77VVN3HY`5RWjKnYs=C@p49?h9erV=TGT z%!&r8qJ6I_aiv;UcG15GzgRh0A!zNRwCM3l=*mW2EX?=CjWAFZ?bB6>sG^}PR@B5K zn~e%VYdfXIT(!hd);!Xj*N@p~peouotr7_j#0b{FllZYuwx0HR(<`C<*J2gKnC>jS zZ9hZl<1dxHo9GTr%fxEg*0b&LY>3>A#IaU=d}o&&a4&RE1$?(01Dbze53ttrkPeME^+V&JwMnC#XNO-wfk!b%s%sx_^F zoib4&sA_zh9GJVKDgJwHy&z89=+ACB*FfKhbx0$WXm}(C7KFQCTA6i%m_IU}y=c%H zKc3mF5L9(ptR^>iZh>b~B(ZF50(;@#1>YT=gET^ky<%eOM!iR*3`H{9=Ll zVBrj;5lYNBmIIBfH2k%CwIE6*_h-AqM&p}vlNExhb_e9Z$wUwQ)=Cny3ioH{Z?DD? z^;+Q+u?BoYmJj+Y7pqQZ<-pQTKG^ZYGPM7l4dI{LVYTB+1rgA20J|_~8MX;@QX-UC zkdOn5?R+t(yd-MbB(Nd}w_U9_Q#oJ2Yi=-4zBb2Zg>x7rbIAL&xBtp8F!r7bY_&j8YLQqvTu|m4h0H*ATs%1KYm zd9Tw-WnRF+uHx(^5~0MvHEGZx!WDZAmc*c$XSKx%U+{5IltNI|c(MNcX0nDZ7Sa=A zKW@_IJM`ve2d^r3PDu^Qq$mRmLK})rTa{b+O4hM+?LPtvEwvCiI%NX!S$6N>eomD zDoxYo)^Eydzi+A#RJCW3*bm@>55AiseOF(9iB>+NDSr~zl+y?$X2zyMna4i(c#R}h z4_~ES-|4`A)%Q^dsw%uz^rUxejam=+#0j|CQak5A=W$sz?Gp7Spf~eG55*!o;&-^+XEc22%bpyH=CvCwxUF9>~;B}2qgQ0serx8k2 z6su*!pW9=?UfIqgZbrg^*VbqiHcTO?ind@eN7%jx)ZJDR%lsV5X@n9?tor>L;Dn~0 zGL19;#z08(IQ+eDph8d;ZNcJPGUr|pIWitE_ZrA)gc4s3>Cj_YJsg=Ly`)*GUa%&7 z8OGm>R|u-2Em)^Jw7oA}zqAZHOpoU@LW#^{>CpF7W2_%1y=1a=99RdO!k2+P6oRT~ zn-?vrP=AQreG2DV_24u@i2$+kKBJN=dNh+>vc67#D6#n+hKvYR2&z(RNkWxGh%5FU zd)5o(G(w3B*Tmj!&Kl0ilQq#}&j1L>Ey{O)^j8R~qIFul$=n$T<(?Mh%@+78b(azq z#OnTtUmp0fx@;ddGm_w*y&b=Bx0OOr6>Xbh^_jyEnCEB5(+9Ou+8`y4pG$|PqkM2p zC)sKfzb3(yKF+*Ww}uKqRn%j|nuZ(0K$q#vpYCshgI)1n`MY@lpAqgf$ zdGW)$D=Gw4QLhwlWH*MxkVG%u<5>m86Di@Jnhu*Pbi&d-q>IKp8~{(kg7~{?I)$Jr z>foZ+pu=$35FRA@kbfyp14`sIONU9WK{&mnd>VY3(GQ&K_25%lpHc{_qN9sqFIL~7 zu&{IwUg5%VU9u_NkxYW1j?0Bb0Cu zt7YAu+2gcM(o0U9+65;s6vgsW`Y8leQI`hG31IKx{jTX zC#+)>f~u%Xh&Qr>9NO0Z2hF>5<1|8vG55rZb+H3YHxubsPH#9IbUcVlr*~Bds-i9- z_Qnl82*=hR#3#=}IE_$Z@~aGZzqL6|KP}&6YQ!Ie-J2ex#nlc9K~>Zx#IEvt4#TX9 zPw;#F4xC0P@%B>&bld5ULt~_0jm|y{x4#tPzmhx^f~u%X=ydxI9fgKf&3We|tvQWQ zVuD!R|9-FsZr?Az2g^GigTuk??OK6j>OMXL z^PqFEATI1uMtCVf$G^l1(9@qGqC$efJv*9H$DwJq|to13sl^EzYD^k7aSl$dxS6AG2Chwn0^m)vV$!oJs; zf;!ty3PDxWC3L#L3TABGy(xI?ct=hnl(_UT6Aqg+#?MLe-KS_hGj=|DJ09QFRw1a0 zx`a4E@IWCJ`(is@oY02T2qoIT&x8imn&UMl{i^=)LhQdXmvMwMQwXY}E+JY}YYSE+ z{xXg%0h~rCar{>%d@AOS;aB9lk7r#A*7n>-3@Y1HA*hPFgqV>st}v_r?ITY6)tJ)= zB}$uRLG-RxSh=5}%eKoRs(yB?85WS?WLSFlzZKkw(oA zg_&Ps1AgzdP9dm@x`a;mZGfgR zE+_<5QI`;Fcuy5!=VxgA+Ol&*wCB`u=y?OwC3L#H`gUw`Ub-Qnw=bs= zO6(CUa!;JGM}2AOCFYwdvmXt=8Z3&oRS2r0E+O`^_)>+{ne^LWXY0dhgc7~Pirkim zYGB(r(n|t(6}G_wu(+eALQoZT37yW%sw#``&CeH|G@EWwxdO%;Nw zs7r_)9jew~n=dWFWnCI`8lgmk+gY$>fD2|$k?%gcoocW&U&K34>L>(NQI`;V&|Pt2 zt%o2sbg9j0gc7HoWxnBX8oK4OKXe zP~x3f-9IpoiCydDx0;i#7IWYG87sCZs}NL0T|%sa=vtdK8}u1NPnG60LJ7;~S-`El zFzTf2Jx^U&i}ig}l#h!qq!3g^T|$(uR)?8&FUsrOG37KuiQi|k;PpUXj4v+z>eBOC zOqW`jU)g>aDM3}#CB(|GR&`kK50!Y^+P9HLC}BH43yRk2fY!yOUp@7$#ik#s!#9rJ zt`Jm3T|$f-#MEY+n%CiugSR4$P~t|rEby`m#Kdc|_k7NACl-+4!XsR>6oRT$_nEuC zCTsAl8SlC{Lzw|V2|DsC`oizHu$(%>4fZ1%bLu$s>=Nn{qMyOE1-tY*(_mH0nbQa* zz75OZxbh@-u4|eGGIAnPhIgLF(?y0HxJj3})TR7G7v?11Ux z$vjUi!zwjOavGsTb+HHbLa&y1FIv9)_&4!nEidF^W*B zrx8jx@6HC;Bqkr8k?%gS>0Ydq#U;c+-;feiMO{M7pu6JDR>WV#;rtWQ2qo-AKK7k& zjf+Z3zgpAKn|XhGga5?cRtT!1E+M`qw)(I&$**zjg6l{llsGe6>=$09Ew+qVDblEv z;msD0wBRgvw?a@AbqO*0y2OXw$}{IT-tRyfp~T!6v6_6XAJ!STOr){lmKXCbRfgZ2 zGDRV%in@g8-(4!MYE)?+yL}SU2qnIYRbm!70r);Z`c-T@PsUU2_?B7i6@sc%_whLB z$-FDt@z{R8%8V3B(2;oYm3pTGTlI6W!P%lbr;bCa?(5L887LhLkkIgnkxamw)Om9-cp`{PTLP)FQPY!77Tw_4$+ zCdCzks;EndS;dw?Oy8|T81m<6$2(amtmWDA9$D(VvA9FsO7Yl zymZEt(+DNhc>vV{L)e`QQJ6FKCsKl{s7r|U(J+*qsvV7|O+F)yP=b#3i#LGAp<=Cm z29D6ZQV6P|E+KZH)Fnh;AB$jx zHq6G@@|TfDC_(23=yVH;MX;;S)?uYeM-_sqs7r`;&LUa;FKh9B)&ZmuN~kjjCU1{m ziJuPO)Akz_f~u%Xh*_+^B3bpH9QU1CjWj|DItM|g>-r;tZGCv<5L887LabiC z8Oh>2uHjXau}CA7pmPw!ZVSN?tbUm{xc+!Yg`g_x65`GBLIf-E^%Xvt;fFLr33VR8 zh?8NgXO@mH8&Oyxs7iI8L+`>^TA+^WvMrECC_(2Ph*Lwud$ZdHZa8=QGSc}sbe;@t z!D3JH-#yv;LstzBUN?|NC_&q!*aJH~iT(IF41G)VK{}^o*OnZp%RJF<-wLF6Q|!>x zsXsd&Faux1P$fbMdT+!!ugZzcf5{B|uba0rBZU%lu8G+9Bd)MEu$l#5dOuVdai`;7 z>gemqxps^>Ws9>?e3?8MrhnUB`llSAS`~*r+mHd0;vw8aKM`8sb z&s|C_u{^iO(Kt3joV<6i<4r^5tVkv2v_!-6H>5$5ph$izPDcpB-p>lo?A@5VWL1ii232hl>lLSd%XKd# z*5T=NCB_zoO-UPaFaDzvR3-lo=ycOy^Ij6O#fgPCCToUIqt&w@UWzjgD?YWxsy}-w z=R%10-8s>$XJ}nRyZA3aRUYEx#dcODa7BgK0))xjXclktNUwXP60zdc(2l8QICybS zq_jBG+g_YA>U3OhaZSglYLPgZ^ujhXG(X;>0FhTblI;&0p+9DAq7XN}3gYd52Gedm zk<#KUA#q;nmPyZZ`;RKaXw9JYiqhg_htGkm)g8y&C#IzsRngy733~@$HqX*V|01G_ zLaY-f7Eaw{hG!~uFK|^)Ula%DZ5MMLvr|}_IQOw)iWwd+8Hts|>5jFgnc@4@k*MB5 zGjY$KRd|qFSKM=|qV-rMZuHp%2eN+TcHfk!5VytJ4BPo;Sgv~%Qd;bvDB1^m_G(|V zyf{Wxw4JNOwgGRTOWX4La^Bq)qLpY9<(8S@yqIXEbqN>U)SgwT(by2Y$(GUD@Lil5 zIzd+gkA-(HP_Nqic4U`E*c+z(TaHl`-7iJmBjwYnChW>`2gC38%@m@f=R z&u*a~8hr(R?V5gmPBfz`y4NU8Pp5m5u@!!7-L3CaJW(MQic@uM4qIbmagGJ0g_m60 z2}|#+*B@sC7*)~zmsO(5(-0VZIZfZjWrRXxiqnCewp!!pHjzkav7bz*NLW*9s6OsR zGNUTGTfIu0c{WwM>{>=&E_94STotDgcVB3YFYF`pPX{)h@}bien>|yzdfQrmB4CVo zU;Lw@r+Luy#3~3YU)F8r4ZTZ96-M2FwsTsi#ZEeR+q2fs_4%)TP~!(qdHRa}$;rv01NuZ^o#K)?<|jzg>>CZLw9qIJu)j z&{j)n(Ze#ZA}epQNdIe|KcgyIk5%Gr$Q$UqZI1q^M|XvwzCvj+2Xfzg2xvA=pI0G9 z@e*2(Rl+TJ6I}l~RR3&!qC!xAq_kMOv|%fF-|4Q$lBy@tdaM#JOLc{pJ>2vqTt_G_ zN^2#h#VIl3M9(Kqb@lsqx++ftdT(f5(CPY!_p1_}{By^p`6vYST}q2IUX^2q*OtdD7|16`iK}t$CTdPqZkiqHRSbYS>x9<2GJw z??wkEpG6l&n!#l6arsZO837-)q4zUTzST4@Vg?q8NVF;OPAk4xrcp~= z6}tKNJ}$2tFkeYeB4cK!47vAOp@+PtB?^YdZMlcZxl%-24C?Jd%nC5StMxGD%5 zk@=v+pPajktNP-;3M!gMD1@YqDtWc{m(A0LjOZ)UC@Y9!+A6RY1dS9V{^Y!js3msK zA3~GG-ShJi>%T*@+uJ`sAI3aM+JkS`a+@WHG@6KfcnYGCAZSG9gA#voo+_@&x${ME zbqG`lNgGx2YFpTE(^8fV5NUV_qN5;M34%rn5`S{OQCwB3xh4BLEGR!8bq}1>zOW(r z`7q{5(g$r$YRNm~2`=SD&W8))yC7&p=7SP{az0#KRZzuW;P~2GAtY^7$*bMp@VJ&@ zDR(g+C5SG9s3r&+DM&X7&uV9W%7QFPZg&8^Xaid8#WOgbC z-#g942V1k@f@?*X)>7`o=CG>)TQ#Q)n_KuX&*E#4oD=nZxD?V)lgf@T-Rh>*Q2YA*iZ~ zYbI23`feMAzz>R0(Oy{}f;9JcFNUuFu^x|aoDg{voWj;E8Z_m2B ze1+8=cPj)fH%f~U_xUg2oM|(bJ=l`b`$4ZHPV|0VY*!wfKgp}A(CP>b|IS$AI+dWM zKxwg$@QN~Q*9#|R^YgoM&*|^dyD4VlW)_9BF@CIXt@4bPsI0rjHz!(dVmDpUQ)H3o z$82ksXEZ_ySu6j%UwskxqfT^dcJYF>LQs{OkGs83z`%#@>{9V!j7BISTfv|AtA|57 zvYd-=U~}CaU@Pv_+kqx9>hWad4qjOz_Ksd-2ID*?iPHT!&xbwuWx}o=ng`g_6bW8kGg~bF^WxZFu0eQV&tj%G46LA7Axe}GgT~&tZ(`&J^ zJ3cD}RnfaC<|i(G0U^%K+1(tAd}lDGK~=O2#i-1X=g_HlbG8Llf~wTgEiHP_`?_9% z=RFoGr7QcgmiD)Vur4!|lGf=CUI=3brz_B?(?Xyvhn6m-#r-hv!B%ZTm{(z9 z<943ECM~|%ee;Pa5d&P-&~s$P?=LzS>c?!tqOs?IL%rm?rv<)Tr#qA zW6D-i2zt^qr9~PW+OxdM6LXWwSK?Gf`kQ;WioJGQD8GBt(M^T;>0PJ{K^&7ptK zZAec97pLmF+rylVE3{WdM{%m!b|@XDRJ4R@<^_o=<&J7QY>Plfrb;Yon+DIEEFrk| zHl(!JDLtw(JA1xx=_xt~JN+)`TfA&V1~dsG~&-7VRlQ`LSk7yRPqA~1OCR#b^iRma2D7RR)c zZbLX#QCiLU=*BN#X50&H+=v*3Shq9_VwM#F-z!@Rq%mb-ZRXfduXSh-oaT@cYP}lL zqcYK0~Ak#({;lXf~wS*y%A@iI|Qr(dF}RMe(s_{3osxz9UAVh z0;%Z>Q2u{F+p2Kmz+#cczf(-%W343i`0=8A!Wf~1yuwe%9H8qNNn9vu24gcvv9E0| zYV^0LO8)<3(`w-AF6WWi_ArIGoKb8+u}k@cF+vIX_x04O(4nOy&V4Zj^YsIUjDsP*X_xI+D$t{w<#{Mkpcwp0wHl!dFPb=CLVs3lwMFRo$Fl zCX_I$WEz`utH8Yi)K`nz6!KZI(V_s6tRx zk5)M_@0JaG+8~J$cQ|w^){k9kc2tvPWo!qu+~n0ZE93wvuCjeRzs+HwAkvy1)o7$3 z@uzf0THCN2<^0%z$n^?AOF`!E*h*1W&14!W|3~Brf<_7wf6D4jxDVU$&ViMxk)sf_ z+~nJbeN9`~_F9&17m;(1vGMG%>vMy=c4NDvr6AM$rEJ?jdVf83L;z(G*XcGQ&z9Tz1V|>Vti#-cZHzk zCUc(YVFQhx%hFvb>h7#`AJ)Xyl*?;3dK4`MnVw6O4Osd}hYJ%qpCgF>Y)ml6=l^` z5H2h0=I7iPDM%ReC)U1-eB9q#oR#QZRv~D)$tyhBvReD773(?~(W zSR&$`TGV!{gZCjN_GNy~jlV@pROY-?W@$KlPnK@7$a&@UZy~#_Uw+Pw?@=-z#!`^! z{dxB(CWz1L-oiRT&`3eTSR!HYg<$yXt~Lpn-41vbtlNu{UuKFY+t$rn^~ta+!B$#o)w{) z^`iW8GdidGH0UzE9b1uCmhH0kR0#RIM(3328ENr!9@~!DckzL`S!I>4JDMl;s`O|5 znaAReaH&cOg`jWVlosoq>-n)y&bBP9gQX^a%jjfMW%NOMg<_<^!Jj$2FUMBw`D&06 zqXS67=pXc##B8cWe^z&J5jL~!IFu1%%aMe!-O*nXyNlWTvq_I1iQO(w<`c#mCkbPH zrN1Qhd#&rowijOqSub??IXB)ZNf__5B#ghL(@oiL3THe`SetQSO5LUJJG54cb1mE0 zu-9ULOsLeF)Aw^)k7as)YGPheZPwvZFbr?$st{B~?~RzJ9~lQ3ha%a}$cJ#=Ck+ny zRe}A7{!#i6lRAy;Nw;q;MkxF)NlH~Z-YO?fcPUYpj=xv zx72r_eQ&fEkJ4fm>$m-I{ahP1Irz8I4|lCX77RaK85}Yfpi1;wTbY%}t-~VLURMa( zpGaxZYw*;Dox4?s)&Fr%>3fadm<`XD+JcqkLR5*=x9wTkrQ+@N=Ng5eJ)V>nZ?B;~ zZ0!zHcJ?7Ey_}vea$skr3h=baLR5)9RXBW`#+YrlVvN3j(%h<7Rb%iJNa`2MUbfx| zl%Vgslosb^B-^qvb)8u?pEE$;Kk4tPS2cRaL(n<~u*XZeLeTUmE!NR@_GUL%nXudU zj{x;0`n$9g#7fpD&6w7|HZ$2gSRv^9E~Uk6+{{jFLxo@9>^oC&IGUcC#;%5_O^)?v z_V3CwTB~XK&~g)P@Ihgy@HvR(bT6Xxx6^t|+l@FYeoiU&WMMV7^N2a4*Guz3OI@tz zT$jR!{2_wsbEhrG;30(Wr36(u_E}~qv^o^l4U%arbM@gqx@zp;l&lss zLW#r4OAM1PhryGZl9*kn8Sh!B8QXSknj4K!B5=(INxIwbmAR`6wfRdL#)wo=BDdMW-0`t)hW|GWN*Gm= z{x;xgi|AVEe@Vj_kt#}52yC`*V1?wrq(KRzO4760JGbmfi~o{_F(Orzs50QNn|5+4PNrMtbm83IDmen$bzWPfV#)wo=qDOL3?OmN`e@TN9MwO&vZ+U5+vrXXt zuO;%2{JLw5NEIbI40qFt1pfX@8k8`qB)xfKvUaRd(Z8f&j7SwFj?EaLT}ZPO?Yv<7 zpoCE+>2fCXw5mhP{3Q)zM5-vUdF2dkVd2t$NrMtbm83_k-le_lVEdOej1j4##1*Tp zTK5_@e@TN9MwO)Bq+ZtAuDAb78peoJQR4oVv)ZiVRsNC&C5$Rb$9jC!exx}5B@JUl zswm;%_eS%7TF_F*U}>z= zU(zr}q>2(Z%2t%bpEP6z%dhQ}FsdZIIlivEs=uURj7SwFUi7RbbN-h!{y)mj11xLZ z`{Q-9MMV+!9;kp5gtw<|6cxp-h@gOq2!e`RhI=E5;NE+0z3{ei@4ff-IuZ9C|D+H+ zdFB3m{yz6=o}TZgCu!0&ZBfeEf+^r3Do zfwq!td~gd>VZu1DInb7vjSoz46{C-D>ISs6XXArgm+ zcWpL4xP_@Ov3`4Rpglu2J}|*mjBeyT6lm|0jSp^NDoh+ZIv8jVmyHiha22CxI*tL_ zi)Pcea|=^p!scfz(4IOQADG}OMu$620{S$_#s{}B6(*+GPXzkJ`Q5i?-5;3XDn_R# zPY3!`%f<({Fcl`+ESm=O$(fB0OmG#Ww+GJx`gG352e&X4CiYBE06GH5#s?<2iqUr_ zCIKB~WaEQdmfklF7ygCb){xjo;4$I$Fxc2e&X4CZhf40UeQL;{y|1#puZ8 z3xSUMvhl$!OofTLH5URMS!Uw{6I{jUlT#Pd`H4>k);PrRF1IihCf+NHfsT-~@qr1h zV)VidOMs5Av+=<#OofRtOzV9^KD|2rbQnS6`Zopi&dDWd+@}MBz9BWU~He->eV01Rj8f_FAFwR)y2!zE)Rw#Puf~iF3)k%K4D08b0s+ zvCGs1vpFzhrl*Q&I>URp15p>|Q)c{IO~a}RotLX$iY5RAB$yDBo%54s0WFk~5626{ zmupMZfi34iyO8E8rfC#fHyg6}Qwyc;fC(B_z1Xx=E#5r=9Ml98VvJV{ZQ9r{#iqw{ zfyjGrk@~9V94L6Yxr%A}9sLnc?dxnBkv(d;hE?o$^yWbcuT4sQ?3&sjWbp91; zaA**`f15#Yn(o6(uT@U#Fy-x-Rr(tUetix+UZ8%s7za69me<6q>vPgmJ7N{4T%!b5 z9Y|lSp4c1*mFt=k=BGTh^nzhZM}LuE?=tNB_JQ8t25Xq65wqMzYF4%SDekaR!>Wiy zi_~(1BVfR)t|o;4QBQ5A5~h6g7m4HJ7O5xA`@o4CgEdUkcVzW#NX~W5l|p7Sgc9PM zh;6qUB|1~WlM+}JMenGU^euGhv~rqAe4(v<`NZZ*>QRxvIl(lI&p?Salu#*wRj(f` zRkw!@fS)b8Y9jHT=Bh-Y7RvDTQw0K-9Mg2pixM3vkw6Kof~!l_rayw=)#$;RNVL7t zfz*1IN2!;p2qnZh5&M#Al;}f=k(9tHe6NVayz3pv-J^Mw748iM0_OzNbhRNRR#C#2 z5?F=r6_N0~Nr`rOm0v&I1p=2G)3o2EL^37PDS=h^juHvur^)Ki4x^Qt?Q+7}wL?8D zuLi( z<$*fge2rJW1VX(_X0Uk8Ok?qdePGzr+%#9EW)##qSFWHO|JgvnDhJZqxK9m&C!I`* zM)Sh8Uk7R`BU?HNMDov?#*nC9aH)|cU|N#e90<`I1L+!iTPFppid8FPoH8H~l;svC z#P?hawI$sQO3dYA0+F!T(iqgZCq%xq229g(jGU{Dc9E50+lwh!b!O@F)Hjj6z{k;) zcv$bS){cG;*QTf>5TCTmsdr)nz-^N)V4BXKH`u35TkNTPR3rtfa;7awt#Y>~>^_s< zga}#kPCGc)Te*>c2Vi1gt!1fil>qn|T?jBONiQ$m(%#)_ulT&)16Z}XQ;}4cy1gK= zUO^LLK&5u1#<*GVD&G(2xZT>=V^%j9MZW=vDqq#u`9n9j0R>^i=n}@ZRXW3f1BGdw zziHH&d>b|awAOD0)u2I@jH~u^hCQ9_Oo;f+4alR5YvJ|70t!CwgasbPZ`HfP(tQO0 z)3o1xZy@)~mcl?=2Z30vH8wWd-5pjp%MX~Q>-3!~lkJiUvzk>^u&V3@ALFz)-QaDI zDKR^s3<+sNpbr7?Iv-*i*3>TY7NF=17AP)A#v z5dY4Q$k(`Y(5q!*fjECI)>x`dPpEv|9578|e~!7PUFh)?%ARblV3o9dg7IG40C<|u z!i4y-W1n_!><#!ahQ<;?=XE@{$hhKLFhm^81DKYi$g;uO7&WKTbZiF&tG47>X8b-S z7;Mu_i7FP0Qejt=@@-o@;Qk}9ePAy{cq^*&%#n}0r} zCQ89Ds-U?Eu_Dmf7~|4asWLjBf{Fb7${Q1td&BEtc>&Y(T5XS2TW)Qq^q*j>VAY3{ zHH~1?8zxoGXF{Yl3o~3j(M&ntkbX6b&Ko&qf-x`MCwql$Zoo8+ROmZMOmknCmSbp>Bj3{`+)VT+yJ)~i3!cyK;*vMGS&4>FIauj#-x=5)GnY+s1&MHdSL{t!tE9Nqu<0; zi`15$i&P$z?E#rx!nG+9aay?Mb)}`U>Y0r|;AbDE z=`8Z}w%VBjZIm8$tre`owJ8!eHzjG6ws%p2ogNBLNc`->v?Og=Jf8mQ@l}=_x-UHM zaBYgjwwy-oq&)4KBWtH&sdJ0zIkrVbuBLY>^v>A&W6^Bt31!7CrGRC)${o&#y8^AP;JpB2H z_P%=+CAJQYk&9G#Ch#~2(=_^pV-qc)x1AEV&r7jMm~XTW=?$Y2^FXJb zQO1G|d%>4E=74LKM$>&XR$$D6b6Rx;t8i_KM4f*vNO-NHN{$!y0x|lVy>USfKY0DL0AQMqcQ@FPV(kkm zW9b#fDqJ@rai)C@;(5NPV%g&sU}D$ZC#hj;{ou?rJE3Ojle0`G?d&s4WmR$;VI+gc zLAYjV?9WomwY@z*!S0W3h0zkOO_7Lp*{9`-%dOa5X(AAK1c+%Gxy9_E)?@2Oup8A- z81>=W6p8-ZzGxrIj?xN$zqzu<$PgH%=^89p2;r4=oQzdNR;ecoLH~^0v0>U z2m~IHW141heqgHcvvnxcsGn09z2GsCBpnJY>oK-uX{Gtp<^qAAeI_HB&Z~`I8y8hZq_h?Y z{M^Mf-LJ^ZLv6mkfYQBYJAuHxGo~de>|l~A`B*CB-*glR+#6t8lCIRatRC~oqa=Uo zA`rOsVVcHI46xERo&O2J4SWRxkKr**zXjOhq7~l!4nhxi7YIDk$248B6&kCV&!xLz zz8??x*@s6m;&bri$0DSRnUnIta2N2Miu+xB&(rU5=DL#U?|#7URbPeQoR}6{34MRg z-nZ*(qlVFU?CgEXqIFKdW*vCi@zW;#JxWyZj5QO#32eaxPqQ~KS#RidAK4L1h2Pa= z5S0oADqj6wYHg?6%M+h(lt+J+GCb$I? zEX|K+_=x+pANoD(ulwK@tYSW5EkopZ?<$$s3KQId36|!^GkpATx+PZ}7p?o?7OY}E z>OniX$4l-56WoFcmgdJZd~A$x(JoXQrTgF(tYSWPt@e-yr&rD_2PU`$6D-Y-XV%B8 zds=+{-ntKN!7ApXwMAulWoX8_3|b$E;1*1xJ z6>dG8$mps0I#hj~?#6h%joDY&tk2f4dSWYD|C`wOWSmaCSVHR=(f>`PFAUd-PYpI{ z0-cHcnJb)kO#inJeBCgu6S4dmg-gx}b`^N~ciWv`FG@+anXOy+JQq`0jO_(w){GHm zwlZ>s39Q0tex?k+(XCb$I?EX|K+_*iP0PfI?S;e%VSiuqXQ=n3yf@p52- zTQI@W{CI{BpM=xefvAl7;1;Z6J~};b2uqyh%yM9YTQI@W{CI|s`=mUHJK99QR@{PB z%!ln58B)jbI>!XJV1lLj@eCgu?zbn?H|E!Ua0^y3AD&+BaQkqb%yM9YTQI@W{CI|s z7kvg1+eM4@zJyz_iusr^)(xPYbEXeWa0@0_njg>b;ag%9Nk3Op_Yr@+7Nph6ucx_+ z5&XDFU<=NPsSkaXla3xP4h-FTY z4@~Ikdx>%2KX&_XA}d$L)7#4XpY76fa;ahinX2@3Ewkz}%OMkH;1-s~gyq%p zGAmye5zA7h1XrQszjI|u=y}IPX8Je5TwouV(9@YY{0qTVELWLVVdC!W8G5U|YHme-m!c>^} z@4Gg$WvGn6cW`EHs_fKRcddSZaEmFC*?Rs$a22C7Ycm^yTbK$HnXTt91XnRSvo^CK zxP_@Ok=c6wLU0wMGi&oV5zDR`wy-oNGF#7Yf&qUJT*c_j+Wbw#a)Mi!3KN;F=QqIs z-3KPPiqV;^N3H@ysOYv2{e9i8_ zWzI5KT$TB8zT)@y>S$)cDvP)V@(ZL59n%K`sdsAdV$Ir1 z+SJJ(|G7B4r$AuUf`nDZf4r~B7r!ze!|E0yHxEJTtOy^0z$!6UtLgg0*>iKG*0|Y0 zAg~ITiB^PdvVJFyXia}b9*EM*!B%#&^uoHAWR@QCYJ$=F$2GZo4?CKx;a6H|L(|Kq z*10%BAh0SY#2ZU&z9BEH!ibtL7ibek9!$M+d5}P06~1mX_9tCiJMnAzl-=|@UYske z!dG2yyL!7~Dcs^%8r_e2`LbI3e-f(li(Iiu(a<-KiRv-OG@;l#K3#jWNZsr_kjtnVm|V_ zO_C3W{Gh}|O7x>dXePle_`EFLspmvF$J(EixIl@n7vF20L%nn#nBXer5OopMDB>*T9X06x(`fn74z|8#wYooXKa09BTD3@M1xF%Tkv^VI&YIt z^0!q*DAAk}A?+-*Pr3T(J}|*m%*Wc}7BH$TjYKRJrZqT)5+^bVZo%he>HK>vXf#Ad zRHsBtKy9^|SAX3HCb)|EaC_qbGp;kD0nODy|Jv%XOoChRd0BcDC1U5XZxkoq9YDJK z6qP4j-UjSk&+My0N!y}u+Nr#1d%+coKedDJN_q9!X;=7oi}hCr%0v=PwUpb~Z4d~o zy4JnCYOlG1e1Z{6Y7Qdd-p>u^4NC+9tD+~BSB(>0;prwuJZ>|DydN~*P{DbsKwwo9 zQeM4vx*l|#!id{Lhm%IyA&*V_g9QSs=`cpZH%ivt}i;=E+ zyW#{^eb`V&U1sJ6pD(fdW3OLFa_80tdFOdcfxs%f%2Lo-6EIlE#(^BT-)}Yk@mA z=>+c+*?C`-Q{{bmEp;EaA5>zy1$`tC$a-TS+?7E{rr?o?A0i*{Kt} zPh>t`p1CH^DP^ns;Ql13&x}yAY)Eyju(azBf~%Mho?A&8JSL2MKD$p%zq3~-c%R68 z^zZyZzH_CJ?t}ZIyNq=TC8hhBX)hM4e-K>7eDK`TC}~^5Nb2Ztb=rkgo#1^U^U>GC z941vNqWj?f=-!!SLP=1=!|KA|Lw^ul#eDGG(zrM`!brgLoyMkg-8QrEK9Tvz`_3NH z^V#b@xIany@S-14Uxul21Q??sspexGB1bQjmX z{Rn)ft(c6U%P_Y{UL%6hf^igP7NEv%pg0#AB`f| zpo%tOcUL$!XNZDTTk@4rHzqcOdrqc=eMkXqSGx)DrSo8cc(SClI_01ztcxiKn5NP9 zT>EO9u8srCb`c6zEvR2XU3tU{`UTQeVaT5(nU%Sv77t$pAIt{|M8(VH)FD;9VP$(; zz_cW74-M5WS}lcZuR|5A8djyM>b|Evgj?B|5HlZGYTMdwfn1-%1R^E4l3FvO12leM z4Vadsr4G4>w?`>B)Uu0$YYpce_m7ga(*3SxEKvbE?Chmr)rvFa)OGzE!ooX+KqUH9 zc%V(2?h7sQ_zMIsEvD&ykniqk57T|YrIo*eRe5q(R>#fpf@y^dfJp4Q_)r@^eH?Tj z<|`1mw3wD8W#9uXk=EeMW4;PjefvoFRvg_P`s}v`kyw1}u~z%ZeAv^dvp^*7cT)QV zbcZNs3&1qp3&Q1*rnFfAehWJ*SamwFrYe={4%?rYn-CpyKGjkyZiC)F?F8apg}UmT zA3@M`Qy#!HjX~%7ua;};HgMYBPQj|lKU~#I+bI!ZN<@x%u1#<|3bqSd2}F89gW9Qa z7?fHo0j4D>CH|>4ogOHn^BF`pz2Xj zrR7H%(~>l|>gET!0$Dj^U} zR)?xP9i~FxqB~?vOVa9uuUbUY(#nMaB^0b`yER;0czX)WxxC$kcvVp%F4rn42W}S- zh?wnz)Z<&GL%oz0GNx%nxraZrkhsc9(W(U%tZH;hEI8miR>m}aezeF*a);DY=6HPqtoo{qRYM*nK)(E@gn#Kgq+3IS@?gXr zfp{M_UhS7N5oQ{KWK2tvd0H+q=8HjbdUOY{$|dJS^_w;unin)BjHmLFs7{TPJg*N5 z#K;ztRrqHP6bc0y(~?wcVjl9YbYo?j*CD{F$@izI;|9-xt6fcr)qTxK)J;#Nb=5Tj z(fQ>xb#|F#IKJIp#x%XpYvd#D%bP20Bh~;`{g^mIy?i4Hrlgn>>T`2qHnf#87A6Zs zZSR?Cn|gD>FzTKG(~?wYrx~dMtrhpdlL4!$q$Q}=(~}`wH6=H1!`my31{DUZ%6BbU^)EdSCd5kyk$5}8n#8s0pu7oN zCu3sN#<}YJ=y{Mh%qkVrl2kCviq!noL1`CF38bpme!jZMbsprplgEVEGuVbq-qb-^ zv)9{ziN3WKs1An<8GO}~lDXG7j}>7dx;9;af}n@5Y)wsv#jQ1As4VsvzV z(muVd(*Hny4HH9;ELQ91PllI?4l1VUTj$X>#D2byGQ-7I!>U%1OVtA>lAzhuq9(-B z`1~YoT`T2oTz7%M5hO58W8JT@AuSuXRvhy92~i_(Tnmv%aOp^(_7u7P1}g=R?(ir~ z{Oz3ooD&&YVY8e{>MK~a%d(=H*P|iK^(!R2pP@TQdb<#}%~nvYK|O)MqcBX<_i)`^ zi1}hG*jKBbf>q@kR#iQ_c)`XbTM&s3t!t7hM69Z< zU{!@WPU`wP?V(IlYY>T$s9L0qizj?p>mm?%+=glT92{SZRI~GhN%LJ4tonSuwp#au zFANDc2a$MmvNkEE1i{k+H3R~W+b~VP!MahKR4y9?W%ATeuxg{byLzmB5UhQd8${w| z>$+sml31Adq>4b`aT})Tyn%0BaydR0e%-91VAWEmhU$_D{UI*xmn;(2@9U9`S7$)` zIu!&0kJ~U!e|i0?N0uC$0S_H3C|GqXxw$&lZ!paJ`d$`^2`O$QYTrWm@u8GJ;BgzK z=|1iU+{l1k3*lXQDFv%)1hiER7e~T6hi9@#ELiAHp8Kqa7)J+zz~eSd)A8<7cQT>n zdgx!-LBT5j$S$f+WE^bocuN+EqR9qg8@&hCo+&60c-)3*8lPc~fmDjy1E0?pRIn;& zSAg2_;5gX#&ly=H>=pp2ARU6nIjjT%kJ~U!_XS7<(#Pr$q~)ZDSkZvYKYJF8M{^4V9=Bmyl1?TzAcbC@1>f_z6|AcEB0}9gbqZ8)+b)ZQ$F@c! zu;@+LY4H^>fyZr_mZUWc8Nc23{j2KeV!S3W$fxzQ7Ow%v* zHZ~(xHm@Pq+pB<8-Mf!dVO0)fYEn5OT@R(O$iHaV1)*R}#ymHaVP zU0h%e+&U)9A`x(t?gy|lx6&?XzChq{8>Z>*+4EYFzE*jZeTnk{tE#PtSEHhmAfUay zED{s;dJ{R1nR2-5Sb@OfHcU&BTbMUV>Tjl;?=%*$>Px=aYSg4;_|f#9K_nLUZ%g{D zw@|)1brJ|X3d6J{-7DOd9Is%hL`Qc5tZH8&Nqy3ME;Knh(;yOVuYAa$1y;)L4HX0e zkJ~U!``vgS;#R?0+4pY+z^Ybn=c+?@&4mcd90rjvy0<5VPgpBOJRZrIz~eSd({cN` zb|gL6MrjlMNXDv;VGGm-r{_YQ+&NN3;&h)5q`#w$(xqM>fxzQ7Ow*{@x7(A@&o+wl zquw%B89pph1BcIrfHgghBGIx#M^bF8wGvi*cq%6FxDC^E|0t~k@eQ(3f>S1>VpZv1 zOH}&}$zcENoKYkOJ?cox?6FkF1&$SZq5*r;l5w}xjisSvS0)a<;n5NOc!#k3p$IX>P8@{Vpg(Iek#M>5uWOJ@ax$N3! z!iWWrERuYj)U_+x!nmnyE>-gBNoKztC+|A+S{Q%qY*1Hi8s-bz&YFQp+5O`#PY3d`@pY%3vmWO|R4_HuV6%y>g>G_3Ayq#KP`PRMj#ZDi!}O zW18;s6V;2@rQDL6dp{KjJQl$;oy~X?M3i@jWy>vh0jp}Hx1hg-2Z7n;cd|%$FAXLQ zir$jfOus1-XzYV&+Ee!pBriU_lPeZ^2zbPDeRmtR-=N`;YW_kNi97Kjr1iVwa*2T_ z1p<#nFij)Sl=CNddzObstL3&TMb;LNBy63bk z5{~)$kx05Pz}vkC1p<#=FioFPX?@6#4Gyqq%L%}$CZGDKueMHrklqJnk!X4)jJOy1 zDEF(lLm=?z1=DnwG4CJ};@uoPub%^~s+c!iZE|rE*lyV?i^SVrVWj&`GYF*-nlN#u z&|tO8l_^j$X_Jg;NlFL`C4EO%0~fp90)fXnn3kj&v%<)3&!X`0{${``&!QvLdjCv= zsb!YSA~ADjI4N&g4yu%-Z;H^k4Ucy)O(Xn;^(Ss-u26sXCcvtPd1BQkBW8eq`y^Q; z?$#ejToo%YFOeh=c)WvYx?9?ZzGSU?82oF!6|kzyyD{phVlzRiGes7O{Unkszf}UN z7n~yySI&)BEt3<#Y34{7({$y)hXJHxohGp6TcSYV5fY~9n!A^gWa-fwu%~Q1VAbXM zlhkeLv!GhFUb0Bo{~Sm{F4u)F`Nj(b9wA|x_PfI)$P(X<&}-yWz^WT#rm9x%iSW(6 znJf~y)(s)^|FMI!b$bg09wA|x`mpU!7Vn$^4}vBGR<&+5L*3G44&*vgRThcQWYRz>6HWvZ(GTjrgL6)gUOv3`YiJ3DiC-~g=rco#A*m}`wB3AY+Jx8 zm#EpQH+}CDTKTR)B&wSaB|io?hN|Eu5O_?5X}WG{;a~y}`@(`|4FIeB&&*NJu1bc9 zA66JdBBAIA(unRhb->&~An=$9({z5YVFaoDWFGi_r~z0t<$JQa+IlWLN@{BmiH(87 zN&b6vz&@9)KqUT{rv^8h3$_imd0?7GR-H7Ij3hxYzQA`G`@o|xOw%}!PQyv7GR>h1 zo%6@4b7vQ*YMZ%G&F4poNNoN-oGjhw3F&)N1p<%4FfB>t9}Xw8*0g~92U2CMs?%|? zdiPs0xIOSUibVaC5yZ#4863;qPayCp4AYWSWcCR1CY<`H9U^1ZcE6?Se5Yi%5q{Pv z5{k!2GSR0ooH-mczrQYAd)7ys7|c{;m*Ol zfN4qUV%=3sD{>8dSNBw~3eT&G#GpO@s^2z#geyaP2t=nhbyZ)Rez5auPQWzX2kYEG zZN6(dxLb8ounNzsip2Nv=hXPKd6g6Sy9k8;W)JmgQUok_{vl&plKgrt)z;m~p+t{w ztzcEo?G4qK2SZ@I&3hA~df7zvT+aN8_xSb-R^gdg(Z|z`{k4=s1r>uw3xOE;+EYzW z8wE|}XZ7=!(coGUrSvN=1*`B(tVrzqSxx&QmsR}AH4=!oe%@+n-#Dm1iSs2*kpVe(ITp6XE%c!!oAn`u4X$+IOEiO4p&) z6+wmOYegckLq4rw%Z3W+Q$Zkx<_Ju9H7Rjg%%`sLtsu(`Uz zgy`F|ruJq@OJ&z)I|Zxo+^y*2+r`>ivEuEOH*3rV;>g!1b?S_G_;5d2#xz}ZUp!QM zT%fJ;wt%^URd^;=B&Jre)f_{8m1Vns046$|AE`E}mjHJ2r^=Y7F=d~`Xd4E0QVOp4 z3|NKdZbjmtc|mPNT7cr#;h8|ZJQ%A&$}H$^5iMhyj*t_^YJ=n+O1IGKfK?%T#;Wa| z5@E;oUM57L4^_3|4+0gZhSveB@NBQ>V_%q;HX*#PGOL~{5P0qu({x6${u*tkO|X*q zVgcN_I!S%oHwkVUoaIRkrmB6~BtzY2b~2_VX`pp^?M7mRvf##iz$!d1*d2CTw!w<7W4ObIRK%uuD}!j=Lt ze0RK>uwgFLTCN!|O;?!anyM*>B9$DEWWXvscPkP(e>!O;Er%<^zLXY-c#@ztE;A1X zwV7nVG+lGo-CrwbHB9Nc`<0AUc~{L=D~Hbm*Oui?h#V;~nwP^6#qwU7j8%B!>OdMD=F33#4b~kCKa%G_SNUo`Nx^fbScPdiOle>V&tWTzX|iQc>Yu*8mIPBcP)!h&V+0fdN|y7iMbqcUSW*RQmh=Sn zwf)gP`5^pyGd=BBu0AZT-ju!N%#7j132reZY;LB>vsN|v3&B;4E*{nbobNQuhTs;a z!o>WZr{!aIe*i?^3aar7^+32F=P9OXw|;pNkP(#nSv+ z(*I3x6(bfp)R5OksPvl#)OKUB1)rCt&9waT{UL`%LeCXH7gn)!+OvG}^iHcpLifQf zrbPU>%Z8TLn?yqQfeEf+bn@%7hF$%qiiGZiTbK$H&MW5_!f4z9q2#&`OmG#W_pF$2 z$lbs{8-iPy3KRc+ZD1I;Cj2i1S26n3`Cf+J6)I*!a0^pmqFav}9^Z=A{R_cWj2;(O z)zHuPg2_%z*uv77nDwlYN6^T3e<8Sv(Hn@l;Z#|dYzS^)DoorAZtT8k`{2J2T*c@< z<#QV@-<+2EXAN=-Q(9*uUEXQ@k?cC9<}gKf?G_9ZIg-^ zYL>Im{x`u@jQ;h{Tf^p}8SxW;e}9fGERBg(Z5A3@e>dGBkEw93_<7lJ9`o?eTycx3 zKO9R>%oQfMiqSmg;h#RZg{d&XBN+ZkaEmFyV+Hl#qelHt>TbK$HuY86<@71^dLU0wM>vfv|m;0W~ zhTs;a!o=G3aj<#C(Z3K}#pr7vr@-u>o!JoF!c>?jIClc%j@@eIe9j0^vU}df~y#vbZ9PY2-=y= zbC6q@3KKb=Cc^WZiGLxuiqQvR=0VrD-#q@j&$)%EFmY|<9N3iX`xk<%82#_~d9YNv zmCe(cTbK$H=Nr#~&*KfoKXZi%u443uD|B`I$c@<$+`?3tnARW>roO)N7lNx8J#BC@ z3~{zq|I8J)=&H=~vhcTv>^jOW1*&IL=K_(bV)R+_mh#nGRsKS76(ct8X(Ep) zQSmPXS22Q@FRL7}EX6GNmk|DiRNrrw{Ko6;@7{+2e-K>7&Qwz#B>(&5?q3M5V#J0Q zO=Y8W@-GBeF+y%$Qcga<<1YkPF=9#lJ42O4^Z!C{6(h`-?J+#)9P<}~s~Ax-a-!ki zq-K91xQY><>^u$2=3D-S;3`I3TU*pH&S7yjPc>YFT*V0f3z^khR$uZ*4RRGD{`@*(B zEZ7HEvEx0=V<5%v++Tcf6(b7Q7z~eMAO3~lDn?j@_Jw!7-v5Q*Dn{7c_k}6_b7<_E ziZzJK!BvcSv)LP3`se!#!Bvc?@v#A{`D*zWf~y#TM|eL@u& zf43->5YS@Iw_SRmwq+e-|{P9?ZPPqTJX`FQe_;kQ+*^9-&}WjhG~(fAf0u_p-eS z;q-Wk_V4#Xkmwg75cvjA(0x4aR17dJN#)81kSC|6%2OY`hr{pl8^1@oL4zY@VC9S2 z#@HsV@Zn+!{W!~E&hO=Du4;7eMb>x^m4}u~6I7KiIq5#Wv?^^vSPt?aW<^fRg`=t~ z_`JiObkPZjECHC7q+V$*B*C>B^pxu8M2?+Jp<1v5oP8By?0dEe*n1Tbd`r?eN*E~7 zj1pMI(*LZl2Zh%-m=GNrKF}h^c7PB4`~`wtpW1R0h;L0-A|hIno;G-(U896msK0_$ z_=<`|qs8`GX|I0Z(`JZ3usDajo-s{V@6dAO>l_AK6lcBU>HFKmujLsziB4<>bCwp+ z%fYXRBn499ZKp6;M+xSgt5_OetKY;ZTJld`v*Dj{T?K;WWZOj_xVR&~aHZ)tqm;n9b`TOz0Fa#89dz$O)%sy=_@ z>S$UIsC>&@CwLAeslc5NTDvY=q0BgMfxvr+7MIeB`t}EhXHk0Z!|TAbCH}6D zCQtmyn1RpaM~&VHEe`h*EM0oFC!`iFNqwwa8bFFSc_@W_=PK!d57>ON5$aj2!J|t{YL_imz_CFC1j4jk{ca^boBc_LL*?LDmlt}!#IK3z zwfbF-*c$;P@OufUaruc}4qj`F;CGQ&@~BnCv<04@;P&Z^9j6xW=mA@5WVBb_`ta^k zk~Dp332oG*GqCYpZ@nCxVCBG9fzy)o@ZL#n&CNGp->QXvM{$eLUeSKJ^lNgzRBc-H zRcJP(6{4$5cl(v z^e)YuJl~lU?o{un-yghp#?L5`I9UFH7Crri{Pk#{K(M^?=OCtO^rR1MN$B`)5E5># z;JXOlcewuP4tdR@$(n{~GJCSqD7VITdrQH-u?{p&YDT)*B2Snd|IWCb{to@#kHsBa z^D~;f^V%h!f4MgWTQK21{JpW=#4^x2o{br77e|m)r#C~2^Fwz`U==BxX6)`=9`dwg zKAKrZk(3&Vki+9)3btUP+1FRb8>h;_$)U_gZOcw%Vz`xZ&+xz<6IeBQ!vo_$uZl3W zGV_sZe>+mVT>)if@3tP;f{D3BZX4TMR)W1=%*Web&ZNeZ`bvQXBn1;#b>!Y9W4)J^ zAS4g-ktgY2t!P4!GPsmqDr-x8?1NQH;*J@o->VD_sxcqqmv7eIuZmFK518YQ39Jg) zyxTZ=OBMK8oDqG$zEszGMk|B;ex+antN18tNfAb@D_>Zv)pWEz>y8Pm;%PQIlcb8{ z?MUgdZ55Z2jvlzQI9Iq#`ZzHw3N3FLyj`&~G^6D*xUjG!&C zQqNuNS3)dTnG&qUJlIe$vn85)Mw3F-($rxSrl(*Fr&+F83msd!U}kIgFpnZjJQB6S zWSToBu!^-9-`=*FEpfoI2ojaLS!-KkdJ48+g0;}=kMd`>cDIA=NTW6d$n;{lJTQS( z?5f|dY@OK>)ADvAeFs|+=ohKi2e)8?wa^1ktutFYYrEB-)F%$K?c#G`6|2FY&8#xp zZe}adYmv2*H5)Cm#_cTTHES8Hm9TV1yUJ{dgttUff~i=m+%VQ6v+ZWKcEVdbC$NgO zu{G^1Gw+YgJBsi-iW68RmLs$6lIpbWVimp$B2g?jfLwlVr!9E#Tz_(2TytBlmZy~d zOniFsuAFLHOh4Yd&_Vg^8FqgZpu~Af?4tzhU%85ELJWE1LS85NYoC2x z^yddB*z=>#sQa?h+l-Mur)i9>hwj9wTyHJTt)l)k;Hn!#+Z*fDKA}gn#{OvB+Je^P z;OaY*84W)N7lW99=n?42obxJxPR(wBK!l@}4Z4^H5C;Vg%orajKnRqC6)>olk3 z^cN(Gh>l~Di^RaTy+~c3F>3W9X?oqV`+)sYWWVTGn*ScGdGoVewn$mpN)mbm5X1Cg zsy6ezpklQq`FxeFZA$8A`b~Tv?Lm6=JEm5QsjlGjvT*|Q!G1wvnnoR>Epb9OgLWbH zq0r)R%V1-;H1BnKi;<-LJ^PTgE8Mk#b&lxg;w`S|`KrdHo&M2PB2nv`I~no1x8`D1 zQE$7Pz-CB0TfPhV4$`@9yeJHDc< z^gds?znm67JmVKVuV;3jUmf~Q{&hFw_c^C&Y+OnNQsNvXu*$S&_)S!7@jzRg$4iUL z9Uu_+9>g?liIlibi9kwV6|N7F7~Ue6HuZV3R<_YV{f^>$58!(R-@!EQ$I|ZF+R5?S zks$*Vd>7$;0kA(wI=*&_wq@Ex&GA)#1*>p$e32M&--WDj-=#)v%ov69tBdasd=2R@ z`Y-0BNCim?hmHyxJF~lpy&b|TOw%~qjt{i5SMRIK(=tZkyw)&{uOS^LepsUQELA`| zJ|yF96!XD)ORU1QBpG|J(pG3=wK)|-6x?2MY4KH%q;T7e@!PrO#WWf>U)Y<2j%M_o zFC1-;8#aC_FK>H!j*jo2+l*9Jq;xl0?)TKNh0&a#J4xv2`?b$fqU)s~Wr(ArA!gKL zfxxO})|#Qqc?Y?M4_o`;RNh93?PaU_{nLTaeGK$-4K8&^KJ;p(fv=RL`!wjsKg~Es zi2(cJO6tI!spcD65^TXl!E!qcF5Y(Xzm*t~9@bDP+BDW9Wou=Dz$!6Uo9QkdY*b0; zt{$|{(7pS`ACOsEOS7OeJ_lr+TN-2Q?0xyhkWK2)v7?1@VB)@Us^Q`)OL_6H12k9P zy6=YYZm$d-iw+P7tiolYU$P$WpbRQ>#@N=$hTtoTuYy<(HqNF0u@M;^?`D*PjfQF3 z$ZC+Kc{$jg9aN|P$=F*4TTBR@&LU#D4@}T>mWt;vV~-K+16xc8oz5b%d|-m6vsCmWm(edvh>98TElJ zCWKCB5!{EqYY)FuIl)xCd>MBw^T2&ziwU9o$Rc91BY4S~iq})dU8}puEC;rj5W0^n zBFhIRcnvZYZ*Q!}$nd~(g)Jt8?jwuH@_`B75}AtMH|(AlePD|Tq5H@n?tE`-9Pi>s z9Ii`r2bT}V+9wLgb2c53_w2~28dnyOmqi_+K0X+ezUPEqg}3;OpZPxD>| zth(1Bm%9Izt?ahyunE!jmzh?wS0Jfjc3&V$95z>{6|<99+&L;^T9R^HEvBV91{1RG z3SianZx(9I)I#!mYg1zR^xm5J246C!^-F;W`B^}1Im1C-`09j=X&UqF-XyK6tsmKx zegm+oPFf*#Sr-R+e@Ro~-MD4iqdh((XT1*sk?LJUb*x@W-W7FP#gAfE>iMRnWW%acCPdq~1KQOFo}}{YUjh-i%t2kyxx9ST?VOBh8s-1}Rc&|v zCS=*@&wy3Yol2-f&y<(@hMYAarrSTz+Pl{$MK0u1FyZD~LapDzQ67KcqKs*}Bm2DX z+Qp>WWYg+g3RXq*FRe~!T1|eR$COz4J_pI&tsHsXvamp~*z-I_Jfg!)Nqi%pH#;9QAsRNULM}X#$>JqufQf)5 z#nc18O37XuPs*64@%mP~kuPyB^;)S8_h?04eJv^w;pzF+8qJHz!HFkj zOw*Vg-S(=z^Ry<#XWA=Rg?l@ZnA7>D`s;ObQqaAGK-B6{P%Zqpgq&u1TE;Y;?K_o2 zJGZqt37u11!7AL_iNvNmY3iZ|O-RcPWd)+s@*?Vp<>h6gc234Ljp*QIrxn@Sm>jrV zM!_oFcZr0jXDRJPFCa%_D+$D$n?==@wH;+^!zCHh^l8x6SsS)WCJ#I-DOiPjJCWFI zQ&$^P!Iey~sv!_;uMEDQ7p5gC+Q&}|9Wa1Q9ug1ud551%xF4hUpv4Gn(XpFqJ&m~OL8Q!*4NSm0NWPGk< zz$)BJh{WS$XEOe3S<)qTuR!4E5~k^#aKVNoa&RHCJz^PP749WOB2;clx*U?o%CW}; z0zU^aO=C^Q_9xpM;rYPllIlHL!h>$|J))`wMMOT67+l5zEO zA98VML1EN~`!2EfnLm1&>bqztDPcEMcsk>DEVjgq(Wt&kD3f8GId0d>L7xI_ zKWbq|XhvrqS9L-^KT9zm*$`@WgkBB>ciC2Hl)Nl<#ra=J3}fPD<9y1TKV+qm@tfmLD@sPadn$^2@;Mu&5U zWo*Gj!0m;q_Av=M*St!JVpOiB-$#>s^3&9FFMr9{f{8EB=c<(+&}-#U z%pgglQb!Z>r->fY^L&5_tP-P(xpo>&o|xA+rr$0I*n$Z$f>~m~XtK*IHT7fRf`BcU zi1D1G4zH60+t+NPxjJ-i6nW{?%A?Jc;bH!{sX$8kr5oBV1d9YF-9XfKa9*X@9F;iVgz6d zCd4?99!H0fi*qX&b9hApwqWA*&|&K55mVr56ZRdwf5&0OCZ8eo$VHU0B=xHN!85IA3LD5>#oVyZ`r z@dANWVzkhCjfRjSX_wva-Jc5Bf(bDqX&>_;#NU2xYEu8{fGwEF=ifsedN&rHtYy&_ z`uvI_2g&@@0`v)n39J$$t6ussnA}d-jq;1g0lnU4AULPpBEhe1Lw^z4x8V29iJfh{8tPUcT8wR)^JE<2}4P1gzWn=!GWqnld3d>8n>o_&Sg{A~nz z7`e1Q4Gbs{ShW*Hx2F4f-H0Hy20#7B5VuK)Lyd{E6KbhTmU+YJE$j__C(j77?!3MG z)wNp%0;|L*H>V8|WM1jK|2RF^D#X*qgjr$@^~%*IP}-8sG_=?Mc-9WFS%EN7yH@F&&(g;=s-^B(Mtacq~ckop7?dcf4Cj1(Coi z91)6LB}qzaHdMJbmhOg0e-D(5^^(J$d{eD@?aWHE<2(0z%DawzRR1Kn1rsdIk7p21 za@SRU(f{$eu!h0vL2Zp$zU>&KV8@;*n$b`achmU zx7*6H*%3-qC}%^St}3LS-P3_!3nuV99-R$8SDCyoRK^hJ-B2K~YFWr$_D0O3f8-gvEz%!VV^xb_h zah^=veWT`Sn82#}jwg-v&s3Hpzg(a`uI`D}=jV5BJEgK2*MZBNWj05PRd^;=l3rPi zB!;T-#=EK~Tgjo5(v|Y8K#IKek$?HslTQKopY6~suMe9sr`|MNd+xNZ5dCw=h4^Che^U-2- zD=o3pEb3zgCEiiuR3^bKn3$Kph4%VH%S~efg6i%+8L|eQ*M+n2%z%4YYi5%ttO-d;gAkpuVK_ zasOg~_F}TDUTfC#dTMWWxajEyMFX^={;rwzk(&~g$39T^Q36{qG4EP{PG{8lCt4S4 zW}Q-x)B3;!R;7OO)6PDqmsuYlDG^JFORNTw1rvqV_t1T0)cJB+52I+EjAQkI2&`JN zrkiFcTQ9Rdj!>oj+U2S*{TEv>QMHM$?jxhli_yB+ulT4hX?4lccd4#1>58dZN3l^sYwk{5wD!O6vm?Sath)7wvX)kIWjBDKU={V<>?w zn85W!zwL{;rA=#7OuI+x0~1))=w}D5QCR)V8uXyVXYXR#D@tGsCU8B`abk($+AfE# zYU1Wm0)bT#qkR64vGV|{8u{9IP;97(UF;39cM#!bqSy-{iUmcnpkTv>q9B5by_dE3 z-g}2TaqX_U_O|w3*4}pQ-l@U+pU%HTj;sR zrPV8W6ygE*TJzdhY8fqvt$ESEHLu&Lmc0eb5up*$kXjHeNMJkBJ+h89^_pp4^Lx}D zNT90BoL1Z^ov*zG1)&k~mO_#~ddFG<^?Jd}o)Z(uz zwK-alz;>cv!i+DXi@$5BJ&-`v`6@xYL(jVQ7Mw}yzVuhLAX<>XcB1)ixS|)Kzmusw zkU&+RoK1O+gSG4}=uPSn`rDNVv><`)q$t%ZEazeL_b#;u5++r*0B-3~!`^~kr0zj~ zMVl*NK>}Nro}aI|VZBCw=RX~6B2Z;+!CEw$iqfchPc8VoY7^eCLt~=_u{9%a1#stW zjqEL0m57Q&BoKiXB(R-m)eDWLlQgPMQhOkQsyxsA`K9Cr_7*Hd#APCO5`h*Zu$^cn zIgKWrMwOVCAc3k?{r!0M^>ytnScZskM2sT>El6NHDM~zzruD}U^5@hZNT4dyoJKtQ zw6DDd+Y@nzhVsDm{boN@xnz^`xrb;XEZlDv)!Ziz}Y0W zCe8pAu;ILE=WC7wm;`3I@z5%rb` zoY$g1vya)MGVlQ<##<|8kJIr8fX8<9rzi#2-mqSwW64}`EWsWJM+pWi|tcubW0Z70idVIXhA}h+5V_+ zM1qa`o{*{?_+RO_2j3?)s0#uFL;uaoWaW|hjz-HBx`7{6Vvf5(Qmr^6z{YwL$__pB^>hrd$ah^d~_> z3le{LHss&sDj_9-s%K4GaM@1A&h7ssXlOygYkO1vU7H&|kU-UUqxL@^XhGtKqt@^t zdPeEdHH?vpBUrR%K|=JNn{Ktugy91TREgHS+dbe11X_>~{cTRD zpP8U~(Wr%ep-QyocRmaPEl7yo^PLYP4kS<|TGNy(QrpHkT96R^?YmqVwL$__qBUhZ zkyO;1Pv`n;JL&g?EjbvRN=YHOyC&+ z`xW+38*!sjVV3jqV7=i|FTV0rAs=y?17K%eu-d^kQO9FS#G!axYPR~ zb8`(dd`JtbgpckKUKZPZAHg6YEl7y6+-~#XMECTsIC>a9qy<&NM}fnU7Tf(R!5|?m zNQkoBZu61eHB4*S=OM>^p-OB|zBt-qyALNAB%}oiQI^|nK8jx+to5r{*zh4Os1iQf zUYTeS_kF)7qy-64mfH;?!Nw)%;t9{t0VRz2AkF}LJihhccANG`1kT%#{yBm3Hl%+} z;Jgj#pA$F(MEd81$d9~3YoaBRK%>@_E0H%zAT0s$e}ZXF-6imybx)F;k?Egj7qgho zJq@osshB|^{c|7rlbt#HRLCHZ{yE{eBR7xBna?1Q{yFjXULijCO%8)V`sYNwBJRA* z?#u>(^v{Xal6u?y*+6Q7bi_@FoU3A z67tCKpN|AlCE)`JRE3WT;MHqy{DBX&AR&)L|M?Jc(4Pcj?T45F2n+UC?8i2(?O!v2 zs_o$p{B*e24|<85We6Xr3LkgZI^NCq7X+#t&K$7jT+#3s1geDZF;@c3M1qK1M9dYcqAs-Nt==~O z1%axi*PC^<%~ z)$0YR`Qme)zaUVRYj8GR+`Y^%2vm6n7UmV}6#NB&s<1TW`1?98zaUU$9qPrcz7D@2 zP&IzDFVD9A_7BDf<_c9&!{|wa<@a9@sG5GaDSs5X;1>j{a0LIn1yLnxE7o{@KR!@} z$C78+J&ko_|C>P7)Wj;rs<8h}pz7zf!nqI58F2QYD9-hw^}mPFx4`KSj#^nxw=fVdPvMf}X1v7z`9}zYmv?7x~qg8ss2NJR@RG2qKK>{s5 zB5Xbuf5^+TXO1&g%gQ(Guiw~adUt+Z(R9{PmaOWlTsvr0*xd84t<_5m(U<2Nl#CWh zi}&-*@6k`_b%v*F)m8trcZdZER83ssV(l?Mr~3BBF7i?A>t@bg_R?ebpH4;#66W{l zC+1A0Ux^LTqx^^XAb~3Ld-P6E3+YYn*3<9AT}eU$ReViu>xA<8)UScbRI8^Kis<)( z>*}ixbWB1E66W{lS01RXd+#fzZ`t&l4-%*fd6VCob!HK@RjIw?BV&P@dV`E5b?rf# zWV9e*evf`rtuFffl{a{dzh*%KRq65+bqni~iNSNQF zzh1MC?q6grU%t4G1qoD{--_2R4$-?GO}0MH%#+a~)>F&(=y6YqlBa&0e&SpXWA=a+ zBxIS^7E&BE=P~-ND2Zc+T&F9_XFG+dn>XGv-f+Y}_(87Fhg1n-d-m(q2&oc8>rRI2%gfBr40~k&r^;M^dVJ(cyK$E)mdPBCj9eSNtGb3k8jI5q#5=LA5tZV zSCiYYsr5$wf{-dfG=CAyYE2va3qq;{acXTVR`CABUl39yh)erhGKEe11tC>}SnAc1 zy_q%h7lc#^f;qKho^R)xi3GIB^7_^5xhMyX2x3tlw(BT!d&qsEN|fb%{`)pZLaGEI z`@;7G_9g6z1!|XNP5pk<+mVne;iL3mA9i+`xcm!3sswT9 zLLxhMc;7DwsS?DH*<+Y{*EPQ&q)HI-P5=Mh=29gH`JDho>78YT;mNaPye8g>k!Kuy zKc@Wi1IG4Esl*#RNT4MpAq4sxq$oV)#&xr6(Uqpd}?CXdAJ-b3MaH)d__) zBt%)Na*T82qA#5D%|bqqKubzO&^F@Q?skTc)7?KYBt%)N#Jf_$hj_b6QIJ4ON! zqEOdfhL2AH+l{xj#J!Le3dpJU>%S zypJK)SzRwalH+rEv0bc<65GEWO9X)`TvL{k5O;$OQWF;Ov`6d?%jRwqn8x#=5Wb3yk-kwBGL>+Ue;S@rLIpaqG(w8~=1Th-@3;y)iqph~R9p6GY< z8!4~S*7xPKvM1Jlg(p|mh`P&_JfbYO<61S_j0r7B$g(8<`z5mkxt34t zSC)lJl;tQ8wfc`xex&*l@r@GR<(f2EmT}1K|3$8el88fEkPxF;Y!~#;2~^2F*@)-# zb(rmq?}>AIf*3{OO)X)OWw91RzRmMJftDW;wv`->m-NwR(L1X0YKy5~y+;kibq)FUjkN3LnbXCe|m1*YGNzdh4zG zC$JMas_@MECL^PcPSyCTTN`=Ns03E&emS0I&1NDBpIMi*I&l}Tcq~#!i-<`Qq8vP^ z9N)M{5T~@tK2P@!=iA#ye@94_xmGnZ*Gz6drl9`(LwzHTpjR62-Euvj-Y5N!>^gGI=eBci-RI0^6M?F){f4mg z`&#pIOU1p6@#%uBuJ`)szW%dK1gb=P+zk)m|8AQ_#GdCpljoi8uh-i@(IBJ+iDx;6 zu+Y*WoK>Ao#D-1DzW{VQ#-zFxVV4y_0JW_x&MyWzut_p zpaqG>)8p9a0`yBV1tt;Es&`{cnfF8VqkXokNTBN7_Bgg}bz44m`gkJZ+Yht$J3Ckp ze36YIfhw`R+msNl_Z~w;o<;MM9}FL?Kd$a>5YmFgpqFth_(BLz$|mmImH*Voaw&MA ze*a^%i9l8DkReQO+J-O9Jc@{!2fJFcoQlxjJUqirbctuV3$^5-JBAuVT(W4m-#^a8v*y!-cq%@`sA1>m0G`(`ntXgIu|0X~dir8S2WNwj z79^S#OJK!kHQ_@J4kV()iq@9BcWUd0rWZ32sB-p8V3S@o;*k~l5%Fr>{$%IHh4tlX zJ%cDdx;}5A_u`$x6Ii}=b@@k^NTXK6$JgL{1G*A1?za-&TOa1vm)31)5YmFgPCD*t zLu&A+bp&znZt$L$WgT>fG;K`;szgSLZK=jf6$>NcK(z*+F9Fnq|f8lIN~ktuZmckj7^BA>$+SgzfvuUDN@ z&>*A*iO*RQSht;lJbCdlBI3Gdw@#YZRNrUGY9df2e8{sMy?Ot2xFttuu-?8@IvrJb zRx=Y>@^!GbT^XgH%{83~i#%T8*cRL6n5S=fd;aU=m$`$!{p)Mf(FaGZAmnj{zR+|& zy|qh>MQ@m{oF*)Coa0Cp+vV7#Bi!_8%i-pg_2mnzX{f?6XeQLhigjR|m59R1O^cRrQhsphoBftHIj)9*On zng3m=ZHhR^MZ%rMHPpd7+kMa=VQfbSf{~e_*`}NfN;AHB%}oiQI^|nKB_w2XO!-uq>O87Vvo0?6mBW9NLCjkj*K|++}c7srw`_qz_ zskx0KgS2cV)uh~cn9_KrapsiU>C0d3g0{CL!kdVcs+O7ZGvCj)E17SE@Y0@$@+pX3 z>QIJ+EE}~-2-@6MYvZUGkxNTTqIdT~Z05sx6nR%IhxKT&R+`g|^addaK|+)#rYg$3EK7;-$$BZNX`Xm(%E-0f5mF_x z>#G!HX$K49_THO53(^hI`g(jeu7srp_bbY>k5PL#wM}}pI8GaU&&h}o38@l3WDljY z^U()B!;e+e`W36Li+#y<7Ui-RbFwqdY%}CMm7C z)766V(q-W4z)Dc9ar@PvjYEI)r+PP^+ zh_Y0jINsP&deK*Ffv>fQcu4ocOA#@L2(+XmHe74W6aBgnQI=M*HgP}7E8Op3A_Of} z^o2*u(A)~&(oXoeNrV>>d5J(vN+PeDAJ4O1TtU*G1mjU&U#!Ich#Pr_St>fI=iw@5Y03BR{zBNYCGmGVYn|;iS6Cy`>_3i;{5R>-M-yRpZ3ub zyRI|{X+c7iQw{TByK@PG&0Sr+;i5QgW#Nq95mF_HHv=r}$h3t-B;;t}Gq7VRZT~Ax z7nTEeDzhE~))|q1o?DJx{bK_kUo9_NShPF~o4tXE4HL&%!mk(6($ueOB2YE%dLHJs zqdfb!y&&eTaIpA1bJr3)YnljDMU~6WT&GoJEoO`LSEbwM^C|tMg0}r(brXRq$KuZH zb3!F{v9us&*X`t8sa#cU{S^-rfvN^Qo!I82O7OnH%vRO3iK{D{2viyE^dIqOnIU^d zoT#nM-c`&*ph}e0PM)lSuej^{`BkuY))kGkghKhgBcw`Xy>iKFtmSHPK0n#`56h&f z%UOJ>z6RlTr7)|ybu$mLmSBmu-PnbPn~b(`9^uaBP1;06r#>^S{`VtT$*BWPgxGI} zV})7n?Pi+3W))j3`N*~lY)z*KgOK||AC7cBeB)l4&Auzn=O>pZSUOKuwA(G(ng~=0 zf3nBW@ya!8((=nr+OljdbyQ(5F%u7*JMH=FbO-Hm*_TFyGAEc(QNDhvI_pJWO{8Dd zWvX|<%w4pC^KO1eNR{xBOY>$87uPArA>BBxu6zAHC zu?4)HrbcVo{fB)=NR{yMD1(Jf%q@twV~g#%nKxb=@4D8C7Tm8WXB=!{tDlK6sD;0+ zo@#WwcFY?69U)a>Pv1uE@Sb0G_boj{Te$O$iWc0jD9a;;?U<;;QS@EujO^Km-bPIF zcqItA-AtfG_(MXLZA9Zg>S=ef6xM`F?kgp|sbDImZ?vC36eOet2~n2YZ9ZHtR?|Y= zD;qwf1y#bgr|S!~eWNy%UGWDAX+c7i<#roU!?%R?YPGN7Lt0QJe0b#kOYM0t(Cz~X zX+c7i<#wBo5mmBl_4)=HKBNUz!biKV`_x*~8rXdxAuULVvfOU-@z=V~Y;L=Dh7V~$ zmGF^JXSI4H+}G{{328w>l;w7tkB^(ru;jq5h7V~$mGH6W?nJdgKa1T564HW%D9i0O zAA>F}XDciBHGD`5s)UdCX~I>%{nhL~kdPK6L|JaP`RJRe7xR8P(C{HGs1iODYk4)M zV^zBkB%}oiQI^|nKHk-HVV-^C3?I^hD&gbO)yI~ER+a5OkdPK6L|JaP`EY$xLuGW2 z4EKd9vHeP)NXw_ymFzx{kQO9FS#G!au>G50%o9tOsbUrT68n{9F@F?qCVlfE2~>&w zO4SdE1e&23amf8*-H|reDy2%+{d;2b$THSphiti$K15AqS?p=U&S>kk4zfLvkQO9F zS#G!0s!dCU`+T&uxwN24_?UQizO~9|*{_h079>PjZnybZe?N%d4UaK$B`v5DKIn%< ztVLbD>}`&Ov>+kMa=XpPKOd*@d)fLMKBNUz!pGhQH?6guRl5%)qy-64mfLMU?#3kZ zGif3XAJT#<;p5vCi(rtD79>PjZda5pUeS8j6<@8_igY!u)#TMy%4@Y&Zq2yw&F&P( z>f+IQsk93J(5#z5NDC689KIls$3GW$Iaf4_)&utz<8Dq(z9XbcT(>=r3g-7O_9mid z79!pi=aWY^GYDzH{fhFmVJ-Q(QGJPM7aFbCx=&vfimmh=AyvYM=e2g+`G{EGo$LJo z{l?=ue8O8#gOC>7uP9%g9>ViFiYKE{{i5|1Q6YR>u=96>R0$t(UY&T|QR2Sn&RYX? z*RLITtba~}kQUspC>Pq=p5N4l5b<^tWp{rse#Y;liu*#9*d83wg{%FAf`llq{=E|)Ia(0gmq+W4GY9jSJ3YQ5r0Vp(3YLPQ5%#rF5v2#{9sU}{ zkGf7)(SrLG<-2P;+X*Mui)UTXN1xWT7yVXaf6It#-3*H;2cD1MgPn%)_>TdWd-ZJF z6{UZfMBZjzFMUhl{tPWhh%4`>eD-}!xs<5_-GAnl?uW;rm zUwfmKail&vF^KM64kKEh!0k2Z4UAd3#lTf9nmr z)z^Y1LeNqrT2PJ~x*jCrED`O9KubzOj!i{LqFTLrpGQv$_BG<@RHY4f|2NWzL&hZN z-;-MNtpj^e95ab{Zzs?q;y~hC&jY>s8*#{(1l=jPJ@2tpJk2;nL^&dw5`h*G2NJTj zGzO_wJZoD0V%awg2~n0RQCm6w73DV~ZV~a62(+XmzD1rrPa=0Y5}?m7oz{qBL`-Mi zr|DoL4jGf6m);2Dm6s2uI9w?XUm_+Ffff-565k@9Pqj+hJdf_V`+yOL+?SxGO4L>! zV-#fz5l@5i=oN@SOG@HfGP_b#C?B?2ueiEoh)JXBS0Ke~eMe!Z&62h!#v zL#D{;*3EIz`t1t|tiZOamf_yr`MIH^c-!5w-@%(L(XntNJMl=&O&dH4!D6RaITjcj5mOj^{|z zJ^fOOPp|Zm`j;Nb3{_LYs;CndcHtqjhom45EMRJsV-H=walk~Z%iCV9riSrAOAJSv zd_=6V1iE(7`<1%MP&FYUL=DIt#(nP$N(_ z(>j^SYt++oBJ{CiPBT<(KNYQp=I+SnUmTEvI5uaSrRI=8{r9xlH6#j89HXYc9Lk$K z?8lL&-xwLXOx@h7m7dl=or%~IH&?w~zb$tu+lM1fU;oZbza-`Cr|U=aXsGfoHdEc# zrY&FK`W>;RrmE`}-7=!Ai8%9qlj?fE6`xzUCr6r&aKo>vk$D64tGTmksOq$QnfiJ` zYhI{#WD4TQ>*8uX-%5IuZeAwBJ=+%bpT#Ztofq9X(zMzz(=N5vq$>LDR30XxzjjEy zcBdKNIjk#3n(n>2{-!>QEvw(sEE=k2chObvupmBZaY|zBkzQ(Ga&GZ>4SDaaon;a3pfnxS|GX{@lO2cnT2jaYJ3~Q&?ZW zxsHY^tf866Tlbk-wEJM)J^GFH-h*Nmm&V(>EKcNGr;R=vC^*oI~{Ihj*!{x_&FY`u1xCe>r7X3ZnRlitI?y!TPm>^^=kCsZvcX zkT#s}>5{;arg=%5ylmc)!TP82zACED1$nCD(}nX|1yT~r()+S)S7P*9V~3cCBd^-1 zms54-d$Y%Jr0EwuT`RKTLu2%NaSv5gO_z4LQL7e_~I;$NPrSB{< zR7I7GHebzlw=JKTIwetR=wdc_ZEwB3=E#s}^KzrA4r_vo)zT+bJ+T?T->?TqT2VIEKhKst z=&YY!=)#5{xu!ad2;h~jN0?MKCtO!6ObalcN766%x}9W?Gll67cQj+TFZ5w1_HA#X zx&+7TANw~}aXjO=%dpMEveMF>ubL*tc}%3c+9+?lUTM&8Dys4=-EMi(u^T`ADv_Is zOIuf}yRr?@KMvkwB5>RxP1m*krm5?f$LUW-JXTRvwOD#J!#@!`BxD#j6HdJ!s&%su z)@LkD$B@8rhctaRsO>rR&pxqw#^AyXRr^|cs8RoP;TzV*b2Bm1F(;cII7nX|QrSe{ zxI>zr@cLzBeFqKHF9tSZs2bj}gF2{h82{&93^x;jhdf!|ef@Rcze7v}jyt3k#nGi4 z8?z!x4|+I&p{oA;k?N5)9r%M51Gt%p&(fN0*81qb+)U(jpRcy2@zH2+YZHMz9BH~I(=1d?pEy7t;x&q)3TNbI;&8Kr zs)f!UrM)Mc2<+iV(;BZ-v(>hTd+U!@u4bsh8M&EIPd!)fWR2AO^xk43u!kc}ztvc8 zzskmR)hGUYjG+qW*Jfhj9A_3;tcyNo{y7tYJsfGe1L^!ieKWhg{z!esP=)hrGjS!a zJKNGFL_fFbor%C6jx>$I3@$9`U~@e~>GT?^aDHtjyl&NGZu6Vy#nenD0(&^piZV8L zX;$-SeLa6_R}ED-7c~=+gF{)#{=RzRrTiuWM-XZ^hQ-l`4f z*5?Jzi>I$GfB%~;T^y8t~WS!ing5EVb5lZ7V&ip3y|0>RMu2 zmN$J(zG-MjBC@>u%4WF*>#wp^VQ4{OXvZ|{Og>-!d9ZkorRh5ttKdvxbubowlbc1(Hafz@6dve`{KsV z?I^*oy>3B7W2f@kyM11I$7*R9TEr6!Nr-av4EjQUVh|ApVsmPrKX~br`&+*wq)HG8 zR|@eextkGjS~;wC-~E<%^9VJbm=tW4kKaxR;0x~;WuA_1-2Y@VqlS@H3vicFO^EO; z_e%91@Rf%gX=4!5f<&KO#aXupZuAXlQLDEPeq*DK=hb^JP)!7?M6DK{E6C6NC7y=g ztFVcks9#*))4zg2NDC7C-Q5_AE5Wx0%ib{!p;^R+s@Ydt=zLno@$ z@U+X+$x9ve;$MR`v><`U73w9mdb2BfRefZpGA065dzQXYXH=}uFAWmCeOtFkHr0iG zb@5pl4J}CEag2J&l_ci;x|v?F>}7@os&F(b%7Z0)7}J{R7oJ`!t+g zV=Mf{kU$k4V-zKg&!6l>V}JcqmFuSC6%yv`K3{W0y|1L!Ck}0`eYxq(CZF@vaT#`rSd%My_OvFR;Yen)}}}Wet$+QiepyG zi)ztH4*CPPHX2%xz#J+{^4a;!Un`@(buVWkQ1y4ceC)=73cTX_VDb^|Gmj<2m)7sq zD6gRf3CsxnQta%vtjM}rdX0rw84{@Koh?6mp0Og|lu4{YS~>kSTdvg7hgP`7(1L_H zyKW6~YK5CM&|StgF%hUTpQAj39;?;2D|*{jZ8SWdW2W&KO!qS8KTywwDEgY2Z8WqX zfmx>&jhk1q?!(;m91i781gh{DOy3H-y^{GIETQKqQ9(ls5|~3p@jaSai*KsxZJn+& zBv55Owy#^3O3Sp_qW8OS+jQnc0<*3tM+O$r7VfK|JGj;`5vXbuQ;=<|UYc`#{wH6El7y6m~p&XB!~(VuI$W zIWS<%r0Su(hF&_hq(Mjv5=G8DP#>i6;~t~Md)p&hB<h1VI zUU;=wYjAV*n(CR3M(FJ_o@d*C)7AYYTk^hYqEVAPlUnjWk`wuk+(*^bAA)$kt3!zx zw04H~mE~RZw{F)NT0|BkA19pt~H+;H-_gqw_SZxE0}8)#a*=-)n<9OTNI^Nc|3!m zMbtzRSVNk_O&P!Ypi3WpeBiq82pI=vgx<7BmCieIUY!17az^HwZ?(GfbQ>NxdV*1_ zrtjPEZ4ndsq+aXPhh^IEQRT-`t)k0~^nPC~PXBX39)=cC6G>nV6(zJ$=G`Bc#proM zntVsdI4~o$X8S-l@4fUzmAvgrC3y~7sV*xL!VBJ*@?Wi-J5J*#d#qHI;vsxj?#Wau z*ImQB{~qNL2K16o!anEujqGd z6lKIJuaC21^^Ojz;X@LrO4Wa(YMI)a^FqRhUm1_xVbn`nKAvGBP$eQ4?f*~a`9w6y zQNyQ9hJpH*u5kt-ElB)(Vw<`kCYU>GbBLHR^xx{G>h;sdcDB6-B?(kHxuUb7PZLi{kB49eMEt~JkI3={h%*>Bjx-e!=D%*USk&XCL8ywc`Yq?tAz`QC^=w~ z_d^*y574n9YuE(DzD>yt7d$rj`nH9vu0aq)KDB<^@ieIfPl99 zz0$f=(;vL9Y!K3dM9{&H>Xpp(cs36~1ERl;|*JQ`mcCf@BU z6ENC4aYRu){8$~shqNH^^YO-n^G*PCWMs9~r&M@ra7zUdE!@$M!^JU&Ke1?q{5%qy-7brmpPT;mZ7cIdOGY zwdPCjRL)6!pv3GaXB71Etc)Hi&{8367VX+=pj@W7tcL(A#Cd@LGTa0Vb~xhHz#@cK;e&NK#> zd$<@r0U0UyxjqhspTf9DYMprAIKk&FK2ywm=M{ruvIOF;5>uO#7`uiff zu*k8EM+qEVbhX`Uw|5>z(RXZZYY?)xV-FX5673XxOZ4`z5zF>8oqn3`8+A1ZX+h%2 zoP2Eav5Nd%F7XDB#o?v*`OHatrC+3pK$Y+z`rE`Uf(V>Lx+VzFt_%ACXaeS=HG@ zpem_BdDclQz@n>($WMPPtZj_Us6}LU*3g1Ph1_0jb3Ye$FiyO?)M605b$>IbHtFqg zh6JkW{pQW;_HnlR@Xz|2I`57bbI%*AwcR#T^(!1?yfb$6)h_i>4?m;4_rV;s*v^(L ze_!$TS^d>B)or>r`}=c@h885|?zXC-%bVDV?Il~VmVc$za-Ik>5vUqdV!k@%VrzSL ziDWW6O3}`Lz=m&%T!x0X+?xaMD*Nx z3@u1#_d4)#P2=svLd|^iEtnSEl7Ns6vBHq8e}IvD2zLw8K@r0 z7Hc9{&G2dC$>^{7R=tV>_wK-alh})Nq1y%L3 z`}laNxR&lnTCGfe^N~T+>hIEp*o@N~Qyj1MEH0%jI^n1dZ0KY<`XC|7A*b^*ZXB=D zK5^7e)_TiwSM>OfkSamQVWYVP{J?i@X+2!mH7wPQJFMN=APp@@+gL%W$Ga#Uds>6(*>--!_C540c=GxWCFCVL}$3%1-k zon_eg$~eLyfhz0^^p!Lso^E)>TvGHBB+}Hmq0TB>-`*2zFF2>Zi!VpdK4MJ$3RQg9 zKkA~g7W=#5pCWG47ZBTPlPFi1A3QH%OtcPwh-^fNvl?2Ez%!hpJpZUOpNvd9LAgQ# zRTz_^ydgp*;twLwf&`wa6{T|11QwR*3(G>eLIPEo1x4vd#5^M2(<}omNZ^cvp8PD` zq1HWCm6doIV*+l|XI2)wzmk_aw2uC8&g2eV*kt%QA*4}r=AMB;R_SIP9OtB^c zRsKqMHO=5)dv-Tm4q>q`qqNGDE6mS~fKqC=jp0UiF(!IfpNK>v8c=(n1&LyNOR5F` z?qbhwk2*fgcWZ!=DJulroM|7B-Zba@$uN+&7R$TJ!`A<2ADRGa)kt{Feds1$sV=U zr9^Bc0xd}FZavT^eO!b+yYCvLRztHn8@WOPRhR{uUo}jvb|%7^vWpfZ+WZ;iv$=F< zdv+t%_*gRJXv7}VSq%wPRd?F%6YtT%p4~Mq_9y?5I#ydkxx)O^d)q&GqN6Rl7!!Sk zjffLOL=k}&B<>dPpWI88+5Ng?d9vr_AZ-if3JFwUOmzMr!i$K_M4$zUerNk8hozO- zUEjTJvRd0&%S^dK0#%p=MVU;5Mnpy;(1L`2n_kKKcG-6mpDjq*4b;?I0spn4bd;oUEz-jWGHy#zgNZ5^;uzTa;b2ATj$~2J6Dg5%#_t zv3Hww;`U}nu8=?##zZqRBIXjYkg|&wBwmh8Zyl+0vG?8bi~3mohh{c%g#@ZF3v@@A zh(<(+zKa$lW=uqhMM$ruxXs&p4#BuDy&+WT((V&|=o{>Z4M zBOiZ6G_mfe9BS+fiF}dGtPdhP+T-ve;u;a6R%k&2Ye?5>y$kV;Zh_h?$`ul*I@7ng zwce~SdwZNAVhs_Ch(HSxm}&Y=fOHmKYsCQV0kt_2sH$DEg>_Er&PI=+x1ETnO~g$i z(1HZ^7)9xoZzOL@-?_V!f+*H#vUPIh_QrnEH_iHp5MRc#q^K1VcTP>R&Wj4QM}8=> z6Tef=Pn(k>a#Uds>CPPyhlmg}0JI=sjhbj(*Rrj>1*g9+!T(*7OB)*M@!8NEdOrkeOgKJiO`{^}O%%>6CwK57?= z;M+fcp?eH1G_)XbA$qB`UPLR_E~B_-nV6wJ?|scxbF5a&M4+lz#1gCH%3!vppCIO4 zTf|r2siQgN&a53sm~TyUs13`RXCr_3Vym^^sa8ft4-8slop8Q2dvHY%{>2vaG->K+ zldC&xXh8yNOK(UQ9m8KnSJ0j{FJ~f9Wv*5G#_PGun(kT^YIAJo8)LRv_l*uVdI`1- ztzso29TDq@KnoIBLwbAp+yXxFb4x8tTmDu%D7&|Bt`>-;*V@w39UiCd>4XV-5er(VC>>oan)(!5YTw#8SxWBiu zoAr$BVodal2t-UGViOT)K_Y$7zt(%6_3YV=^*O^UyI0q4P_B?b6~;tgN+-gDh|5Hv z1&P}q-ddLi)v;%Hf8u!lV%R@Sv`kI&eAyu)7=jqGAfwC0Y8{Y3000xd}NO`DI8tzFTc-AB*U z=HKY@3@`&sWx--8n7}yujc>tPsumkU&+g!P$6m_cHeE*6CVKpD@Ei+fTW| z{A3tfijPk$W@Hy*qPsXmEFj_(-MK>x596s3FH_sIdtl5RzVO2u<0y&* zsxS+*)`y7sM0}>~q6LW}yDhw3mQ?oazUoqx2WEYv4tx}2B2ZO~hj&(1OJDg$=mt(g*fu!UGP!;P3a(WM3&)NT3R{K==BHxJg6? zn!};RMDV)&X0yBYXTq7h%J88VFRG*;Wxk`u9tabK9+`Zh55m?4Hy%x9VFr)5sV15 zAc3nE=&pgKw!X8{a<+dIq#0fvXnin**g%>($PMFtLUO2~=Sg zXdN;UU5F5OanOPUu5+NTs${9opB|a3o=+ERB2YE`Zd3j!a)CX&(Sv5GT~3W>@tyi> z_$_CA){M`G6{TLtOZDEP;w<@cjEO*%`5B}o)jf5CwGbPt#+nFJnV%?Lc%9bzd$Ag9 ze?Y9(JgsJ2TZ*xUce(J+6y1#~nb%s^t07B!D8@vf3h#s|%9?6vtl=F3*{gnL0#(oF zMH;^UsUgOBw$e4V*lvZ5nf{$BKCJCyXXCttD;3PE69mzd2!-y@BY`UOYO0F#&9>j( z7t|K4F%zh|LvOj}znhr_)D!C&itMbT9e2s6ReV;<p9Z2o;ptz?bW6)%s()-hAY}ISD0xID3*x1!YA=&Us^Sx##@@*P79 zehD1+L~pnqKBo4~UW)Ck9BX=tj8BfuBWhf(&FYy!mDsBi)E=<54%gfvttbvYmDHoX zd|5TuSku!!e8OjbmYRFyUCXf+wOJ1GfzQ0~sTI=ntmtuLOWMqJ*po`Jrl&IaBnD~v ze(6lFq@L4jv!j++(~|~#x_~sj;nsCp@}=j#Y)@TU;{{JG@K}O0%^5c4=56xQm+R$Dl;L0jGM@>$zHE3K+J6zdWLlqu<%*4Xu^gOa9t(nMZUNeDX8`t&Hoz&@n zTC5Z*9nR*$=cKJL4 zkLP%tr^sK2@e)3%^!68mv}tt?S}RR%%EkSJbaXbz^;aw2&SwM97`4xuabf_struOt zJ(^$pnqKczB|t+95^0EDGNdI>I3kYiTRmKP%@s*p%hlaPpeh3q;|~P!%Bmm=obRW{ zt?$KFuB^v!J?+}zU3g;Un#S1@*TB;6zMkx>KZ*@!7n*cpXhGshmo7YdQx*HQL2Uj2 zJypLttTD|+kw6u$fu+7nL^UGH5P=pX%2p5KF`p~huMMt6I_VqVr)E3FRVu90MHQ}^ zRTL``J&E{}2(%y(`K~=5*tdfH+Mv^kdc1HfQ?nh9F%hVG5f{SUj(gc>uO6E+>D#)m zRkx6j&!;@ssAK+l0UoHKR zSs&0dpSqmlSXQ7jzw3L@M?{WUINB?MUn+RS#}@fiBJvTjnFzEXf$`CM6Lb$?=jaG^ z7{!4EsxGeV#viBq!^akRXCnN^M5rQHXh8zwqu*ECAFYp^KT3_AGms&Hss``6@tyOB zT5K!gw={CrCwMp}Z>2a2Tnyvw6u)E38O z-3ii@|EQB3Kye^}s=1-vxZm5rWLxChh}e6gPV!J9(1HZUNB01hX4c2}wY7>7b?-|@ zUV8p#BMywIT!St=|8m7@i^G|SK}3ki(SiilmcFp@pqYMY+;VGgsudEbdLJ9X6K*(I zZE=htVigfhh(HSx7$2>UUKp)6>G!)epim!%1gdK3-T2nTS;_VmbjYOdbUbc7Kyi4@ z3gv@`G_Z;m#4OxC-;o#V*4Q5T0V38BA##NlBrra@a~B<`f100%SEo3TKowIu^X+Z@ z?U9!yA`iXA+KULZAc65I%DS6Tx^MT&{95~73<*?yjEvw@9rIXikss=oL2vmbI~T{R zEUR1dR$ayzkz*FRo@>j?g^jaEzK)3IMC>C1El6N|bbUV4kM0P!<*g_VBv3W>RVY8d zYrH-35F$K?@FoH+NML+){n5X-zBP6z@7k{?LjqN$X3^L@+|eHSh}&uOsCPB^4vHhY zcMz|gf4vboW?`aVOFn18MtkI=?S$y^PDD#0(1HZUrzitEchmPiTE&$X-5C<7s#!CXPf0t&9(iCd2mPP9J@`6`V^WL8 zyy=pYM&y`<1C0atzGY|Zk=G{T2@%_gKnoHWAARR;c}+e0*G)#>MFLfw>IL!%E6>>@ z&$gnbo`(pLE3_bi@zI-ldphbKJ}0>~Lsy0bs?>h1c>DFc?U9eG^e;~vIF2V#9Bney z;`ftY7?EQZ^4zS$OI3ekk9<23S&7&{1X_^5_!MQz>gxKg$WuIu;y?mb8~4}ajuYS6 zBma$v-9(6Sjus>^K1Infl)lJS?hW@G--RK8sUC0ko9EZDm z@&38f8*@&~LasbMyqAlUF-N6uN1y(i_aR~r5okdIStT$g*gezr$G^~^Qiq{SA# ziQWrCRo%8$ zV_gYxRN)@Rd4QyfU3szpFC z{&GP{d*tQp#7H90f&|8=D0NGC=ub+Q)nB}A%aB0T%efVJ#LN8l$fvZo@~}bYxK432 zXpoi9tzF589JA0NEISXqP{khkHX`DP5OYzqAc67G>V!3!^@cAC>cJET5~!MaJO{ry z!NVST9wNMn5WNH~NML-5;t^g#*SC1<>2|heNTA9ss3>2uth7Dy8YR~9BHixrwG@YE zp;X*sgT;s(v*47nFRIR9;h8JKp z?U9EP(Ts@JM4$x;jE}xw5}!+td|yv@tKX6#fvUM5v-1+wtJx#B=reiPu@}biDyqm` z>)hjYjmR+zuX{bP*4og(9(gDcBZ*i|xk3vP7@t`Ed52FaTvZoyY9vrKY560o``kwM z$e$Cjf(U;i(1HZUrzow*rqMN;^LAa;j3I%l9%~%=soB2v$Y1&m=Z{Bx;)f{?yla42 z!21u1;_N@1JCFRtcM*XWBrrbuB2eE0{MmhrUY6oO0#%#b4_l8+4YEh>O2mF5#I+h) zkihupsbzx)ynJ{&-S>O|LjqN6-#oMq+uGP3`TrGm-hok6Ya1Vm2|XZ9LT{n>0Lkvo zSs)-?qyz$?mrw*l6G8$cbm>7#01+--5CQ4g&CH;9Er1|hx`3b*sUpoQ-+9lOBhQ4r z_v4T2d*?jA`OR#Z_sr~Ow)l$1rWSk3J)?J$cU$v5=HXxc73otMes2Ub|DR($RO2}n zznj(KclpeJbU5arkc>mT;l%Ie`1)^fvHdD_cljfn4cj(ef?(Fcx%9| z^2W01r5N3fwAq=jD$o%b&pGg1gn#R0Yl4+8WMD@4){zbZQ_gd>_u|J}QAKm>`mQhs zfhp%%>X(b>8nG|_HuCoW=d%fuwijP9&MQSxp(~7EXVo>QcKGM>4?$!({bX@&F2fF#^2G0|%8qFRXzD8vjo|ECZ8opvQZQenzdGOG_ zjHdjWKAvY9gL;~G<3bF2Hl44;2K=to-yc|=QEF47gTNHNj_J;LW36NHt<7%L%P~A( z!t*HHT7Gu-NH_hbiy5zOA>;fPi4Fo&xPSca z#!E(8rH9Tnvo^25@LUGZad2z-Rh*|TbHky|#>btL9Ot!bFGZWh7S0u0gWH@)mIW=xAzuUs8@@9`SmyKr?lN{$!gARq80|y3) zVmMgJn8K~qw2nE#tTLT-Yj=YPhVwz3C*s!fxzF$Sj8gSVn!{@H?|#6!!R~=s%wq#1 z#FpR|@;fxm3^J!YEMl&F%)eg(1g3ER_}!E87qLEnqm`9#*v)XRhI2UFT7D0qnSV-ZH3MA zGMq=@{0g^L)2`j#XLL@fZvNPu{|zC`sc{B?TgdMU{QRs@ml1soDK3jV19bTOo-}btx1k@5SYUK zO#N>O@)fYCC7hxK+3&{ymw)+s&m}I$59Qy~=PTGoc;@{t4EIugtt(46?SCsLklJ z#vVU*f9niR>0#md+G=C$pfBcuTUM5=wuJ`f1H7qO=-xHKl&p*}bQJ0R&kE_=oA9lW8 zWpK)L>t_z=!%mh*NFU33NTClM+-(c|?&C`EQhWgc5 z{5@EimH(UK#StWa$bNZ^qW?RADe;Sy_OH}BiI@S?-8oyY^3Xe{SJP}p^rd;C&fe#~ zyT-^^Q9B77L88aUM#juZ)&Cy?Q|*qw<@vXH*{$BS%9G;#%|9jml5tS1tJT^F^M}KS zMU7jl()8aHFODEVwc4luO{f&^(?3KCIs892G3h-)+gqwwWAm5yWW9S&OS8zvcm6s0 zh@+bza0H2i4O*FXV_Li-Y*7mTrN39}!qmO+cg<0K+BgZ}z!4+iq-IvKB2pmD8 z-Suu})ALcU96U|`QoJ~VM8xh6X4MZHy&^Fg}P`vV=A%2;{Fzv0k!|3CX-i<}NjCC^xs z{!ybL8ULHW6xD(EoZdO=J%O)weBU_t90^R((N(?E{yTvws&NLOs1z?cFcmj$s<9|r zU*|KJLeDw=+BZJZ|9#Jqz!W{wj#r|+SxyJ0=-GVj9mOdpfhl^$1U{DFR$&Ss5%oCH zf1M6Y1$?YtBQUk&W(y-%Xq@xWeT~2r_D9+p_0PFgm~#HgvC7ka&{4li_Yj?4)z}TN zue{1K zL=esYRzK?wwm5jWa3G;-N{w3DS|3rOtnEMoM*z?NbR^#ytDl~cEF4Ivno@Ja zpSo^6tZX}wz>z?Nbo9v{YHU0v9Z0B}QqKwv$#|!uav*^tfe7h1^hqxB-|Hrb{Xjz1 zl-fD=X~ynCVfKC?fg^zk=~ysem^meAoNyqaYD!h#?=jYS%GnMia3l~R9TOjHFneYl zDI7?sno<=;B^k?4marX2;7A}sI-V^$Wlq~PNH~yCHKmGP{Mh*IW?|cb1daqEq~o_j zS*!vDdk6;-s-{$zlzqmExp{2|5;ziwkdEN8MXVLE?SumfRa0tT_Y+2^li6$s5;ziw zkd9*hD%O>CUg1DO)go2EOM? zqK-fgBvef)-a8CBa!UsiI1-4E4&FN~>ImdOLe-Swy~Cg*w{#$ZBY_C%;Jw45jzA71 zR81*9>o@4gEgeYUNFYKwc<(T&Baj0LRa1)3`VBgAO9v7-5{Qrv-aAa{2;@LQ)s*71 zeuIwO(t!ky1R|t^_YRXf0y&USHKq8h-=HJ6bRdBvfe7i~y~CuAKn^5SO({O>&!8i> zbRdBvfe7i~y~Ci6Kn^5SO({O>_tBACI*`DTK!kMg-l0=R;0_H5Ra1)3`aN{ymJTFv zBoHATymv6_2;@LQ)s*71eh(eFr2`2Z2}DQ-?;VUf0y&USHKq8hUl&JiF&9MwM*(}YXE%yTn90^272k#w>Is!S6P&K9atY4=iw{#$ZBY_C%;Jw33 z9f2H3sG3rI*00l%TRM=ykwAoW@ZRC2jzA71R81*9>(}YXEgeYUNFYKwc<=C1M<53h zsuro*cXT>(O9v9XtNb$(h>#B6JG|5p$bp2aDaCsSqa(L;AmJFXeMm?L?;T$12&6zl z)s*7BgVB*&I*`DTK!kMg-r=Q=Kn^5SO)1_x7#+E#0|^`nL`Vl+yP}Rj4kT1fDc(C6 z9l50g2^ImdOLe-Swy@Sz_TRM=ykwAoW(6uY-2;@LQ z)s*7BgVB*&I*`DTK!kMAwJYif zky|>Dz>z?NbkMac>ImdOLe-Swy@Sz_TRM=ykwAoW(6uY-2;@LQ)s*7BgVB*&I*`DT zK!kMAwJYifuKE>qj;^08CMe*iPtgJYYQ!6Hx7^RH0ga^ERTP4N(I^$Ed>coVNGj#Mf5l{-a0<3 ztcmNTI?uI_*vnD(g+tNOfdrSwin`<8I16gk@MoyFFTO%)Ec zTsn}z6xL3nQnt?4v&1|Wu9xZ#snc2bzc&eoqNM`~OkwRL_Gf+DD%qr*aHteHW`8}2 zji~vhaH!?dfdrLpaoO z=|BQgSUZWcPbZksT7qz>6gl>NQ=fH7%_AIYxpW|bDXg7D@xKb1!S7BG4wWKD%^$*; zYkxlBP|KwQ2~1(_BtrX^HA?=FEF3CDju)R7WtU?@ghMTt4kR#zwS&+~jGv*$50?&= zB1hDs9Bg5X+z+)}I2;6~uyztx-mJw!+~dW5s1!Nsc7CMS`zp8C54Bu6kiZnyP9n)Q zhZSuwMmSW893igLdZ|x>g+ncu4kR#zwUcNNYq0|(hY5#Dk)u*2pI+s07U59Kr2`2} zVeKT!cDv7V=ISdPDn*Wk!&d3P?|LlW=W4lhAb}~Yoy5-Q5bu~0orFWB$T6?$bbZlR zzX*p~E*(f<3Tr3P_j(2I(PL4lJe? zJ7v&u*QUjJqo&yoL0}4NCt*KU4g#JJ;ZU^Wu@Z#+n1~eCPQrc$9RxY-XU#!7o^wH9 z3Tx%Fw@SWt9RxY-SD$bw`gH?53Ts1!NuqndE2<9* zyGIF!N|D3vGQy#jO9v8|!rDpLol`heiX3*g6b`jqI*`B=)=t8n0SJdmk;Cr#!l9N+ z2NIaV+DX_m8R1YVa@eyM;ZVz^0|`uF?Ii3OnQ*8SIqX@OaH!?dfdr9eYE&g8Fr}_1If<7o&uuLDX|i=Kw3B$;S*|p3{fbiU*DYZ&yFc*k@A@(S9kevo z%lCaHet*%6NBoB`CR;7O&LRkvdUk865q5P6EA0-=M0{M|T9cbBr9#7qVKP zyXZ>(pohM#BjT-c)At@cCrp{n&Y| zXZP7U()`Z#HCOl>`F}TC^E-gimMm^EfUTJFQfyVox-M+X^&mDht&tHkt{>}mSmTf5 zwYffD-zm4v;CB54p;DhkM;PVH$FRRPXC~sa&T#$K_FMDRk@pyY zdortpH)6gdFxBg3KmF~b%*55=A4ZHDRolCIT%>R)f*yrOZ5ryMq7Dm(qBYHzdf0cM zer<1+U6R1mo%Rtr|K52fqQ=k@kv$){y)TZ{5DrBImndgM%&M+`^!_)3P_(9<{QD1g zl?LtfMw^o@+Qa3`im|JSg&1wsTRZcxinj|gTE28?F4lfuLH>M<4++W8isskvpM0Ho zyFdxH<^w0KX^%z+d0NG_G^TBJ5^p`KV4QSSX1BjAD13_6w222hWIXt+iFZN6FtHzW zo^k2&E*A6uqd;0&J*LWj2d!xvO3ukBP$0@X#8=Tl zn460lb88mYU$)QCk=C?NPCxVytogS0LC$gxV&0nk#?Vg+>yIz*(~;)CMYrgbZ_Vu% z-Y08IIfyOgf{huT0{X)udvv7b5w0))J^HbuN;rtruO7?4G2o8^()=C}DRcbEH^*Ba zPbwwegX&m9kI&jsi&?h*e|YdH!QX>%HQX62$tpXnsfi;<=rtA?8(%JB+1uyhul9%W zgZ+&@7;8POFhw}ju>?~{^UqIrt#Cc8JI1Q_?i@37O3}`v&&!Af{sLS2TL-G#5Ds-L zq4oA_GnXyNyHLmD3jbAh_X2nG4`Z!8TeFGBN~P|PO)#D&&SGbpuFpiw4q5L%JFAN| zsbnq(L5`7OGugU_TXdu~ZS;us?yziat+nln2|}fQ?f#x|@98vlGTz8Uly7VJFBNNH zt=wGNL6GBcx2f#MzrNOy*0g%NO!xBM9_za<@?EP^!M%DKV=t$$Uq3yOiI~&(oPXey z29{@1J>gIUIU4>xffc)TPDh%54t#urd)>fl)`<#C5GqycSVv=9=LGg*<1d+rA$iiua(gtS~yfUz!cK_Z>r~wcGq5&!x}s>#>$*hw6lNAnW<+Konx4%4-OL!)jw#x zwPRbd3Tb&5b_Raumdlp=hPmE6TYsd5BS_>}RKqxZrYS3(J0CwLw#=?)eA;EUX|^9D z9JS`V*urn}GfW|^X}_D5J+X%p%uVkmSea9b9_^`Yl-$vP-Cb6IJ2vEUWpruD@0Axm zUO2W6s>YHA6=awqhobr2-ddFMgbXTTmTWM=%A8U(9)tN^3UXJ==$n0xQMg~SaHu0P zrpTdaen;!wFZ}yI%gc_=m>{?6{&PL~U;#(ZAVT#LO^X|P%zgXkP_`@21krI+XA$cK z`ox4M`X?i4&rcLQTC5i7qf83xxx+oXQu>tV~=(f4mFdZ9{SId$CYRr~ zFOkod){Ki34n>g9o;e9Z(VDincCE-aTGjUESS<-mo#@wJ|6<#fOvJfLHPgHCS>Ih> zE8$QCIqW?bgrfOfhpzg3OL&iJQT2wHvDh6)?77{q1TkReTozp?)zGxb&+_hF-gbZ$ zwc(l|R4RDsTI0+8sjOJt_)Ns38F?Fi$>;5FuHNk+XshhbX&}w-vN`CqZ`aB9ttVaf z2|}d?{J6%b6}gbjc<#YVY@7OHa}{t78O$-iJ@vNbNWlb$(c&r!tL-78{XtnMyz zf1)+9iO)g!5>^?Ny7052ZEFOfXnqIf<&z_S3M%2v|G1TxUUBM~%KQwT-ZM+DIr9(x zd=$MkDg7`0{#bOht9Z`s_kl^YN+HefJ6QPh$iZ(0dFK}HCLEYTdTGdd{Zx;vCjTwE zR$J0H@b`JCd2zyFzn_IerO2UZem@!4naBYhFS3b0#R&(dkk0vNzg{G7PVU$gbUOW= z4WF|WCx#1$eOwX_l_H0tHLc1x%{99C7B)0=gm7RA>D>h{=?A^}xI?S^GJWw6AF!)a z5`<%`JUR=9N|8g+n)dC(*B85=c(Pwj7W;uIr1hUlup=W1aYxZA9$%-RImW6u>99MbaHteH6wSX8 zU97!p(z|KK`8LvlDWpp_tR zbEE5<#~;f3Kw=8%s^i`4#Qgl6xa02U%ie9ac{_THaM&{>;ZP}ZD4O3{_4ZiTm38yX zS{FYMj}@knF4ege`@K;f?kE&L#@BwnVO~2jOgQWrnQ*8SITX!*e=uR1t8KO~&GRLO z2?wT--v4O~TRb#~JO2D)s_!Ph&Tz-qS2*msp*Ys66gd>FX)mwLb8T$-z^r_*k8ofL z>6UHc*t2GT^JB@G;Ca43KhJB$MnnsTJu4Otl_H0t`JM5?mb!9}3$Z3;=l6T%M;uHc zeIaxd%ea4sJN8GV`EEQdXLTRiOgQX$yKtx!ITX#mnb&Ex>#kYB3Vj$Q9GF7-#{G$G zNzSv}F*f>NzQI!)Sdo+K35R_)Asi}24n^}jt442jHFrl?+pIdmfhnZFIX#sf`t~dC zcpAOQw>7kd)%3H{!eO6B35QCNL(!U++H9w*(!Q3~>QyC$15-#(TsD(c8oZf1d=+;1 zQf7Ct?v%_W9I89hBdt>8P_(9bLo!_7XYXniIv6Y*s&8i|)S5IcB3D)aaDFD7yW$i_ z=cM)8XWJRrMfp{OQU%?WcPCkm_PPY2QrOj;#QS@D`}goOdUH}K2SEa6Q8_BsMOi(AF+|=mg%_?=7_tlXxjQ_6Ragg3o{(S_0n=h zYg(Nt%lGW?CVRJjvqGnlTj%<-XRWfj{VnIP8@ztXYg!(ky+12dy&ZQ<3tH`-ADis; ztxXk#8bN~Uq>BBSxwjD~c21n`pLjgcn{u&@*eWDciiouGeOYvtZT5c5;g0YBPSt7K z)mG6Xs%l#PQHB2OeEG(l$TQB9ao?5fedoanL8uWVsJ@r2KO5hN_M_yAYMv$E@jE*9 zZOd?7n4;xRO7~@>-lMHr(BOW=NWG0WC??cPkI8|A7#4A`hInoUkBDItp41SJ$gIol z*|@#$>iix!HHxJFT&j(CM2aNT2sso%^{|ueS=22ewy!K4S-=(UeRQP0a3G;lY;_UgUwfZ+TZNYAYN_s1!NOc8yt< zAE$ES)Q9cUvvhpRTXnxA)CjJZ>Z9()touzOTs7K9ewg}*&8*Q!IFL{&ax~l4knM?_ z&xx)V-%qdn*F&~6S`umm*Gu*0B@NlFc0~NH#YYY=_yzOT8!jA3s1!MR4ynO>hn8?6 zICgsam0sJK*+~*=1lLP-?Y1@8!V5(7syIC|;zcy8)HP8!kWeXdytk(u`=aN^oY+%) zak|#E6B`&W2{nT2rTXth<=D%CMCd;(imZ8emY!p9vTz`wQsgLbs3<#eZUrY&zh9fa ziywLT5l9ef1lLRT!}Ud3iXfJyt&N;?d#RD9k)!aHJZwk=ZPnK^cBHR=w8Dtu zM+Y3i^->+2o`=n@PQ=3sJ0f?U>TaHUHtsb-rD#p{>ttmQlj+ed9r9)RN6&kj1I|lA zjo^Bzt`?k?{TxSx=j#5*P2G2ydD7yA0|}KPN0uA+^e5lX%tVRseQTadQ`vKoLD|a_dm7TT1Pv)B^+u5397G- z-l{K-sK$xLLFL{413jz~-@O$50|}KPNB`sv`Y%uNapKzjBc2*R_4lqTeO(;eb47P! zIeleCXLx?9C!3S>!b6U;W)J==-oczWdON4lWqV2ZX%bqO(NNE!8WSMSC_P6AWZ2i2PRR_!dGG5tw@Z=DCfFdQMG*nu9b z)!1O2mfyeFlWo8DocE|s-*og;DAL;-k?`a-LTw4s{NA{ogFL@o80WpWr{`F5Qy**ki-&?xuRbC==3A$~T$^3Y0A9Tk*R`MEcIO^y zeO>(pt2OasV(rE5 zgUiNP8%E3&4mBSnhe{#M?~d>K+V6co(P|XaNjTJcDW&G6M5{INYp>rf-xGNx**kef pX@j0yoExec87oMneR77yu*)?O< zW6n8Yz<>co<=?a3bKlkL?>X1AujZQmex_z;rmMTF(=fOGR>$sd)7(G2U%GFl*|GoJ z1FHk<#NoX*&OO}v^oTwk{XDuL{b2eo;s4jqsm^bi-L_8B`Xdq8#w-ffG+DE8Pp>GP zU$gyxk2}?Kht@1S`Wn>#?yI$=2ep?0Y5Ju1xdR_T=c#C|^Pd!n7Ws9yAHh5}N3Pb)N z6qRS16P%w?Q}Wsw$!y5KK8#3Y1WlpWm5+I1#LlJKdOK$SK`1Ism=kQcrIJqcl5GU| zeau_4VYPN|>MW!w^t$q~sY8G1aebL+RBef)%3G~TJ>m=m{l-5}RxHfXin$NI&gDnT_l^qa3$= zHPV$Y9l;S)MW5U6@5*+)r*h?M}-KT{nID4EUY_<3-Squ*3RFoEk5h>#}U)|kx@V1=Z zhH_n5<^JJ^l(T#WcO^maz1~xG@uQEf^YBkVZBWAdFMB9>DQNdjn9kn$n8|ZAv;Ur` zOW$$}XbL6d-tRDOI!+{+Yyx_?d%L&&SQuU0Sr}4?yUE1Ma}zZ= z#dCER?@R-lLa!?yhkQ2HCUhUqh*?%%Dxabdo#!2oKL|xt(y24VI#<)KzT(G-(Yr%5 zK2n%2;6X*8DfGJXvGCMH+j`AdM$Av0t{P|=uKRlCvuH>tswMk7!2QoA+Gl<;QT#qm zQ~h>?ZvBlSm3*yZ!%VeRK6xTl@iydKShI9GI)vtE4_Q=z!jYAs=H_AO?&tX5WBI(x z*Rl|4J($@rB$O0N$j8e0--KyBKXeFuskfn|P?c;WX<)H<{#^h6*r0@xLJ9d;Ise;6 zPWh1-`OZj3uSHd@Kifmwyq99Y=|0RxMeB_c&KQX%`IU7vg%Sh4sX(0lQOsG|@Aq9r z-WokZ?6f5UWgEW7W~fryN9m81+JHr2jtLB$PAWfkJt*;2eoO1&;lWY26*wmL=`L2}r zQDt-w$Qn=<4xAjMxBb7T>p!KUG@0lW!2ip&f(T0nI;p-Wbhm{d@zO-FXRZS;_oVDf@IgmY(CEU z)=NvT+t_FXoc&N0B0h}3pRsY!&Au9RO&!JVYWL>W4pXnq!~8w{wKRni$11wRmhZ;U zu$xR+Padeg+#(E(?CWv_Rk@CdgH?_uV5Azuh>~V84vo~Ic(PklElr_B?Wx{yppps9 zzcrc>lU7Bmy>^A;7Q0IlC8(-Q`#5lUV*(T2xHG~zMCJI)EF4{Te3xhnC3a023z^9# zaJ4|btDx|@hr&LFqfyc!j-aY*1-`K9lL_pq1rE_p_iNKJjD@B?@iS(keFmRs&NSwE(K5 zRfEpHat%OTV(Mt-7>@o!--|Sb65GakLqY`;uvj&Y5p!C1%Db?BJ~kSz0!mPoWw`}# zu9Y#=!U>G{_OhSjsjZ=?`eY3>g%aJ%xWo8w#-MVPYchlWetzf>YggP@G=L+h>ZAW~ zD0{Ukc&w9cyvDW;*R$v1(X}&yrhL3R5KbR4f_3VNNNo$k`BTOYPxI&EkKjPg1|{~M ziUssBg7n&QjjT|7cBpcNu6VC}SAAJD@wQIP9utB$Cq=`a^M}PQ7@|LKW`0dvn-$E6 zS>XrNx0`jrXODjqN(v>m6msqKuHjyB`2MOEgeF>tfbV{wmq zHY0+HgVfzRSb@c@P(7iP&gbh#fpx_g)#g@F`t!|Z6{==Dkz1+b9Znu9)3hmkV;)E@ z0hAO<6ts(is^wm(+Psj7C94nGx9lGdzrN4m2&&5J7X`U-EyR=vnMiAcn@nrCiX*Zj zbiYe|3+vvG9Q5@Pxpp8Q%jZ|7d#XAZJ2GPbsl93wuMwivmfwVuBG*e4LaE^-najk8 zX&W4*nl-_EP?+8ZCFG|dt7IFV@pn~`$ucph&2;sQLp{-VRTEvO=+5wF#&z-hTUY&E z$?vA3_AiIsp#>uw`@bxHt*3#SNvYTv5uz5ccKvTalI`&@s z2jHghb^jm~6|LLJ|4k4qSS`aiGzXLtIpgeP{awlBxqK|2munf#`%hyw3<)Jgz7vIz zkCpSki88FdJ2UX5-iDGwRk97a7IkxDz<+E|LP?>7e5{=RZKGP&2uz<=Re!%q3RTHA z-O_Zxd_h%>U1`qJ)w{3Hew#|J%lV z_AVN*cS5g4Rr2{(9%-WW(Xjv6poEe_3Hew#|J%lT_Dy}R>!-J&q)?S?ql-9Mv<{Xd zUh7Yq)RLoPi_>ZSnQm9I{p?L5=2_=OR^09JW5JG-LJN|gk z3PWR1?-R>SJ|$kO-Ba%eckIX#jm|jf{fhi0zOUuNp4Hy%OY&0Km+o7>D@VxJRaEk^ zoC{?CCNsR^T?v>%fy~#++S6c20 zLYatKjy1D`vDUr>j-aaGeZ8R4yDA`s%B6FsyfBBv?Lk<#QaVRa)r&PfATX{9^t>Sx z>#YmzH&zM44)%*Vf~w^AG03+H9Q!O29?2u@s`}5yMNZ2(f~w?W#Rs!e&1cXd*|%3? zzMcMas*;Ztf6U&X|JuApHi39z!_GelMK#MU7Q&8JfC;PRXjFwYt@G~fAAx}eepkM( z;va+kV?bQ=UVPbYCL_AoR_c~Ed<@pvQ9+-h6i-c6EjGtMyj!uDyg@Dv_Un z_Hh5CFFzE5s>VHtfeQYm;#*+`BPO2Ml6S5AM6_6Xmm{d^MZH)kepwb;yUC?m>5U_~ za)}f0pE63ZK~?;-N?lq@GwXUN=C!xdM{(LZ7{ei#k@_#Z(IOM*`E3lEjIX1wy~baY z+fi%lW#<_$4aMV&nsWqI1?4x;*F`6Hm0NeN4dytsy)+L8)EdAMRCUawvA!lXTYX@!GwOE_*@Tg^+4Al&{bgC~dz>)7bO_LoI+YkTF{ zPtu(C9k5ZbtxnFJ%0H*73$429zjmJ$GBF`%xyG)`Oe{*+%-NtS<*SsVZNI(GJLV71 z#l&(1RmrxMm;=inpF3#0Hbh`0_YtC;(#pdWhUI$w_kH-x@x@2?&GjwF?~~+qRKH3! zHEVZ9U_fwxj-aZXWHWtx@J_hgR@-$Z$Z-*C-Tk$CUmmqVRn4=^^sPIS6uAX?ztl?e zULAqS8@fr9psHtW%=K-xpi^?Yb~*@B&bM&1ow<`EsH)kun);SkB^P%_REMc~M>j{{ z7S9nJK~=JC<*O6~cU32cX3yv0neqKVPLbc>n>G`0vDQi-nP?F)0Y4sTppP>ww3k~& zZQ^tCUM>$s&4A_{K~-x#>gb~eZI;PxwK4WOP1pTlm{?qqBdE&AtCl_na5+wHLC(C= zM=iG`rm}L1-W63T|3iM8`mZF?i220D%qPkzitkgt5~cR~KQB6{F&=ucel{jOT>1y0 zsQj!VTkie$gLwGyg*#UKmE zk49fmx+zY}wek~{pU>lYZhEh+K?^)z^^i8d!@J#;WwSa3vZ+X+dbb+%wOO zwLd~!=jd%H*OgWBKOeQ>H?3Sr5Dw(_a%^L^17d;$^)_x#9wi=$7xgw26{Q8iyvu^T zne2UR{WV>0L%FW3lHYms_usT~B|*rwoaR{f?G2b@F-dQu&FBT<=bxarp{OX$VoN<1 z=arZ1Z*~3jHk9kiD*4-u-h+Btxso7s`xfO`@~{kEUg@E?(E?VBmWO|jJ5W@V7KEP_ z|H^wZwJNUMKSFOqxvs2|^I+Pc9(o(fl?0)4<2c7%i)&-KN`v$^l$MYj9a2=37KBmZ zf90*K-x$L`y6SBx*OgUDt4OAmD+$89Hciz=tfiect*V}oYp-(8A&vFOwCuZnM~aLu zEpu4p8jj8SzLjYGQ&uVU1X_O(gegXo>^HIq{pGMjBCR1Qgj^!ilKOWYPBNRPbFSg8 z_w6a2th5KJ^heVH3qU!ReSXW0O|>7t3}U(VN@t(Ecb!9Y)4iwY2_=ORYi=aKpwK4T z!+`@CvAo?u`)iu{x_Y%7ID)FGrLlJ0lcw6zk%JkrwZ{lGn1<_Ic9%%hI#tQ%%dBpu zwfiL3MQ;@cX7wrnjM_P~vmX1X%gWTC46clo2}f0Q-OLhwD7sAJ*GY2&xME z5f2V~nrVNwlWWK=msC){dKjStmmeBxovP&X#~L)(o-ZEBh)GFFd53pL=q^p_ueYJ3 zP~yz~c<5ifx%NT>xou!FdYxUv(g>Ytjh%V)TAXTfJZz}nTx)M6w?FPaZ*?duCPEk7 zB2=V=KveR14~u5n*CldYG|zrr-kb9gy3*?wdg8w+gy?A*4|eC9X`PGZR?*L9uX1A= zMCeZ3+rbf3C9xjGE-jmBKR=aiJUlY^5DA)8)r(5KC&kWT0wB7+UMZOb-pm!(;s~yhUFK9Mf z*Z9|pKM3W2&?my;W7RgQBTr1!W%%C$?fO_){ncFidg~PZT}|I%rtRL}AD29hg^Jzl zXw6^BHRMTA_3|oZOwwilx&|~wz7vI@cPI#Fwv}<{ zyLsw5To*9eDi+#?8fzCm)Rlo5T=(VVdJ`vV-o?1DtwFo+Qy&Nawe|Jhj=qqf!)N(v=9w26U$^pDcgAi1w7&q;JJer&G`tk8iY zsA}SeXb5cZLON9}+bAqwCoj8eCtcC0ZX7{X@?C{*zb-iz$URtP;w1H2myWtU`|R|D zl0u1o>S$yA`)icC2F)7inJOG{nLAKf{Es(vhphM3q3QtYX@j7Zfs$tw)A((MWC z#Sv5`-_`b2k~DU@Jlb&5s|<=i|P9zV*Gp7)U>^oKUI%{w!(nl5X?aE_oV`L2r3ZICW(k;f-`tQexMbjL{d zy2eO7p`=j4tRxC%J=iP_@t28RA(b3%_zJqM^E^3%sw}TW!P&rNQgN^x(+^7Ml6Ttf zqxR9lu^d5F@?CwO6DMs+k;jXcd@rwl>H1o$^ZM;Ml@vXXI-g4*PQiRmpc{nLR}EHI-xfWBukI zirS;qhAo+!r#T`@>ZVM zsvUkeP){f+l*ky)+Bh@1NDY0Io(2!Mbgko>Ada9aI*wEjE{9t=OmZ5jyO?IAClnt= zy&d%ug3vTaD-L@$5QpC9Tf(%B>+oO!So^*cH#^9_#5K!VY^@%On{HO;TEauhEPxsn zpNeI^}{+ottpP%7d|Rt>z6ebZ{_IS`gkg_QGT9XkRT$W8n~vwbmp-{dJWjql@xaa`LD*F7J3;3cpnZR28x}3G&_?(#+`< zVL*&b_s0B=<0bbqUpZpXm1J1)9W~t-ha;s~Pqo?`uYa8&Rc-SXs48Jy5`>)Zt+~Wv zbUd*q&KrjmuGP5ueB+3T=aV7yV(m`Da>J3*g3vw02eTU<)VMzR3{=&8WfD}jexgo4 z%SOEsdn^uD(;K^4G*Jz=DB*~w7m}et$0Lqi{|-k=3&MA;7w*3&s^0ec0aP`1brL-5 zT3r>A8(~0rkM}{_bH<|ah0h#eeIpsdb_A>Thq8D8p;_Ihl{aQ~SHlwXZP42?4Qdu# z6+eXrVBaq((6Z%SacIRrtobw*KHNGdjw}ddZ_x9IH%^{=2ojHP2C6!EDg|6tToQLY znrT4HJnM|>zkY`;#@9Kb{`6$nz3Q=8etsZQS`cdeF=adL0EANT} z@6IwHn$Ld+sZF}z{kN5o5~~~&;KYVEqItuaNNGVxdhiP-n03Zvr*cSDiK`Q!-{S|O zW4+l1#8yEKRVD!97E_KWycGuneIAQBJ!T`NS@|*QxL6$Fr@b_MF7C~afu&*QQuyjf ztX3ulz6PAt*nElPMzOOucp*-#X62!En;F8X==gTtU)6oGPJCumRlDkHC`Vji^@Mh6 zcTEu+UqWd%n(9-aX!)SLHr|(wL?S9W--IVdZQm`r4)cRjP<1VcZB)I;!+cVKmG*-$>P=i##TE#F1RF*Pe%}ig&}gxiZuSPfU6> zTHK%8QSuqj&#s~WgVKUv-zZTGtMLnpmw2Mlf*9DJ87o$1CFF8V3|ypQG&T?^Pv?(5HJd7ji7RA8)x7)?!$oX8{PY_gxhl>k$ z*1&Rgh9XtbI3=|w2p=})h)ZrZ!gr3nIl|f|7FK>fB<_0|!o@Gyc+ra9Xc9OE7Wh4e zl4&Whx6v%|@uPY8CL;wN$1M=ED$K(q2NsL>nJLb!E!Sigjq=6|RYrm3fk!}9yJsiE z`DaPu1g#-)a)=Mc4xR!JEpBl{i$f_;Tt7pES|LbjHiE8^H?BDn3<(==16AejPKF?_ zRpOIZLki5llOwkA3pOB%{48=NWugXS(&oRn^sy)vzK` z70pG|o*;DH<$|-jZHF79j5%WOy+r8VBV8PwFyA15^myTdSCh8E4tryyD(VfWJr-~G zaKQ;Pmw-=CGmh}xmU!ZiEv`SPBW3sccnCos--z&nT;DH|Bp?P zs%UGAC%zqaMmzO4Y5K3m96?)+lxDpEkxg*h1T$<`u>x0j?*3^Z)Tw$&v^^PQP;XyZ z+5}^-*1)w@DoIBC1n1gT!I95RIKpV>Lbx{dsA!Wp2Pw_w_N{7y*LPLM z-j7U>s;JlIiEif`W3lEJ-2&*k$ciIIv|I?Y`fd`N<L&Vw_*yQDErtbGNhcW8-JMZGq)$712nt#EwnJlKBNh9lNw zC%|OuNO9$|FwTRsIz#WqI3qv}+T}J#Rn%)!d#o0|!wT;wtc8rtwj9wRHUav6A0d{U z59d6%AlUx0!dLItz`0Ocq$=vQsXal64zWUH?HS+6Dvro>Pk?8(ZN*>bA~+8&2%EH4 zxG*RhZaS%us;Jkd_SpP$H!HkbwjaDH*MlRBRSA&STM%dWiR3)EAZQj^q3P(pF#mCP zq$=vQsXf-laj-)8W&-P`yKuzSW(iRGb&INVS|sPe1;J*l6&A#sz_($nlqM?bwW&Qe zPQRTM-fXZ*?6t|2Bh2b0z=4pus_r?FoCjw!S)Ht~WYn!0?S)iDy*9PS-bYs}^q<^RN}9|Q zwha?t>mWCc-|k4x=d%$)?5+yUn@YAbdm&X(uTAXT9hIICI3iQwzbSm9aGPbOh(Y z+4~s$1DZ^1f&D+5aWRXDgA>55*%fi8Q84Gh1);{ipHOhGIi`LyL#m=)n~$)x$u5C` zMGbMRkh)Z?r_JqF$TY6NJwjzeDfq6>#vjP8_j0E*{1m z*&@!coX>f1=HZT%K$oc%&}UI6q$=vQsXaFK!{$3|Tlx`tr8siL)PeDk(0r+QWnn1i z!3E)6XZFu;eE_prj!0G1Yg2n{9^|HP;4<<$1T}Tx2#Z?r(9|qiY+e$^d2lu}Z0~o7 z-F^)$emWynQLjzy2|{_-Z{R2$gmHEHb3~V?aiHrqMjU6$yeKId*touy-yx&ZL8$kk zA5sB7YcZG!OJRj>C`Xjh#6iPL?ZpEPSv`@I4D4BDeS>R@mVoK1p-5HKYx9JS zt{5tAo&*KeM{&f3zv5uOU0KmCDw6Zyg0N!fH)v6L5`29>5~+%MZEBCLQn0ERs@!b~ zYs-0X#HF}6coVi=RsB>X=fT+sh_c^c{oJPD@!B1!ih6Bok9}83#c;ZjM(nc4iz7PB zi-QyS^;Np}k(>u-qjB?#VOUn4xGu&Esfv1SYLCUKGm60{R#Jtr*ghr7%!z}qr;F63 z-y=B>E(k{Jiy^qFq_Sh90;r05ZE8;tcJ3^O{1J{){#>5u7ZwLy7mU>8J&)vkKI_3s zE(Y^*j?(EUZ=@>fwW&Q;zq(lr-DA+;C==?Wy_ znI}>e_1e@Pn_t`D8-z4>(0(~Oh9msg*qHe1CX!X#NX~-`f?GijoSfGc?Z-7h8fkvX z?rL!KHL;#OTbYE!tOcRYUx#4Nmo8X2v;k5T_1ZjfBq#@tc597$Pqg5OXxBJ+o18D6 zXHhjuv%WjiLu~v-D@?r70;!66ZJzjLoCAF=EihteXO5^}o;}^nTygU05YB_M{-}ky z@MLErOd8P{sfv1SYEKXfb{&LUJ!;^E5|JY+zwy%$my_1e^) zAT%k+hL*=)!ok`@IHKN2Hvc#^Mhtce=R7#`C7swCto0Jwl@3O#qF$TY6NF3KvSD`g zNf>{2G)LTTz5sUTdWc)1A~+Au)-^bO5ZZk_0jKwlMyjG-o7xkEqaoRl`F#Ue)EdhX zj-|2i`f>;Hi*qFB!3E)y&p~*axB-@a_d%+nUYptzgnA>hq2AR{Xk9RYBZ42YxhuKl zMBVmC&Vw_bXnYX-Z9?JVr3pw?)N50Ftlzn3Hq@@y2_A|59C7kYES#IUQx*CllJnrK ztUZSnb z6N7~5NLADaQ+urGJS-brgbOOqp))w5eO@fIUiC#?qZ#YRAti$#1o~w|(YP&jwdxNxRj3-)Vd%!L2E!Br7JVC!P zO0!mKq6gU8+*a8<58=Km+F!>LjVpV?i-tGF-jQ=Tg60)Uvl;1QJfQXRn_`cIxm^A* zDv5@M=XR-<8$}^cbeif3TU)B2*}Nc*pn0CsYz&LN2i#euf_n>sxP0zaJqG3;DKEA= z8i_m+de0NAV;8{u>j4}=eHW!!KDYIN2{#r%njSrN2W`xiF8pIK_Y^OAv)6mTmnsl#<|6~s0%5&Ni%M(5S@qvUE^>A75o*Y5z zD3oSnATvFoeNsKV)3qm8FQNUlJaIH?EHvBN9BUNYa|EqxQJVGq6njE5^A_0ojy+eu zni>!b&Q(r}&~7gB#JO(1uxMCktbC{)N6#IJ98YI>fQ$nH=A<=9YIBD)|#je z7?n_6tKQrKX^ezMwrRA5l?G4VLPwXL+FeebNJ{`(Z>MF6AQ-24!u+5i+LUp#xv?L# z^x=K`7R-c;BiyxHtY&ZowMS_|C~KJkxu<&J)!ioCKd0ka=u=>|C3OW+eJWWj>JhLQ4(BcD93!5%pK(Gww`L(+7!kw~)DKcx5WLsgiyumM zKqEHJimK>bDW0&YoGsp5ybsW521igoNNGX%(rT<|z5f~<>pBUkijFDaiH6o|#qY5< zL1#6QBd8ywG@G$Lt(7=-Xj4qT#m}On-hi%n!)mXcPKrWo8+4eaLYkkciqe8`?`tD5 zaC2uI)5w;aokwZ9MvfqKWFrvzM%&?WoegJ$=53y6Z`N7t8{>pkOq(NB(Q%eM5t8YJ zg-)V)^L7c)J~}$)j_)6wlIVlW!(v1ss|Z#+Plg8vPN+Irgme9llxB76C@*w#-Yh=6 z@D1p-D9!hb9=z;>o68&%2Nu7Bp+XAmyjoR!9vQ~~@f`dIq`>l7W5n*;=X1T&loo`|>%A~_sXbh){~GAEC{6q81!34=A9RcB4(;1N z;cU<`Ogypip9UzkY_5HNnU9`RPfdM38~wS-8^u9KAgl9gZk(l$R~qbGeOLTZG@ToB z$yV7+_rVUC8kn(vHBi;TWvO8C;fa{`#gGVm#cD~1wNPPyGDq}VlLp}%o`~Z-rXi&T z;X&uI=)Nu=F8U?`RaJVM3Oya)i09u=H6V`m8;37Sjzg>VQ5-Soej21cFAxQ_KT?{- z$i|JuEf$v`t=c@Gs!*piQ2Q2%J8n%eAkuxt;erEa;oC@mj)=2JXDgb$6FsX=K}xgL zrXPA^AFm?F>~KQ5pP2zscS^*mY(>Ivw=&>JgJ0tN@gwo{{!BQ~^pluVM_z4V`7tl7 z^6?8yPP-scRinQ$;d=Kk;@EG)4T$=yCgQBjn}7v_I3lTUCTx0EA_kNjjg%II$x$D` zcZMT=SX9E+{rle-Q95?Cj^#pFdHu6kr&wMu|GM^-8stjPBMpg;X{AuUh9~BlEs`i< zrb&X10mg8&nFmsujU0#+u;v~Ql**?|R8`$C1)eW7g1=RUM7z_!pm{Yf)QtY2ro_rA zNg!M`hW&+JNNHBSS0l%?O_584}S|e?sa}cQ!B87${+R&kN+! z*?72TB{1K25N5e<1gcs!F$pXK%0PO6A@OtFH@Nz#4_=Jdam3o03t>e5FER1#G^8|} z^YiUHe4gD07d+4bRjJLApihqyvE4R9;_AU-*j&>YqwVi-1ocsrX0x`8zr*WAPB=3B z4p0^KI6Uz~drBKrzf+0a zioN+;5};;_s^Bwe1oFi6N(tf~leu{D)GUsmD|b+uc{tr6@t+ry@%Ys<-2X`K90!$y zD?s%%{z(55iyBm1EP4$0$M+3R0#(s9KzQQg)n($oa{;(y<#vvUiHU=$Ih7%@=VYWb ziw^END!Qf5z=xN1169%Wws>Oj0!J}(b1()sisy*%%W>d1xGLOzFaaseRxqdL7%JM=nv0Eg&gKZZ3Mr)pA)-N^n0zS&JBs}{;tQLrZ7Ws-^8i1C zHB1L;7K!za&%-?fy8~6xby=xBHgEgtU!pgJ;lU}TA|=v;;^FQJ6PUhXEK-{FZTEX8 z_SrWd9Zs79RnhfjdE)!K7}0TJI5zfIi7_uY$s9`UA>nloc6|vhXNz8+V^pJl%Q)0Q<}}3+5>?Svp?TtV-U9KWCKO+;s;Q*}UEP|}f^g3MxTtPA z55Gk@aVuI=ntBOAnEOB@n)jWDBgGz^4eCF5BF$txrXP3+?_X^bC);I!$I4&g9TQ(% zzbFIh6_<*$yLn@S<>@fgvMi{x9a^kFnonvI&AJ_yI1D}izyHUe#v(Y6z_S29j4he(t#k{gudOMvXXxoX>tpDTUAZ&P{EN(rM4pcRyT`C;w z_DyuI?T(O;e4wh$(Wy|& zy;R)w#E{Tg4#Cv?D!6j88%Okcod)lk{}LmjCLpB+VL-uP3~pkCeazf|s%~6Qg@=vH z!h%hPM3wDBFk_Z6+BR*=5i`VeD7-Dev7UZNY38p2hTx1##+bRM4N%pHR;)$;xg4ar z8xp5&hvJ|l6HM+ba0LCrDb3ooMMJR87ZW_`R4P)HZ)_TPJ68aE^;qPIs>g?7@iSBW zIdMHl&@Y_QY%ihkq4?L3>X`Lutw>dO?xcaSrUF!C^HzDHWiM9OaI21AOUiNt{lY2D zYD=X9EqP0(6+>fjp6-9flpQuo-UgK^jWX97SnX8Uzo+gO1g) zb4j#@s;-2kL%%lV;mhgK$P=4dyWv3}6TJQ|RH6ip2T+hMh3MmKP$q7{KiO zbjWF17FM($i9E3{#0}?7FhKYKf|r%}ax<`{lu;WCZfW z*260FYTgP5RIRS1#Dco%5ID39_)T|1O0&|rqyZK?+MxB@b3pSm&3CjN&HB$H8sPT> zHkh1$4ycN@uzA8at|5+y?27x}WN`$|ca&y*sg)XHVo6s#d>{*`ipCar;*CioZ1dUy z50qQU5j5XXn)N}ZHpIyj9C6j56+l%qM#2+w7B|9uGZA&`!a0KGJ4y?}s~U~4*;~X` zFT;SUXsm}PM%J>xL8i_a^|Tj9(0oT}wyI-hBdiwhj3=w~0;-}hE1u}R#sW?6^u$MK z%n>x-QJSq=TiF5&JlSkkm#RQjH1@_5R~lPlqYb?P+R zQ4%F+zN0i78#T`o@nkQ&G{Q@wDjL(}iBZ$7aF=sWZ2$2sN6?%~X*P=Wp(VE7))P&i zyqBno#-@3qFy9IrUF(6T3%hA4K_ljrW+P1R90aEeL-36MGcKw|qj(>E<6-!uVll@o zfVHEHnrDMqzo9tz=Tk0n_wGPEJjxaz{^2y_iIj{Sc;9d|4%Xyz1dT>gS`bd%$c8z~ zMq`0PJ{N(k%jRYnuP6`8R{0}ORCURPRes*MvhsG0pixyyvtF`=2cg0pZ!8Sj#zj&u zj!J-QH!HzT*U4-(`2X2syK{ZW1#i|S93QlhBWQG((rl$dyBwHl%+_SPlE6iT!?q_t z%RnPo@pJ<6MA;RG;8pG<95Zw%N6;uYr3GQ*(;VpBbTZZ`8q7tumlr2Mj+Zg?nalP? zBlZMgmAe|Q-uB0pHHTHW05Bc%H=`E zakeh|zDTYYfc7C!n(f)w>=4{)IUPGSozL|&l;5-vM%$Y})&no(iQF}Lu(0iPyc`4? zdR^KVLTR=-<+(#JHf}mfk)t$J)soEswYXdj{HuE)Puyv#fezKD;StZhT(1o6)1fq5 zzhtr+GQFl@**#fY&(8-;gop9QVA*pt@%kJ@6T#2J2>M2kK%NjjXrRsZ2?!yRIfC}FQJSsYw#*w|E%(5&QLljJXPWP5 z#G8#I4|0c@6+Lm+{Q{sW8s+ARi%~vcW9^6Dqt0>!&3BY$>(&nUfaWQFxNg%Kpeh<2 z=7~Jtu`qhY6dcxiCr8kHM`<>m!PXNx{+NPaChh>LqS0ZVSnA*l4c^Vb$VQ1ALGvA@ z1>tyYFNo|LfFoEAqAD64=83>6dbr%n>x-QCblEio9S>z-(MsaS%`yjok9Y z;Cg=0+j$Ol_Nv4YG~ZF0{f~HWa9T14KmSz$sES5zc_QwyADp%f!SkEOij<)Fj?!%Q zz)T;=nh=5!^T&u(#YI&~1e*1$EguiTQ`n3Rqg)LoXuhMgASAerg?F1naL?G28mgjk zSf1GIH~}mg&&7|q=Ojwdd`D@v&RsKKm^EZBrn+2`sEWo#c_JWx0xWR}!nEdHwUnSa zmC|f?mFK=tVM-9jJh0VL6^*3wM0%NtplcV1uZ+Sug7)@MS`d0&8i@5{i=b|o{oJZt zG#W|c4{T&jx(i;?l*P@)C%JI|bQLh3ShBGvj#z1dEr!+L+Bh`&LEAfmFr$ez&bbFT zrJVy;_n|6U4`O2t_8b7*)fa=^O1V)Mw0DtuKDJj%6?eGbYB)AKR+j5gq$=LS)zN0c zqEiFVF`xoR&`}+fW_{ZemO=PBf6RUp&Akumsp-36V}##~#TiqtLwJ36pd(#qjFiS? z*?!x3epn{z0(5}B9I-Dv9oh}~BGw3)h?Hh^Q5F^GHs(I;8n5Casg$7cQr13iGakP@ zy$UURS%dMtbQm?RM07arhg3yr_C8wp;*p<^!FFN;E|N-V8ZTwDWh;$G*H3rAiuEzm zUI411G}~8pmM2K55h;{L%Y52Nc~+Y<%&$OxFy>y?73YY*iJNcpo>hrV+2*%f*TlVmr3!t-+}J(pf?funh}MJs9ZD* zTAW=f6EY{mE2 z%d!g?@yUS5pX~tKn_ZBWO0|*Fg0Og0J=-^ocwj)B9;AZPXD>@UD=YH6BO~8!V90`e&toABO*9d5<2@ zbH!8XFeF)DLPp#&u;IbJ7_%QAr0Ad)NNF}^duFv9*+vBe8wdA0!Mtjv zQp?nKNNGW6SEshE{FTUGBK=C}H%4jp22aQ9i5CV0{SqlH2qR6h?G`f|L2=Fn_sw&McG$eBS+;xn8ngC081#?7mO(u-0UQ6oS zpgZe7{~yg(t-BSf8Ed~Du6~$_RJDA2CM^5WRx(*>NbKKnL^JKoMmRcmCQ{Yq;3W{b z&{5j>!H}qM{Ia9t!CYu^WI9LeTAT^iVJ_0rHa(EiY?jc@nVQvmEl8laZ=C{FXq}zRA*5bTY8f>+54jkBToLyptbCEcMNVlLu!> zZ`jCCO0%7TCZ%bd+)F`o!xO10+cgtZofb&*{G1Jl-mNxh4we;g)<#dHs;T{#z=Qlm zY2j5vBE8Ig$6b4j@MznS95J|6CTMNaCFfpjEgM2J5BGeNCU{3Je7tTDQdN#oCe%K^ zQc^qiG$1Z6Ox5h@R}1Y51|e0AZ@&ag+}BFKb{P@{-L5z`dTEIhUiRXMZm%<7Y`M)+ zj~=c_X|}GK|2K`}=C-);t_rEjS)Bp8ye#QvVJ`zBK6aL>XmCs1c&j^7)hy#B(607A zY2jan#2(XOnku;tIJ>?LM}#lT0RP@cq&!U@q%`xQ<(v<-n_!Qx;yWN!b$YrOqJ|ui zjI@SC1>-LEb_052p}!?Z>~&+~uRdLnCOz(lloo`(!?)+XzttOSAF@EIYLmSfUKL!F z?i%+uAX?eBcD%fDD6U>ugCqRAWx(7P*QJLx1CY|JUv2#cP1*eyoyxC3sam=hUKvi!4q(kMjx6-7uLk)-?Syfca3MS)4;Sx|)PLsv3 zweB0qYqTK|u)Mxz=bagtb#FgMT-2mP{huGCVZGdt(roA6g3FoN4&6R4`=tVNJNuSD9OH_Cwcyz;igGyi!wYlRy})K5(Z zpN%C_^7T=m+92%pFj?!cF%8=07E4zBCt%oUHjZp_k(8b|2^}wFKw<88sfCTa z!_l@=pH$x)vb{6M%+pfUMDGj`-hPq}R5B!1%v-04$3Q$)x`QJ^>ZL)4GVi2`HdBz& zEQ)g>U*lUo5X&~*rKPHVh3Rm_=HJj^z%+V=qm0R26lAjW881NmslB4TvQVOr+;G*_sA6wRBWv#74cWvpp@n zkDO^hm>*u^xZbuuzVNQk5k~`4poYyUDS5|Cq%>QrSUj3%Be>w4UDi6P+SoA#R^8G` zPA_K}5Z%igOIM4!=^}ob+-`2dwLBucN9XVX0su zY?Bt=GbBcyY@^Dl*b2L2caGQ^oecfIZIpWTn}d`V1m7uVHSHH$V9@>EI;vVbFc}=q zuaIgEm}@|c|EHm3nlTBJ_M|-pSya*gk16M|^FR480xG zq=pcJlxAy~de?TWwV@W8=M2(ORo4$G;CLWSdeqsFXw$B8-Vrw9H}2?2j=20j2|W77 zO4>&AkkW#X5jrq$)21qzeRHIas>GZWsGAleU2bDYl&!bZu|no2IPlzuBl>So0-x*N z(vOJwNNGW+T-aAEWpg=$R(k2Es!vP`-2FODQdcu1(lz#yYrQMr`+gEf+>T3vnbUep z>8(SN(#%HVy5jwlk6?MmcpX)}9i9UIMsCunoAV8b4V|k>1()*Rz^`c>p_-HgPog?V zO^=2mrCB|3))mzl%mPkag z!;sQ~U{)?l<=1c*Y^V{aqpGvjS+4D5A zLrM#RMQMTK!@22TxhzOWRdgpJp4fZjpS;?u#>1I_2QVpxl zb2M9tEjiBdqF;%4%`}`N(qCsnRrfxcat{G1&F1P~*W?9uSSHr#AHfk#-)F+c6{qvM z9|fc|+vBj)a;abEGpZwO&ozX;Kz_d>)UA0B9q;9DcS=j?=jf~dR*vhK44m)g$j==O5VIn0KPE7|V zqf#lO$ep9voS%wU)fcCPV}Fk)95IgdCfYaKuRA!=Q7gxEY5$PYV@9L6Y?hEm7hRyAjc)yHQBNo;8W-b< zI7XBYwb4zerQ!(Lo)X`uw7{mKbkXgZYNIo`^ZTw86^+*M#1i&DIyJD-bzIy{Z$lv> z3+-Tt?*r*q&6Y@Mwl4r9S~J3w5j1W{Rg`9Bl*3$|>`zLj%!4}FO(ApJ2I=Xqn%F|y z3~H*kNaM@ZLHWG1+c8l-&um1_)xCQ?{Lq}T!9Z23+?zws7Ki^IW9J>$?->^LdVJy;GY=J{!v3>FL_b_C5kJB&a2LE!j>BUe_g<=H6{5 zL)qfNRqS2kd;qIj7H}K!OupMmn=r5nXO}mu%-XxUyFm1+-5Q?c?4~t-)+d{u59+uECc9bGx;#C_9Xp*APwfCA4O!ND; zo2%I4TlKS(>Ti*;Ds!y`Jl=OmKC#?Pi#RY_#lpu{w-0MGOCT0d3;1AloX+PraA2B$ zc|BLL(Gyo^S&qtc!m0^1Ex~BbS*ka>l@_t*sfum$^U6v$z3+ronl@OrmnPac^IKI~ z+gluJ?!6cfc#@JnnAJ26^U$38tqD@#qGWWrun^=%3iRpG=|;u zUaB}dOaSFa0sL_hIfN6fBoSDD<^d}*#XXF$Gs~-9H2lEySX}KHPM6*u6 zGs7x{vpYF10+C~A4DVPhZ8GcyV4Cm5wKdN%-V)9xJ$6*Es?pZI;LvO?UEZ`viUCU>)*yw7ME?-#<$~~Gz>HzY$T&2M8CASUu}as%1%8`GQfqQki#UF+Ue4KR zDt4&XJb}2~-Vi!f389`_F9W9eEIe>W_V&>#*7xErGyMA| zT2CNw&A>E2>;8?3Od8+A{=#v!Q+jwB=qDbQUoPoPekP>Bs9`xyE4mU==WrSrnrFy& z5*_&rU^ORp*Xm~9VvpJhr(nV`B@J%3aB})`3plazt%~GiEw?MNKP(Vfg=ggabjlDF z>0p~?{~?~AZ}2Gv=D)9@yuI#C@Z7ifa0*1Ws;7}fmMecQ=mz*p|aF|G`Ha~L`8~wdmcXdHCe_fm}vha8Qe})QcS-1a^k`u70ErL z=P))ZRmLfp5NF8V{Z!=g3)8HDdzT0VR@G7`!@zA76vJ(rHRPk+ROC~emG%`6tdMaE zCN_sBgNu`nGG%}tC%!nVNaZng95VD)$~XlR;u>;(88=p0A_gaC#Doe*?c%t)@ zj(;;oD;3G|`eI)!Z4?Ns`dFLT+q|n0HVvXz#*_jGHQ=@8o7b^=1`;z^czJ z)8Ihujk3B*4^C{qt0LcDKFTae(G>`+>eDj~u4O06SuMM9;`<{N>A0e`Lwe|2C;U`c zmF$%Un}Va{*#^#>Fnp;ZOS+YFY%u?lKwy=NUmE1~^_A}!cIAX^v5G7xe(qTALnnd2 zs&~O@FuA>*eBn-KPW0zbm2qpi-O}M71OlsYKgQ!yzo6QkUOde6g zmCk}kg6KI=>$Qq_wUD#-9XlZqSS9Z2=kh(Ah|}Y;9tYnO2&@u!+`V}|3QsTWq}Td` zKwy=)8?Jj_MaHH-I$ZO8IT_~ztHhn^f!9=I+w?=(HO|)+2&`H+Wij;g*HNmsbK`Hf z@h`p?#s7_S`R4dBKMmggI7+Mk?nLV8E`iol*3Dqlio{h~ zZP&2De1X6!JQDG!ln;F0Zk}&e1^3MYfmL_~iQn_{UPY$P)X#Q(xl16hN?apb%15>C z1EaI;n;aGhtit6aNmZV!$d9Xe>YM3_j`+Rf@(_3R%^#}B(=HX&lQUmCVFIhfJ^FrE z`TbDO+vVK0tuJE&tHd35*Aps|H*|H@r8AZSfmP!E`SmQ`&dba8jc3aOfmPz(_LeOw zQWDTHXP2voKwy=+V=B~7sHsfO9?Hvnt)e2Q>P}LBXksDb6ikRa)n0p4WJu*3Ij4sA z5(umk_nqTbsz`y$f$Wk^qXh!1@Oqgf>BXx^a_Ua|#H}+00;}+hLy~UtmBF@4Yh^iA zh!hB{!ZRH1oxtnvs7}sVm7TXb;aL%`iMSr~NIl-~I%Rs<9g)vF;aM2&2YtD3)X8~< z@<{GkrPe;2xFlTGkCF+djl7TPhc;*R)E7Uqx?e_G(Wuq*^Kr zrXT4o)1hSM^As=${z%Ku@#HoZB!&><=F^o8KfkGQ3MMjcq(IZeFErnO2qz|Fx{^;7 z>agFBaw#UTYLizA_)hskjr=t>QhoZ7hxKc-#SwWFr(nXnXA0P)ey3Z!G&Zt-RwVJ# zAXa{fse%ct`VpTDcSnDt1BYmA6l7N-0dqXqH6C$@Q!rr@%1=X0E}=1fG&b_{0CblG zF&CR20)bU{Rh6%vcjhOIADY1&xAakP3MRzW+JU!2$k3gWmBV!loL*`?+KRr@zW&3> zm$xa9@$xgxJmF17FGzutI>oe0*hv0Vt1LrE`jb#)=HgRMI0X~&r&FM(%NIH)L_=hJ z2qtyAget07cNr5{Wj{0pJQBXqo2HuCE4dLu#<%oW_SGIH;}lFZOG<(IOFz+Ro*H5w zzb~U%`I*YT{aXYAt6DZl0b}_yeSC2YC&EUAkje9UDMKz*hf$l7A$xfd?RH}Vnc$xc zd(ECxFUg-I{N!`d2QR65p=K^Ra#1kpdd5?+m}mqz1rt}#CqqH)cXaU-4KcMagpBzx zK9OmXj8iZn=A&`{P|~2Am$Ko~c7ebu z{1zl>chMpkG-w7pv*sejtNpl^i2DYf>-1pdo72XTsw>v(tg^@$US?`F26sKU~OYdaRtNfe#ju_5utnb|yEN+D{ z>oHzAn7}HzZ89vd`Axf&)13wU={WplB9Br zx`VuHBJ;Sq3vdc1upbbgg-@$Qrav0YQqLDqT>Ee@ifar%eXo%|(NPU%<>(EHQ!tTb zodVy_meBp4n!4+Kx)Rx1-iysUysId zo=j)>a-r^G6>bImzM`Q9WJAngHl*1~p?zQ?{v1E;Z&wN3ZLaBeSH$X*592-9!O9H) z{}xtV<6o)YrW8|)B2B-$^^gHcTf{E=5lA-?4Z*<*V4RLXYKCwLO#`Z-` z5D2WoHI(m$zcnCtpY~&G4g7_ghzZMxARy}-E%DXVtJLIv4Wl-fH@ zf(blo^AYDmKjOEx4)bwLa}o$Nw&T*|J#{)iMKHZKYh|?738&!S#iKU&vaoR@=7Vap zPvHw>Okfo*O-bt2tUswH)nYS;E|hT!Ch$1V*G1>@@5n$S*07lbn7}Grn!NW3?N1(5 zuEEmNCBP||z+)o+O5MkA1Zr26?Rw%M5LhMFk|mq_lcE!qS=H|jLNAI5+=KJFTNp$t zThCW69iOMhrG{$>p2_l?{?z<7tB%u@hFd>p;}krk!dJOc+X!~%Ly3&{&+#~j+du#Q*c}Qhzt3Qo zJ(~(W18(#9mv~=dR}UOwgIV%?cfkAdScPf+MgK7hydO+q5l4fCo&om;_?P&4qE%g> zpQo|Dof8Ecn7|_uf4j$mNXzrl%F?I>bh2(L6dS&wv2_QLZY@&btnpK-$M2kd;F=1D zyq?h~{1h;L4rEL)*=HW17;lTCSd~5|751!rL>oWVCSLHFWx~;5dEUirumw_I*8o4I$L=Wu$5xf=g3qzVt0?~jUS*z^s5;{T(bj|yrC3$|a4M`z zzDjMl54}j7Y!pH=C-^E+FAD_X!uC|ij5|wh?fMc-^Z4_w!NfIaiW27bm||7EeD1S7 z_#9o>+Et5)-WozK)b&!%3@H?d$zM`oZ|pJ3ZuB9T=I8t51(RAsM<`zWS|My>?%h@u0R;fUJUzMEu=;tyAe$DeY=2Qa;Yj&Rt~pSu*!AK zVwe(5VP(thVXN4^r(ARf@w*5)Q3kWRQt%+5ZWtP z)wos~ybkP3R~*+Sx{V7X4-Q_VOU&#AqLyA7^sd*6(t%wFrX{I-%TQvU{(|0n-bcZz zDQ(l>qopl9Y|>SWsCPe%yu6u3m&A7vh=T}^II3Dhmn)9o9Ky|&I(rD_eg^q?RBV*aThJZ9l}ZOJ3m?}+fg9A zoOsSxZCB6vN(iR;ZpNMv^5er28eK9@!KzpuMd#e{s`_I_XDy;<({Lg^>PvSSbry&x zfoYIDWwknYOlN{={>8E`jO6*&q-2__KuqYJ1_aF257!ccX-SId5k`(cLpt?@yMk4@ zp=nUyKTv(IZD%cFqenP#owG-6H?506*sIdOA@f>}gJEZaX}%g|6i$Xzd7CrhOi!ia z>@;ZYy(qn$)R|zyl<$ii{ur6Qa*k$oaI|w6$q4AJHn8?ounIq+NNi6Y58vwevvv!2 zC^$+8M2xv-KJk+JhYuto@iEE@_8X69 zEo@E-1df%$G;inIrooblquHj*7Zt1ueUl7*TRoz8TlFU*k#@2JR69GGEt_^*AaKl= zKufwQec@LZZ+4~XI|Zw7T$xBHpZsCm%ONaq!+Qm*PSj5UxlREc`NoxqL>6fa0kS6x z&neF^f#c&a&Cfe&Hw%^ybY<^q7&5HFQF|gG-R%o;H~O=SFANw~n zNGyM815KQIFzeL~1Oi7NVp@`X^*e(}ba%$qHDFj}8p)%pa*xn&mwOSBxaZ*vlcMaH z?V2_Mfukrf&F_7U8U&9#I6Z5UQHKfvGa^?lSew>Y| zNv*TTLgccRY{_{$hE=y-@L1%S^)$MC4FSdvCxsBO|v(5s6V^lHCZ#ni&fg?dR zn00J-hE+HYRwRC2=?pJ)>ax1dE)1(So20@dy(Ie6ryCK8YHNEyV3I!T+i;*j;CNn4 z^V5^+M!>7Ly6kb(0ESf+2BboxPhs@j+pa_;y0)_hqbom^fNMhp0!JBRntLt>PlC9n zMao3;;S8&A?6XM3`TB!TK#|hSaX7=OxqME2xV#5lpV5Vg#HocguxIUM#cJDFfxr>j zn3g2DUJ|5SI-tZ%7{jm%$BB!?n-hH?trb(we)eNnb$4Sb_{5mgf*qZSNPOJo4Eav$ zloxF#3j~f{$FwBvG>ih*8fnVDF_Rcpy*ic(g-6R#-@Al}gx)rLm=_$YEEqIRAaJZc zrg?Pc(P8jw&`3p{Ih|n@j`SCaW0!;Z{bQaAk4s}%b*3N{D%9SszUV@TNX&a>1AcAW zDTS6H0)Zn2FwK3oGa_Mw_cuDDMi9d)95Emg3+s;s=LR~;%2B}#tBybAk*wL4YTLI! zM517;9gI;gp@ntB1p>zyV49z$m(dffkDXDkEf>ykTtU#QRM@=o#HManwIdW<8%4q0 z78Z2JnqY=i_;;~ANvhMNDj675j~X5HU^S2O`KP~Adf&Q)xT_aK@E8mAj}C<3U*cYq z&8iZgiS_t(O&$!ZunmzIS*|KsxvGdRt>!Ke?RWF9q9Z%i1&M@Uny-FTt4an(6wwEI z?hLE&8x;x5i&e-adr<0~a1)4HOBchm;}W%L)>*4O==~~WTN6<3Wx6q}!gUGTlcYFR z6|&%Wv|?1)TOf7^FNXOxZRooyQNh~(W_{s=C$4ot8gpA_PB3t!z$z$+oH@1 z>?RN|`Y(ogqX*L1k6pCdV0h;$BxwB>#c_ByhE=#X!1nm+$F9o6wCXvBD7uNjiO z6}rr0ek+DmcqGI2xc{!PAvyEIhyx8N9T@5VT)`?lH^lb1m!7dcnLi8I&BzM^v4e6O zJ`d>AUj4OZmcFt+DH#iV7Jfm&Dm*L3_V|2vZzZyzUJoYC*ewtj(o%rEcuwt>4%C`c zdt9qT63X{rmjiYyScSg_usunt;Z=zw&*;mxPFo}p*QckzoR9Bl+Bg1PgT7uQ>Fdl& zI}m7T$QcjP_hW&&Pur>tf0N;FH9Si2 z2!)d#WVg{R^$)&+j#YSM5DClO{05ib8>ow36@kFt(U|7@YUv)Nm)Sq-yz!O4Abt0)f{9FfB=r{vPCX(~62yo&m!uJTizxcnc3w&)HE~IiaFRp!E_= z^YOfv2RRbts8pFT|cJTizxBYvZf>Gc4mNVmK|;1wNA^Bt4T?!?1nva+#hd4^SZ zWDtoxo!!Y9(?yEZt3+7$!E0HVmZVF~-N`eLMatm$CBkYH9vMWU_5OjRyy<4eedim2 zz^ize=6jG!29k_no0aCz-w5k)cw`WXF%1Ti8(BF@1&>03z^jp%=KJR*1IV(UIZ9k| zp|AppM+TAD6Fz{vIdxevpL9ha@H#A}`8o7M2M{NtE6VBgE5b@D9vMVpaY27_x6MOk zK|LlAcy$=l{FJoJ{vI`Vk@em6 zm`TWdfxvqqn3klj)!j(q1U>dWalV38cw`WXjv4*PyG4e~TJjSJyr+X{-cv8z%yWY7HHeI6F9;22&Uw=0exL$6kLd{i=>x#+GG2&}>$X*`;v zR%h_@oyKnE%@usrFoDM_zFx91i0p}(ryMKs6#V*do?h6eLZ3;msQgQFZ}`rqJm*O@ z**aEJ!JdFP=a}ZcgM2Tw==>Zd=16yn{Sz@Q+IYS?m|PqZskD*C3;Tn3Pf#SzPBMqY z>w)Z9g{2C9qj<#=zXg7m5UE7E1Pov?mg0Dh^P%;whVhg4Chh1r<5hHNL~dE+ZPCHT zaKZVkobFbgOnR*c4Ts&A$5;Hsqqf>|LgTYNLW{sE&EG@64WNIBcAW6?FW;fpKZyTP z#T!7C$0O!Y#sd(2Nx*mL5D@#_vhUW)m^s@7?h zVd2Q}^yT_roM_33f90j#)hAL5jEkaa z&DnaK(BypfBLiDEEds0Rw`vM+7p|t6D~veNm=mM#t=WGU?!%X4m$MrOPdo515 za6(fa@me{@DjaM5Cm$NZhugrVhReLuxw_!l`-+@#%z)d_yesEW%T6jS0;`S}7{U4e z`EvL66*ytZ3E#-whX!a7Skib^@H>Uk<_N^EiK}khbi=n4PzPSMdAT-hiyYbY5Ro* zfN7qOPR+n}S{UncsFH$JYxa9Um!siy>wr62#EDD2WpTrSP{SpLS}KoW z&aFYP-Y$Vw34W{fRJ|Q1$Y)p>+x)7#f>k(%6GznXUHu=u<-k@UEOT&>K;Q^qOmjc7 z%;B>Cw_s-E6(U6a;#gFXXddn*Z{)Ga>*vG@1dfo!v?R^%k`2EP__Gy@S}8dVN5GFw z{?z5eO)x7N2?2|y&?-~z!7RNY@V4=ETGOF`m-(PMhoBSp>lzW)bz+3z%-90pK~0nL&mTH#WNMGDjG8iwsec5mzKTP zB9=KH0RPKlS>nd|0&%JFc&M^AjxHPi1u)I`Yp-QNO5tes&?i;F(bhOB8q<7b;)(+9 z38Pu!=R^go@b8MmuiSairq&F$YGEA(mlS@ZxE1iYiM07pwP-p^T3J`YD%?Iq;)wlR z@Oe9p8AWsy2>eDd&HdpH#)8{`Y3yikdj+f3P4R*Tx-rzG{!j|=Y@3*A<74=)M-*|z*ZyM7)s`5qV5#LfEaBeZp?=rQtg|*#-*rkhu6s*F1mq={uRs&4GeGV>Rq*@ zc?LJ2WY;XnsA^3QZM+S*ALDJ%I1j?tjbT>BmI_wkzDp!RHs`{q_%ZD1V{3tUXBh<- zes!SwtqXvBE%o8P7%;gvls5dTIc=f(nrm>b-*A@vG*!W> zoL(`ox87jdZN(Q5iJt4PgEDsnGbxG}hz3)lA=lHD%IDt$rg=L*mkV!Ad|B7#u0p?y z^MQL;NiucIg&B=}S<`-Q3RVp{H5;aHB=q9`XCM*}l5!#aix0CmoT^|I?omY|bnta} zc;AN&S{Eb`I3Jjnq*K*$A!PXo_F5gMU=@CEB4KQF4f-c}vyb}Ah0`x^A1uDzacXZ_ zwMxaB=R2sQySu=h_!;y>-II{L(go@-n?e0&o&p^8&&R>vq4Kb?D(>qnQLMtz{UR~S zyM|o2Ma3qat1l3VWBWjG?_jF8>k43+dy6a|F1ys9#g^Z`C!7a>&r86wDDJB^%|gC< zeinN_F@s_iwjmN(scG`9@L4SO@+N`6Pl9PlQpc*Ha%2FjGChL&J9)wOg`?@>jwfJ! z{h=^E+Lx-9pNDC6+~H}VKXp@`;I%!u&JIvjn#v+uSy8OAo#+ninLn+3@1z!CHuDTP zZ1ZR4mo^E6YxBX-cuWBOTImX4nx8yeqK4PYC$jq+bcJyc6Jk5hiaiY{t4v^{gQ_Z6 z)yU2p&Mq5Azm{Cn>Pyzg9D*-b1DJg0JjDdg6Q;S}>(f}M5EH~EcvqwNo#1CzE3Q!W zNg&lZuX$HzP2#{RG>H8Uu0^q`eXV}b@m(MdY;_7mLYg)oU|9G z4tzh%WOJX!3i$HMf%_3Nbn?4k)aGMZ`UujJtYhpNS?RQNeaLzH!W8%zOLhUBu%sA-= z#VXuVMPhh^5wi1Y72Cd5UpQL?pK>DRyi)RTdFmP!)BW){2d7}d#>54-@t*Hhl%^(L zKHnTVBu6mYty_gY5vy=HNz&Xs&7mMQg0)XrE0iE6nl5vN?Yy?nw$#{IW*7%Mc>9>> zT7lx^<9VWU>8Ue47O1sOp!siv z1W-zh@Y)5K{_i%TqvTSequv(4^nWKthy5XD9^VWC{U4+>A5l0T@hgAInv--i1g8JH zje*HJrB7v)dk`?KA)@$d!=HcJrv@Yx@H3t6wk$nCVAzq@YR%so<$ov2RGMG#US%2XP{=UjcYe*f10%Ttx9G(@*8%}nz{{x_mb^&cBf z|F%(fUV=u2Pg~&j{y&H^m4@bda{719v5hj7hT!kb>ECY`6J;t5!OOceN8aA+9HD)w4v|K{sNz$utG z(E6vmxOFFLK^}3U`Hv7*vyG!&ubPtqr(j~lsULFOvPbfW>km0m??fmwvVMD5y~0Nz zuxe-3Z}Q%CR`f{nT~34)hq9cKY4)?vc>_+tgt^IQx%P#}vT08gJyTK1K53nO8aSB|eqV3JXQXAnB3MW3-h+r4usY6D#wLoCi$c9g3!yBgbd*Ufh*v3S%esgzZ zCikui9UDH7NA5PICC?SWM6T+lT&s>5jY!$UiOijmEb*tC!@~XgfKxEhG$OzBsqT*3 z!3ndjv)F_Z=PbX7H!>!$%HnaZT#Y|fg$KN!mu~-1F-^}X&urr4aNvx*vfoSDxT6nf z{;uN|So-(Hx@YD0Yj}Kmw;7z6_+7;c^Uq`t$sgy0Q!p_pN4 zvzNlCMOWqd5zVR1j8=iSNqs+$@&drIUlsL(v9S;Wy2r8uzK#y=TMi`|fk$o+cOMXIqNo1Gb6qxyL#A znEHu4*E|LWs?W=M-<|kvwF~%DJxo$D9WOca(!|LEfmMytFUTz`cBDbK7IEUiR293r z=Y?JB#d!jORYAKi%KJN7(X*#hIicsq&$u&c<8XA`5`n-f{HFOSY5WWIeDiR-H9-ji zfmOJi_!$t7RIK>ABR`evy%WwYE`PDir`}Srd6zrdKTkK1F@aUjiq6V6Qhzx)E}6~q zF)UxjW*mvJoAj%OKwy=-&N(?_%TTApQFA!qab3lNU##f#&X%9@fXV=?%qyLf4_r^q z=^n2kqOYo0m6fj##&@nS5LlJg`a)8jp0PS<0=+#Ij&>3cq@Uxs_h@o$#tr9 zr^D;Sa-z>p6|0<;V?X$PKY_q1T>kvjp`U+RZTh5YrLA`6>s9KqR@-uIEY9-ylP0;_aA&dLjGjiEauLpfo{&q=+UTG^>oL#4&Z1j$z`Z5z z;c#EcWBYgs-Yg%N`6;80jDHKiU0gQYD~#8Y)XNjILMIvt1b!+^bAPyUKOo@i02bz! zrr`A*ye{T7dp_Ld>t%MIH0yAW3QHia@<2AOTAG4WFwwBid^i^BLMz68;Y9hfrX=0D zBl~2vSRk_j8iYiuOf?nZjf zsKrLrPZS8Ox>_Ltg08ouhWvb4emhsWZe;4#T5QbTg$ho=#Jki5(CBb8da+1jW6YJ| z#Lw%t(v?ID1XeX%%DzG%PQk>l#)&X|`4e^IV~vdy z%RSWDU_l~0y0TyGwM0`( zigt#R-w8H!BwFo!4RhFVHpo{Nh^B3#;p{0Z>Js@_ zSQqDW2KT2h{m@AE=~yQPtMFPcw#RSO8CwEBe7)F@E1m*@*LpF{XO>ID$iZD%lx=cU z@Ebj}AOUW*JgnZJ^9JyHqe=)l(6L`wBuB>9jLBcW3SV$`j9Pn(6r%FfB>0i7sT7 zswP{zc(Q_3r#xce%p^T(K3bbtzM~hho>_~%TJ0ea?;pm%ONYv|muCTBntRr~cOktK zYO^;J-4(1#88Hu19loh2^wcIocmy`~#q0aHf8_UbHu(TOE_<>tr)Xgp z;CfaJ<8RpzIkD4~DCTs5|)= zg8%PW@LC$ z=JGx2)x!$-Q@x-w$+ZUql!OD$3RZoY5D(v*om9u|)h32{%_Ntj`zzm`_Z0}-9x*LR z@5ap}kGs1mjcdCKZP4@E0rBVL0@oUrgG^vG6av%?gD zz#}K7c^stdP0l}iqo^zgD)@Qv?~3g_Y_B(QuJKywTs%<0D%|6UM57DC$l>`f6{lHl%KS;>xf+7MLkKcOZ+{1u|CvH!8ycp z6p<*ZVoW|xb72_^dI^A*(-kXDy~p76_bM zO!J+Fug0WY&F<{7NuYvNcmxm$7q>d3p}jL(q_aRE@F;_6ey&h@E|z6yEUEWdkogE4}qu$t!ae$IS_Z^o_XJZ9n1aLf{F_$R^c6Y zk$6=n4+7fwF_&ex1Oo5NW16?96L}D;mdKXr^f|~37jWP^VN@;c~B{1EL(A>mhe>g zcg63)XEjF1)A?Ldon2`}v;mtaHbB z&aIC&hueII_iMolH72kM@5J);t86o{Tpz)%e2!J)6in#c>J6j$o^V3(A#TIgDGn0( z4zEY^#{z*>cqf+McJnY98p<Ezhpg2V!`VWSxd{20TDu>%pZHt4o^MaV3-wHK;lCP;Q(17Q*$I;EO ztV4gO!gs3GRFm@xd*a~6+#uE~a)lbFU}E}5SD4B@Yp$=|%!&B&$3a;!iFG(~OCYf7 z;!SrrvtTrhTECMMm%n()O*X37$c0;Ta2en-zqPR&B=Iuu_B?|V`?mSYzm}`mx9&@G zunO-ri-gO;VRGm7eErpCY>wK<8DjWv#Xs5%f(q?(OOkobk@9$6cUKqp&%ry=n8x<_ zSiAQKy!kqbIW0G#xD4=nYb2D%$1T|~vCCv;(D|DhzZ0y&H23~YQea0s_ZMB0q0VjM z4mbE)T%p_3@D{Z$T8+yCzbj1hbG(|E z!uvxJY*d9#YFsn03e)^vnI$d2p10cWnHFlCg5NIwC4Qnqvl}p`#E*SWa~67P+}Ebu zn+YS-t!dyD#%syRXZi41XFMAj+MD7OOyG9I^O1N1hQIY=rfD_;fmIW#&H&$>*3`4! zVQwQyoevf2jb{e}oG4Dg1TIbP_d56{tiR*OqIC>K0@aLWPSc>#me$lrrP+xKx^e^B zefMLjLDeWu!M}^kpPxq3=_XX;qguh2(`rlzs)bWwF(2(tA4=yojE_2+{xMxjP z3s}u-$)K%Y1fqAM3k>A_RmFLm0n@w}Wi4PDCj#ER%fTvKmqcPgUL5q`eS1OUzG_V9 zym5tRyjOD=zZozsNlv%o;4W`bRYvtxV-;?9A`!S>sF2k};LG-exHc>HSXXd)iDt7zcqVD z-C4}1=XV*ahFN}-yYG*r)8hGVFS5tu?wlrMS8O|rRd@X)W0mnFCpcA3MQ=`AszqFG zblX1iP6XR|+XOIixb|0hU#;2Ht9%+@ny=7rcgv1x7r~Y_umY^=I?xF!Z=XYriun2P z$R6J}k9=ou-#?sfGjJA&YsO#X6BnbY+w5e(H21CTvmpEFbbeoP{c(U*QMR9D8{PSI zMukKz!p~L8`Pv|q*%VI%Z57LiqisSKXb~3GkJ$I@8_ezwixG&K6Fk1X#TC1lay6iX9_z#=`diG&$bWpgT2e>?g>#^ zgwaZaoF#mI<+w`$ZPotXYpAV5m=>XFgA=z*WSuIV5eS=ZA7o6F{ml>j934^Wx79hw zT)}$~n!kfRx5%2^9&sPX?otF9ZePVga&D^N6ihT&mjqQeZ;`)W(L@~ftQJWw?CY4l z@ko7vz^bYi$?(IeME#lRa$<3nS!7U)bq;Up{Gd1m6RTgRfV*=eYIfd`6ZMWqk|Kx0 z*#qiURB#F=Tt=ioX7X0~mbX49X6Mc#cjlgSa7j2$F@aTYToyx*!9eZvG*OLf6J`;k z%X!(E`wA#d!Nl>CsnE9mc6sLOYMfXKaLdh8KM3jyv@@v8RoS z)HHjSJ)n9z#VME=n!gy{!A^Pl>^hvtU&U{=+T6flg~KR;z^adn(!l%oZaLhz5ht$y zRFR#ZZ0vjbR8XgWNP}fVGvp4tO-nrt%e>7pKc_*h=9`@iYMOE46~9Ypd@rj*kGDh# z1Xh*jzx48HKc~j4O*t`<-ygL+z__Dx%>;qKs=~KvFrwia$HgNw#DX^}a_cv>YfzO6 z1Xgvpo(9MI&Y^mRO*rxOtcr9wmEoYaZ9#E9unNCJ9zF0_MT+)6$_|TsBiO(y@m>Ao zH#KQmmD1iO8++qnU%uk38s}F=s;rXs<92MYW6b?Jj}m2 z^>)w@KfbGo_sOdc)hBuj1Xg($r@LJQ8kk=e2&}^8&-aSBja@Z< zW_OnTONlbiRa_pSyk6a3vq62wpwz~B6?xFXNPR!wglh6pMqt%{?5Y1eRU>XAyqQtX z-W{S1tol!$)PHhbnZK)%{;}Dclj{plg;oD~Z}iXG)s)AUE*G*cwEt5cWlx1w|0x^# zrvw=<^D`?JWO~*7Q|4s^R{f{^)qiS9S-m>)pL$hBVAX%>*nd2JfAjW{mDAI%OIo%X zw}}kiiU#x?lcO49O7NTJXUg(Bk!H-=mu2*Pvl^#hV)y$rcs!-E+A>ws1_M6vy8%~P zWEbCCE)ZCS%SO{OqL}8t{9lyDYwp2K3&puy^-`aiMz(F0dauuy{@w3|g_79kLr$r% zjF2=0R>|YrDuv6Bs5SrppG2t*OkDrnO0kz(${M1K{@VstSqyHi=uB-&|0_{y0~6Dn z&6KJ0#+BMAqyM&nRdSA*GPm)lQXBsyN^M}`i+*F}MRD?vby zM41O&De)irZyQ)uRIH|rY>ocd_!m)X0~7r}&Zc)%O-qR~`fnRp6>7bX9!sqMzYy34 z_6jWfrN3=p)sRZvsm0e8r8fTmh*raO>C2~WN{KRBuu+N&q z%4oqx*;Dfsp7_qc5j7wTnYNL$)+XhxG>(Cf{<>XQu|0GInV4`G? z88qE6s?up)m?R~;(EnXdd?sP-` z+1{MaxV(w)0_456Vc&H-ux%M@WSoKt9HGJ^??+j%Zl4_3k++8g0;_T><;&~unNx!s z>$#1JN+-75usu7QpDyDROyIZ~?l}->&2;iRu;=&A2n1H)*c`r()6It6%d}~!gp+}U9e9iOU+e9?=yWwUFwW}#oA0jFRBuM|sC;tgAN zbfr0~mp)z~unv$tiRk}X*Sn?3@8Rolm3k+-&$sdwWf{#4FCZP=0pmh5_7Kfo!Nz-#^d z!#~oNjd8VNb9z|_1Xleje@%Y=(w4^aRVnV{)y9UIW?8X_Tt~nun814$-0QxIEsHd2 z&!)a?DG*pC*2G4|wyc4=1>0h=P*`ur<&WzaKWR#3!z!b7RZHsb^Wt8ks>tAkZ-*_S{o=5A&!lpv0x!!dX~9;cZtbKPpm=6CHQ5Lkul zH21nMv|-bdteI3?P1wQ0eF?4$lJq*jnlBlDnxNxE)QH|G;;dPtE`TzY%VIytibmMnqYPW-d}jX#OtyLjJ!t4*bUkCdyPe@{OM( z?D7JB_48rIkLxSgugi0_3J&~g$#0d&*NPIFzw!m#>*m9L-KeKv74~Qpy~3PB^hw{J z?o4&dOdtZSX2bsECUo_iJis*X+gIt6Rqx%|jv`Y9tFWh}NRZ_XN#?cgZ2D*mfv^pq z1H;Vf(!z6jfN9=SXEr3wPjzQq=e1R^3i~9BL~n0PV)3>EYv6Ay5OsD&L)h7>^z*Jf zz_cXg1X+>>4?D0a8*LP=jK2Ix}Yt>J zUC!GFiap``gKK7xB?gm}ZjMe0R$+fyk$BKIl$1nQRmT4ABoGFHv5@*>qWZ<2JixRh z&EU5?s-{&{KIe8)unI>8iNw(B;iO#*Q1hql1!8<$EIirSQ9b-(o>pAZR!-ax1^TP7 zy@FLZ!U@~sv3<^e_Rp{O=3d@t&m7a5zcqX58hboClM@@CPd>D#mq=h6n3kl2oT$0h zzC+zUB7r@kF)c}1oM_`_c3_9rQ(^CDO!NIsPF%<=JTP91z%hfE=F!WX(Dd*(`-)G6 zy$CSPeTs}DNvF-J)VESaWrJ!iRH`l4&VzS9rmG7Vo!27nTSky;O_tEcJ|-gZaX!=>W2qkQeho0q z4=6k+`KFMuxqtriA`( zE)ck_V4C}7)a*@2urV8azNM1FJ=D{VRGi6u(cI+j9t;67L+4&NM0OpUK9 zdsnp*2wZBI=HF4bjLD-@z1g72HI>ThNJyC8guZgQ0OjvQK@;;@be-V^z~emc;f^#S zR{eXh9usRQScOMwk=Xsnnq2u{%?#rk2n2r9nCAWrUD}a*?j70AyN!kNz$3LtJXHwU z_Q{NO`p`%qa2a5l-_2oEkJNe4hpkD-qJE#k0M47xbRKWu_jMLjkEu!DH#-LSjqsSb zqIx8xM;~TCDwARrehVV8X1^^d_OW5lm*ffr&N-$v=UJ9O_@Loz;;}*@LIMA-7z?m^ z@LOmQH;R>?ktPs0PnedZ`gZ!nX@e(w+0RcP+9@SL zAaI-prgLdSd%g zz`u*@v?Sf=){A_c*?{d2d?66{2{Fy1eh)Pu@7wiZ?^phCoHKS77`W7?_lk}RElR9c z1^Jf5{9s4s-o-@01b#yCsW$GfO@@ATWi?ypQe5LOE!x=Z@d$GDeVJ9Rj?ly5FC?)= zO*mvgJZ5_^OI~-e3b!J$hxNyBYtpR|G9Qv%_w+JP2TNQTU*fpGqQCpzX;3e^8T06xV`qvQNi_?&@u zDS(o>V_1hJ4Fpv|oq;f+#UwiLeJcycdK3;2rp{-(%)}4fIv$vxS#%alkx09VqYh$I$miiSeu&D>XX)K5p}Z) zV9zu^*3-yB#zZgQf#58Sqx-E_1E%@Po$)OgXg!YUW?Yc*JHhV?)7)#a-3{2A?#KN6 z;${3>ScPeRqeE2{vFH*-S6c+qBcJC$)0}bY#wO_yRWBMQ8k?wt>!$;m6b%Eb2CCck z-Nnm1v2YgIP%)WiP70$q1rx1SM8hFN6SY|{4Y7XsEb`=65?%9Pzd&GB#D*AX+#^tJ zSzZ&nWVC)3*%BW>4_fV^I0X~>t7BlhlZm=t$IpODG96_fiUn z@1-~e6Xoj1!25!=>SHxDIltR_3Td}tpAs={n?PXIQk^;Q^WsT${8){RY0ak)&zybA z8n1AHfaKZRo=^H!I>HrC|jbj5qG99`4~}` z*;Y%VI0X|2v!kG2iwd;ac#REl~bQ;a}hRa^aV7&)gVZF*Q^!``_A>0iN? zx#-7GoPvp^&mzHXX-!&lg~moB>-wbdZXdR+^(cYBs%KI#>_2Nl@7>neu&7_3On=vh zf?$3taZw{+3Tc-nlLcX$H5K5X= z_fq2Dj1UN{!o3pjuZ%{L#2n6aXU_Sp z?xozC<^Q|)%k%I&{cP2ztE;D{r)Q?Br!^0Tbz<+B9VUWm(KREaK{jf}Tda09+V1RX zni*CN4`W$tWz}j9{)17U6s4|rJ3b|-u#qLUwuzuxbmmi(k_(IQz&CA-w;2~`bZtn_ zTIv(*#(uK~e^IKQ@%iQ=6G64;x)i?Dbj6MLPv6j3`k=LG_NhC49D6Xi7<_%`4@P~0 z>)?etyu`a&#)Xb0Oa#@UvnxFJ$@PKd%h1=bjTmfN@6s$v>J!}K{4B`x!mA(OA+?_0{00ZKhL`>`_c1$!{6pRpm|EmL+T?FC9JN@>@=>gFpG zjP)MXWR4PMoOSrO5&MukT048gIr}WV*Isp5i}A)yOA|)5l*f%&+4~c<97TR}%2%uJ zR)HO}jWg~qX=);J4r;;bw~o@*9D(}*LPJi&i}GyK?Qup&m&S~0eFB0Ni_$DVoryAq z`l;*ZM;eU=4Dh5`rZmft=90oJ+P{#Res84lanUDFs$~mn%xo3MY85-KWM<;P+F9!K z_YuaYKZmK5pgDt-R+Jp)bynYPu(4h(WxAK4EAmRG+p}= zxt{4>rtF!vY*Od(+M}!Un3?F|dV($cG0@mrE3b(N{@#{FT^Xs}?Y5Xv8uk%xWw7SM zf{f!i$9mGd)E|EBSZMrEEhOJcM(<=4rMhvB?HV%JaE;%eK(*+-h?)3a`~d3{Kg{q< z$5cwty9r7|9{u+jY{vVMM*jDnCJ$-b=~z&d2}%sB@p+`teWj<#Lpn;##GPw1*v_!g zhVRp&CW7`ArQzEgU1C_?5u=Uq!-_Jh#g?{U1CEW;2900L%tVYfgT0;~Z0v>zeoD|@ zptPc#4vS$mBZG~G&$gQSs*Tc;U7j;ads%BGGZT#`&tQ#bj5Usa+2~2@rAL#}a91=T zhUFeO)`4PU8Li_RrxVo%RJYQr57#=2XFOayHSrC~4c9{X9xi9tp~w`(dr@93zcGZCz* zYoBDTj}12bHmxv?T}spOrYQAyd$ZYj1L2!5I;&xSqP^-F zDt~Vt8?V*tAokxa4MZFepHc{vP(qZ)#>~}TWDrDgAo^q;Y7FkV)>IeO61H8^&ek?3 zPD`=Tn-D0WgeaGKIYVm^CWvBS!@JQ4W8nT7(gr0^OW4S{eX91F%?6@65WRsIod{vgK6(B4IBC9?qj`wz zUF;uW1A7|YM=jaTmbm*GnM?0B5#rg~vWGLYkiL^lw4&6RwVkc_Immc>)7x~7qHP!S zw=q$g%by}1uH`+Q6>KxmsK2$jiJ;ddO2hZ=X7p8SJqtDJC3u-u8MH@DYYC-tx?O5w zr4VCVfgvVBrz3V2$tD|xaH73O$PDS82 zrZhxsg(b2JZhnU4#4_nQ?NJ;h!gD+}u&ex}M7F6ae0dS#$Y?Lp{t;!QAx{{d%tS02 zVAR_(Hx+?e^k~8k%86Fh_va|1zsnNS*rk1C_Pm?VL^Yu$eAOz=hExRhkJ%#JPRPA@!bsecis`kB(<-JpnXNh zm_2T(`0YW)8UCl~2-1jF(ZcPSO6uvC%~s6>)jC$H`Y$arv7ph@TEfOzut5nLPfcmN zjS?xXqFSPiElEX0)m-hZ&wLSTh{!CO$AWn?BE}1Umo`iU)uLrH@nk~=z4L`|X#=%V zqQYeUkFbHi+ig$+vyW1u(Ebm?e`8H;C47B>)+@@G$3$sGnUg0|c}h^NY}eMT6&Y1# zLbMAARoF<8*hEg0C?k<#TmCL>tfK_gLVISSUWPhGC!cc0(}uq>dIVqGdZo_4TSUKj zX0=L>CS-a85dg$jC!$Nl3$<1D{Q8)3`&CNAZlMrAp9DmoMrIqQFFjNHzRIB+ai>&D z!}SAf3Mnn%)z`( zp@n7fJI%FJq9}n9N{BN4ZnrU^iJS4`MMG%=B~(k=Ai0)Gl!^F%WPM87M4ZoCz^GfI zqumB2Qp&;x&CXP!D1j1MuPEd1c0amLQH*r~-qHq2sFtvSxt*yAlu$yH@pn5hcfl3C z!p4Ep21=-wutD=Vl_*M}gc72RzuRpbthzxTc4nlsffA}EY|so)C5jR#p@b;o?{*s} z#*fln4unV>D4|-y2F(Cfq9}n9N{BN4Znx3GFR%XACtTV<3DpudXa=YfMG2HpLX`1$ zyNy>zn`p)0c?PYEYKh;6=bf}hWSqiE=ElA?lt2k3MA?xu8v7xWE$1OG<9e5DTu3mR zoX%0=cgz5XT$%Ift>yi?8Qn(YkOWF7VVkFTsJjk7uJQjjBVTfM2DBa9H2{gS}_3n(GVyI?1TE7e}ZP6)x9 z4(uQGGt#)aaH`CGqXcRR&v8!$$gWuvpKt((LYtT*P(te!<^8v-=wnZ0_JlX?V`nw! zb~VDN^7*jL6Ql%c31X{PW&L^hQ6R+M)2pqFt|7(cwU*9FJd6UtqA z<;3+4z4i$L_d9^^<8)tUz1%R!=->XJiJ)4djJq(vH+aVV=J7H2Fr!UlTPgyzgdgc2 zl-2jQ_Dxy!89~F0*ujY=f@+B}wie=KJXSUMaBPC{s(k}pNZQV=sNb7ZToYwFu5i4; zo$!ldiJo&O7&)z~i4bi^Em3ytGg0wpagV=Rjy0z5o0*D0En#o=_p*BJ+&*wTT*f}K zZ8%Wg@ON!2&kwx5ih6O!0`s-@^NeAh?0I$L&e!^!Ubm?hrD3OA&y}_lW9u6)hS#v$ zAUiDJ&I`0A*j?;eHqR-;nbAG3yUB*A7YXxO+x}Qx+r_CZjmIt}Ih9aClySy@xQw~W zEt7Kl7*`X2Fglj#Tp|dZl^|}ZUJ2X%jQ)oEtbb+ZBua!9jy_rwJWuQ~Gx1~RU}IIs zc}(;>jvqnbxDsXDb3{=#9O&S&JKb2rd&%rn1Zs(z{^?dxZy#J5M&kY7y%JlwPcZ)d z-b@lGq4kO~?wtZ(YHF9m<6h(h<55MPia;%4!!a{dewHWkjxEB7C~-!m5?Ze);~WD! z<7wX#v}eIaNQ+oqNO1ItGVYNgYI2Ok%xM&lPlJaUwva?!NY>pep?f!vmFEX)Q5yD| zykjKn$ui8S8)%a@uwJ2sdzR3eU=Qr6hZ}@@^*6>vK9)90wk@QOt+_?oKzo#i@Aj>n znBcGUH$Gl`B5h#3LJQ|8VFPPYl&`fWHDG0W7=^26kylQf)uOC&{xYq*G*!3m zv0rQHl@qU)f)4IE#dCj)DsZiRe&Klip>d7X4EyW^N<_U#h_Ykvglyg?53D_tmlf%4 zUo%hwwS}%ni%Kss!2zl+b!b*|B%R6PHE_$>~S3i|6fYA4;H> zARId(3_DxHHt2;v_s#TFo>7>qf4=!6b${<7tgXIQUb`^A9^x6=|F9PG@6SIreJlx- zP@<&kGu8jD3k!X^0M3t5PfuEwtscyC>1Ry@)%yAHh5D?5D>Ish1Ch0(yS3+u2wqh? zA+P6{XD+=>$v^)RQ<%l*m09-cTWk=&8_nzQ+XxXn*|W+~f&|qHZC;ESbt|(?K4*Z4 zdNlh$pN(OB`jxUKf@*biE5)w*xHGRq?|`UVqoLK0PvCETnwkizmG4$LHYv6e+uko5 z%Ys`T$#xp5u7VlaovY)e@tm+T4ol?FwRsKR9uDU#OJrg~g8Lfe z4JyXwRIAKv_s@Ekxm}3uzgL+Bm0SbstI~5bSj%jQ;6oe#DLqGmYAq~ZfZYnN!gib< z48#h{Cu`d_kvwnpg(iY((SC!uytPsvx1e*w|MMezR z=o?iuq3OO*-XzX16_GOfRQKAIm}l-vY{35fKzKCmo46u!Jl|Zdi;19GxptRjW%pKM z#|LBv;-A^ItP6tRds}N8nh2^Dsg-1JVegvx+G{u-9_O!H=MN3z>X1q%f@;y@4^b~) zXC{`NJb{nDz)S?yqN4{Q$v?z3@O2x_qPM1=MRDd7eN`*InVR%(d6=m$CCo{9UTr;F z_|bk}ixN>U5~A$b%i_`$qrv618`!OVsR`5)Hp1IQt2={AgN@>swS>C8|6CA3~qcI>@#dr~`(*RXNq)7kbX zUX(yBVdFyc^enjBeX#K^xJ_c_?=5+z*b>qPN@%^J?AUwfbe?`5*;};c<({~tB2Y`% zXgDz^YxCg**l6&`H*sC5?!4O3tdc+ptyh#Cd+%i7V?BEM_TZH+W==(*mas8=Xd$-u z;AXJlc5!qf@8Zv!j{Zlk`cOja6=lcXJ9EEG_EID z>n0_}gaq-P%#Z|1XuYEB*n4Nl>R69XVZ-?GlJ@m3B~VM)=%2nEyQX`CjU>0(iM2z6 zdF>8!r45wOdZoRTy?)@kmgyIHd}}+Fzh7j(AH?f6t=CL+c)QT*5*NV(!jm+*dJ$T< z_fA;;0_>PRTjMoW4 z;1%cjhgYiGoO0}I)$XdI%=2hy*_(AFKQ(d-qiZ#)MQMm`n_1pg4Dx0E+;5ZfF4ilw zaLq_-f<3U;wW(nSNqS@`3_3GUMam*LW zPmfMlNANf%e((Cvboo1sc36$wtWo2@`$@U1l&BgP%`P37qK@1%*F?j&IbiqJB`>-s z#*aB?B1X-PW|#X%sf9MrW0Zy?_&k!IH#S+v#aM0BhF5$v>$$nF+9Y2*qclVt!k)6t z=T1u8xIVM(#qZIwM~^>Uz$ig$f_K|r!N&LKgtJjiO~mU3(QM;5t}ahI-$cWE=P!}m z=fd#=qX+ac5&aiMvllChtDl4CGfFGU&`*(k-<}Qi67q+dh{iySsrJ$H?2!44(r`3j zU*}?j=htulW|E0GwKkfSs8!!K#(NQ?Gz`O;5OT?30Pu|93QNbluf9ea}ip zX?T{A7|Dar4zWg`v1qif=vbmO#93a6vv5A&90y{+(DiQ=Xqw8@yNF@qfTwmykts4 zw7L?`8!tVQxP!Zx2%6zUX^5E^7RHMXTyMSAxsr*X`QVg>v70koo>7@$r!v|qnsZKR zhy#ET46{pcvu4!7nZ1{HOvWe`L9lp7+wmGlyS$ia+c>Tk@>}M?!;yf?@q_ahw=ah!Mkl;KQ^TX+snE?rL z7R@W#-h#6P(y;b{(f;sWY=he6M%d_x+XH8m+GM|H!i#vPvD+EWsQFb2dej}?-9%7t zDGmD}e~aWdJdS$wYE;ogh*n_>DGmFP@kss+B1ze{+NRv4_N$}WKd;BxnoM5qH1D=; z2)kwvjno#TucJ{ddQO-}`_F=r{AsK8+T2_lZImb+63sRbo@{%*b`hgAJdJ7`$tUIf zP3zV3l#Oc9elrud`bYBLrq0ric8s@B;_va%?Bv22+jPG;r}KRGu1M}VtGT8HG_X=F z+E>&b%szYmWi7w;GZH$M@}!w;G)s&|7%R%Th<9w+zkLm_1x+nfE7Ra$Hf2p|E$iGB z%uH0t|DBEg>}~Xm4L4<<(Tp=n!_$xB-`TxW-o~5g@ha6inlG4@3@)e5abLpBL|DPM ztk6pzBXm?+Mu}4+Mzac=YiMOo&0~~?7?#UL`TkLDj4X>gt5ov2L@1llsEAhL!(t~J zpNbUYr7dlYbi2B$R4Z{zD9hzvK-&ur6QnM=c{`ayb*xeMcC}`6#Q_F>x`Y zw4w~`QkO3pP|G-RtAa|kHf9KCvp;3jig>JWBL3dqj)z(b8&M(ucv2#2ZzQYS^S!NC z=we1`h?#iMj%R;Y$Y|vK(vxagGDI<-KF@89vafI=I#uxFL!#g6iNRA%#F$(YS*ME^ zZ8K^wW|W5OU`Icm9x|$L>38ZcI?S+8t*%9*S?uaHw!u4=I}sae!&8ajJ@jIc`D~P+ zXBVX*_q7FlH@rl5J#t8P(^*T;c{5S4*eLFMbFJQPNiB6&n~7{#nIzi@buMd?G?86- zrrXMXh-1`0_&!df5j@}g?RuujvMSZ0Ei@Asu7~iqMThHQu;;+v?Rcf@1&z&pe^;p%9hGJxvXl>hH}ji* zxKp@^IK3!}qclW+din8#M_%dO??kIqi}t9Q__Nd?KDWXp{c`t4CW0PK zO2d8atdhK8iRMP((T~)=&BwCXzLm5CE9SAZ|Aw%2xm~rW5zezu_WZ^8#*3|tUN3K` zREy3lbXJ0x)a^BR%Pn<{6(x?Ch&8<@u;J$mYfmim7^UIMy&dcFY42(nubNon{-Zly3@@lj=c7VLFJ&k33{NOSPuijyXofBpKKes$#m z8$ENV7R`2pCthzu`Tc4=^#R2yX_TP$C=HnwodS4=zIXIT#UpHV&Y<o; zJ$C8){c~!Rp!O&Y-*7wW#Xs|G#>y^(Y;^9U_0lXcxD$TRm*3#;^ll}RO$4<^Y1kL% zY%`v7lB>~S^Y2zVhtqm#1{bUo1KRO>dkP!#>aVj=g0_&-kc%8$k*B%Djm5{xd(vwW zt(WFX!7)Eyhxe&f+ej|m%0>xlkJ2!9pJd~ABf1(3dp%I;6`7tZ=F$Epdk%hZMK_~q zy@H5v2US-sqU6j|(-`3b2vC2vb+CoahGvt~tSi#PHjW6MfY0m-LLb{evl&zaz zFqe`2jHYF0nR2k`%E{cSYx^R3?9&dLKTRe=c@L&vYl)G$)=3jA9$wezSQ`o5Re+iK;%lSF6u@ z(r>3s1fAz84H>yVI`Yu+`HXK%`F*s=XpxQd(H(VdCu9*jC(F=OxFy0ewc|*2TO8azh=hXk7*dyYB?a7UD#1g zt9mewnTZ@{Ybwbo^*`Tu}fDta6Djrl{9a)?(Z{Or6Z1N(JQs0oU9bW zH+2}V2NyfwNeOC?(u#7Ue-fM5sk?FD@)ougc08$2V4QX?e3UF-ZS14v_!1@K_c3P! zVn2ZR4T!BN1l7V!0ukBoAnpPYRNmW&>Nv|(udw&DSZnRvv+1Th1c-nDVi*u3QV6Pr z864*9fxm?xhy09~>|W9a67+b`%mw(us_+AdE!T$#*3 zWCx-j5LDt!e9Bc^54$lFZ2YXVk44A!GGcx|Y$61WTIM78i4aucOmtjZRNuFI2G|gP zA0hJWwNvDo@cjQ3g$7TZJ?d%`FNPWcUwg?n4H%zB2~qwxqLLmlFS`a$ycW87E;$lr zq<>#J6@glUsQtRK-umNmcyA#7>NXi>EN)_zM-U_B#JdSB3*zDSvU;sGe&EOYft~p{m}kbgWg-SQG40(6pHC#J5P}@p@(v5*qP| zT9j6lEuo(*es3a;jX#!nQi&+%v{upY^r`MiYf_Xf<NCm zerH+A={cr|_iD9$^CgO?$!QQZNhQJt5~7SzXz(5P^Lac1rVlgzy_b-RKrKqvYFf!Y_#TGteGJ4%*!eA zOb{3$Cj7YbZ+`)uxrOeQv23q( z(1c+;kJB4oswM2<(S+SwA8)gC*bu}Qw$bIdLW$5?)U5N2H`T%hYEc?i;a4_ThD7-D1t*_L8(6Q^J}?X#=AcU>_FO->rio0%DL;1cb1GT9k&p zKbtSG#H4M&yS}V0ZD74ZYv+}h>Y2XZqz#OvfN%XKEwFxA@5Y-rMREums6}ab@BDd= zrFzQ>yynS9(gxNmw3=_Yst(ARMP5-cCPYzUV&kkQMik)RubU%Mgbmc9G{lSkF~jmc zV}9P_W=ClQ>lIpFQ>?1{mb}si#s2)Wberl4nBSZ-0af%QUHc*Swa0Cy8T0GldW_PO$k~Xkj zp*6m5l-lJ_`|1OulN4p??D5uUh;$n46zL>vpcbWJE;%^V^6KgzETrZrX#?vOTHzNP zsa)T9j6lAA>tvd=}vyT2W4fHMA7@ zUQq8_%ib!iS7>D)lS!+5sFJjSIZco~u&$wXGGtU;*>BFM5;jna(l9eLW|kgr#_D57 zhDblKUZM3RZA)#eUS8V3+$@;kYBTFR$P9CL$_x`WP>a%vQueyVlB3Hez2uOQ(gxNm zwA%Sj(kj=rk3`HdgZ+KpSgc-<;r3*MJsu7-+=LC(qBOjf32R`fwc?t-z4}0D1M3x9 zRbp0Y4eHp>D69$Y)s{D~)`3jDAp!QY7BlsP4b-AE#NyPdXE_p@#yEPdkFn3W)GpcbX!iSU{@kFLM< zH`d2KlGk&rS7_n-Q_xrw91mq);w#9s*q@SVfh$(3MQORFRt7Z=;Y%KeG9kf;EwYkT z1&zN$DBFJ4XM)HOl>H{bXoW z+}%({>!mFe<&^a`*!azMQrpygn`PpW2);d_7Avr=1uL<$luB)gn#Aw0ItL=^?^swZ zLN;Arc%n)q&P2+39*ADXXT46y4omM)Uru9>SMGP0^>*?pq|yjun0NXuofD?dZ)GB=7L7@U_fdhaMyr2TSOz_4#;Jr7=YmQ| z8$Fxjz$>4 z1A{Dw;nBBMqyJ|g)&oMuP9A}MYT99J{W3Xbs7kb(ov6dyV{R}Fh1kLP#EV^t( zj3Nj8t$XXXGZ9paW{)UJJ5A(hDp5huXJoW%}uhR>x{BupC9dx`Wac4CtGIqe9fqY z67<}J2-D~=V_=>2*1`ka7#-F0tR-g}Wbmvx9AV6T^v1Hy3fUrLW}xQ^tqJbDvX3(& zejjArU3IEXql)P{NNR!%o>`yA7~g75vRr}DLM5c_Hd+(RyNLsg2~Q)flb_zxX{+`pQOYf_(=!bTaNO&1uc}D6c_tyQmhW73B;Z^E+D~SQZDk z8dO4#zm3)e-(zXvVf5R((t3JPHIofWn9uV^Q1^n)y2b55GlNPfLFX881+>TSijsJ9 znD*g2wS6ML{U+Zu1|NH;t{iY1j)yZrwWca>)X2=g%P7SEjrdaQxw_%e zM`;7;)HbNry=DKZ)%z)$XyN}xShwC#R~DbD3IgfWHmFwc#)oSAo7JU_|BYzpnXEP* z>MIGP|9@<(KdS~_JTF^?bZR1)YK=OlMx2}?ZTxS9Uhbee_-8ixhPPb`o!SP~dOA#3 z3k+OhxAA`x809T`6eGJuIkERv75-s{a~>sBE8)f>b=6iw+W6my`NnkBI@i%v7wOckqFOB%_x3!#;;poiiii@dI8u7{_gbwQ zBW2uk;D$Hah$l1UeAT??JFUdmlCXLuV>e0=RI72^EA4CvP0m-Th$z826EJsaFvCe3 zNDIAR^RBc(wf@zfYN0RksiLM-M3i8Kgc40U{jD7xRz-S_w9qr#z;jK|WAtt6vVGm; zxT=18qx$>7@er3m2x)^71K?wRr%u4rPD1}TLFW~u|C^w*57McLeE!SI4yyECdW$jJ zqE&GGZQ}Tw2-&-oz}Ry^AZ;R~=ag76uZsm|AEf`AIJahr1?Li^|C^<%6gkTwyrcTL3c z#kS`QCrbk9|0Xb2NgTn0DfE96c$@`+^e-Yxl!Sz~3dhp_bCmodI(@pM%^Kc9o~hVB zg808Zrv%K-8eR>M7H#=;*2-2<0wGyBD$W|f!-vpf#k^XN2XHMZc(y57pv)8MQ zpU;uwm9B$uuKaHTwSK9UEuqAe|05?( zc~sJJ@nS*#Jh?rm*>aQ+<B+mWj=&P(5y{sL3^y4jSywqu3v`0l5*N=*F{n@sJW|q__u=hK@mDk|%p5`IvnUPUQM|ixVQq6pC6u_{bS&(G;i-)o zHy!-wv9BZ_Hlnd{YAU=JwXRwyB$VecPfLIGe5g@3Ft}pf4DqDr)m1@xuV<#>Hu^I>}aVCBo z|7jc9dn)wR7Z{1xo7~omDmmoX#qla=)S@HCKH4t;kqHPYaVE036w)$O6g#Dhky!X! z0i$ahW+DWQT6DzNi6TJs0D?-Ki7ngRwd!|-jjJ#cmrbZ=EI2dJLAr#wYZ%wv%#{;Blse zIlg`7ZGT=k?L)nh*Krd;wdk>d$V?wEe*RD^jWj4q}n&-_vof>QW zRjP!E5HxCuDCSxpE9whfMa1v@6yh8ZRN_ob53H;kAtK^8?ohny;u2=epHbRG2pYA- z`&x__hOa0cj#rBSu>%MyaV9Vx7RIjde5a3bFXMI@$3C}gDZSgE-YV@~(ZVL{T=gkQ zK5#sa1Cb4gV?a=eGl9|AiZT^Eud;lg@$>RN6Cr5S5-mJkxvU=lvM<=!21I2b-U2}- z&ICr4!<$j?Jpbw-Bm1#L6Cr5S5$&5*eIFFBKvB7rwV#;-*cYAbL=U>e&|j2~P(_?^XfA6$mPE zCLF!%4xZmB9&B{=Zek(?jas6Gxu(18w_`4WjU_y*m>;|1lxNcv9+`i4Zhui54EJUPT}OXEm@<0f@9= zAx4MN*HkKTCLF!n7y4@KwQyt0(Hka0(5NMP1f%027a52#Kr8`*N}LHt@2&vP-93gI zh3~}4{@Go>qV82E#wt9=eiJP`e%oCy=Q|7Dt1SbfG7yb`pb}@o(YyP>^EVGdjXqr$ zng~IomT2L~303rJJ7$Y_sX)93B6qiio>byYIC^&{jFK8HB8^UqmY4`Zqn79q%vP|^ zaMgkMvA~>f;7mArHxWEy@Ic1fl~F>w%yWXTs6D;;Qzr zbEq-!$V?L6FmLo^j=XZxNOH_K5VZQV9P2QnjixA*SLRlOuaDuwz2kK% z5%!R%yOguft`%9iPa=DubjghDP85t9mnfbB90&uqNn41%CZW7 zv;yMK6_Z)P(ncOa<5nQ*MHHlEW||2Jce;H_aMLeQusjtyq0K&0%$cr`3A z)EKk8mptYuaV8w=tLo6IB9z5l$emJ+V$-@$Q$!?RNcel^2E-C*RS*!pQV5jLdPVteF^GTdtpl+Fi0o}! z8}m=(HE3N_OZ@&o&8UC5d=-d}Kx74CWeR~3N{Djps7(6FYe_(~1ESS$7Gr&ta?%DR zP)pcQbA8mRxV;4884w+Sh)*FvfdQ|9_!o#{)!dDP#p+5Mlt3+EW6p>> zTCr_ub%=qXS0wuIw zQFi$!R$EuL1P~8_80LCFU(jcuv_T2f5;nBQKHB@Wu0Y&NAr__(D53R=^6MXcwNUr6 zKs*2gur8`4Y`}S=+Rwq1Gm7E)ff7oHGMrti;~bor{{h?TIBR8H zR7==^^Ix^kC1Pfn3^eFaQ*I_IaV3J2-FfbV7Gm%8w zaUD&4Qk00Q?bT|n`Wv^Km~)q?mhc1pgWX#@9%8K)bTm#iyk}bJ3qMvp&#j+)vCaN$ zAjKzGk^QrYxd!zzdb*uUMWE-x54XV`*e`=!! zH|b%x3^3<;Q7z#I_6Xd6xF2Fc_nI2J^QV`q47~pke)#;INiTKtl=K6Af_HbhHnWuiA*0_oW}`6XXvz*v#5CZ(`Kio+A~3TEY+X z58lxaJgR1zUe#E>se$wZ^Z7)p@NRJvnWcr;hD-gPt1{N$+!^j!FXJp%i@EIP=Nh7~gM&9&d%;hmT8 zqvGH*+UAa#%Q71t1-i>tVLqp5 zJKhyhpJ2~{-)q=K4bQHmWn_v;RpH$Uk%-LTzwG!SkD1F(F*IB`zl(6cV5&dc&1;W ziORdCF^(@ZXUkG8Q4{uvqWBa&$QIsxpbx9iQML;2AcY^9%g1ZsbqY&A&?oqcYq2dX zs%aXd(Udl+2-FgOV2{8q{~b@LXZKk35x0j*KQK>Nv=8vdI>}&* z!{hXpZvAAd@J?9xk>Q`J+O272q#x)L>>{{h3%fpRr#>x5-&6!@2|ut$pm#f-RI?T2 z`kRL1r5~7oE?R|msnjP$X}FcEJ-3e4b5u5GtWz!F2lfcWmsB@cPWM)NY+?IT1H9W7 zeyq)R$9CaEdFcoG1R00vwz7@Wrs_lc1WG?Bfm*^3>=8vNviqcZ^QEEfS#8eM7p=lO zVd@j?Hhqz)Z7&zpn?Dbeo?~`D)e?SSk0?s>t2*oS;oQd(YZM)?r z{Xm}}FV%Z1tGB7Po_*=iR0L`XKhQteoig1iRotJ)9*K~x!hH=={E&Cs)F*htQjDqZ z{k^o2kku&K>qN*W1>$$~4`LI?>a5B5KWy#h1<6+7Qv>10qeZhV3cS~$KEe0ZY+G5K zp?kH>n*Es!CD3!>2lfb@AB|3_F)s}D{Yv}sz+D_tdRN}}Q=i~HPOPd94X>`=2($Y^ z2{?k%bLt*`zQYD3&~xDj`UktWG8>EXxWpotc9X5bXG_A5+&9*!)l27> zexOhAuISZvcDMLW7CzB86@gm95A+XWiaNu5wJghK2lMEj z%-$8WU(YFlTEY+P5!eyP<&+xe>B0wF?CV|Jbx5=wpA=D_AhWoisvf?bkFQ!|-lvFa z2|v(3MQLBd%0~Xo#m`?;r62h8O!#rG#dUS=pJ}8Y=o74vzwBV_jKX^!w|h1@85mc~2**CH%l1f$vSMN@SPk zmFD?c{91*}r)t8F@+DuZU)DXB_aEq!*b!(aYtSekPqWGHIX=^)o(n(FKlsMsI9Qj| z=6r~+{eBR4vl6YsCtlPim_=ildh|klepEN_e?_%~AJ`)hy^}4Gt%NM}!}Z{5wks`p{dVTP!l;(;1A9bKJ`Yb|3#v8b-G=|VOO;OtMXRcP%g)OC zS*0K7lcHSQyNmsmwKg9!vxM{mpG{KFg&*i2yuq4$LS4|mH}{RPKQF=E*F>xE$sP3x zu2F3osxQ)a=ShRi`>Ihb;Rp5z#KWCC!2WvGmREcJ4xbvxCy=6571|YGGiR=lexOgV zrtZ3%waDKXzOR;D`hm|ssprBE^bb~KFORF6Rs`@|zuTW*;f`{mRrm~%`lKie{2Qq% z^XEOMn)jfiTEY+P5%^+yxdUwbU)}kT-DmMBj(o}~S~ZQkux313`hh;dn&ID>Id%FYkxk@fA*`Y>ifvL{Zvw(TOKB^`B zz#dVQJ!AK?$%p##qOq%GtMJ*Y@B`x+s86t4&ze1K<;5QS>K|uP5$L(_!|@EcQJ1}J zNM}Dj;HTb{lKl?WS1(0C1)6KiZ?--}hSb}u;6L{KdneW54|Kab(vhmNuo zTN$sfiSxJb(6aZZbxApYcKLlN#?KYEy|nnr-(f!)8|>(ykKz3mcD5`ly+EfDO3b?A z$7VGu&2D(~1EOn{K%RbMOY6oLH%tW8>aog)?aJiJ-ez47MDC*z{NqF)%LUlWg0#w# z;g&y3I#-IFzj4Y^yjOqOs$7*Z=S&Jp%D?HCOiM)3!D7*x&mRqY_G-&FjbR4J*yk1xEql5nkQ^zO>Oq zP^}_Y`mv3fO0$m1)q(g4yA3tJRnKEVpeujUtA}ir*j?yDOb<47cNsRS#v@PKTKFdG zt;W1_p~aR4>C1B}p~MgWKFs@fS9Z4KVXzT#tQ+5c(U!O@DZ7cFTGS^+nE`$DBP_t8 zLZ6YbtFm5g*`UA*tdDB}m7E1|?>P3|N9Hjsok!L$zMM)ZK}J3h&;BjMtAAOZurOPD z6G63V`*dRmwv=Uadw&N%N@yq5ca5u9YQp#;d+*3NLfpYBQ$L9QP1&;wG8FbsRo@*h z@401IB&QNF;~+8fFV4bBRb++kxe>^9<|a2@^~N)!NvwIox@>u@j$*1F;zdzwsCr~O;qGb%LFL{Kf_ zlLqUOv-LfXRkwN`cxEQ37TtkJ?ra3!z&ZC203aP zIsRIJ)r*biWm(eCw>EfE1f#s@pm~;P*j0sUk&$mR6R%g*=bK75weILz!|0{-X4W6B ztk{4*O zhNVC3aziDQATtJdo^%_&OFlP^HAm%oI-Qs3yi4Xvn6Ea%4s3J0R$9WXCp9XevmLDo zz7OX%o{#=|D>3hco{Y{ibQUEwS>Q`FaQz7MT48wxW0*=v+dXMbumXsv%*O;732iH? zoSvO@_949vXYFg)nQ8Kh1C}~)T&RQ`f0fn*-#4hWjh(Jp)A~AL1gGa3olD5s1*3Kz zwEyzNK*CyEaHpH1z%q6&=p_zDlC0=JJ6127ANWisl$RDg$vr&e~=c5_R zSQfwI9x$m1l!&}tBt#j1w-c8ywPal~O^`NFLbZeq+yf>xff7oHGX8ESLN`oRtBs13 zHc&#fgbmySCN+T)N{BN4ZYRcXn5v--lu#{U19y!{O`wDlqKv=WiK~}d>eyE(p<2QQ z-TeY`2nm4_N{BN4ZnyDe$RB#`lw*z(swHgDJvkuXk`O4Ngec?h5SiH{iDlX5ZFEmN zLl-$?^)nXK`>voKv5Wg?|nn(94+6k^|!#7`JW#)Msg^tEZ0wpQu{I7@$e8aCO zZN4S3v#Y&~4r8~cB2Y`%IC3t#9{+G6*f^K=Ci5*A$ivTBYMHMeF$MVqBq?DB~MtxEfqeW@&?p8U4fDQxT{o>=n?CYMB#7tn>3)*O|Vp82{(! zFG9suftD(?gbl|tvOPPlv4Y;k`SZP%(1s+amMA-(Mty+Metw!eubJVO=f4Ql60K^O z>7`m`!7*sn@{>vI`OpB~ru!vTNao}$!qOi*?kUPR+Rdws(!TeY?}PsQUeAptf@;xw zD)^4##2f6@jsbjXSdxjLTIPG4zQwLHW%&T!uaP42Qn6K3i{2qYG;WI|Ry5}TUcOg; z6G64;ItcFQt=HMWo&ESF$O@sJQ!Vj3%t{PqB^743NjF)Ut^IhtLp3FV5=xj?OD}IH zvjWrm@r7el6G64a5lngJ05)!qNn$1c@#7`3bTJWBOO$bi199P1uCY>S{CLYZ0rFWf zKEDuc$MZuF_D* zr6g7}F@O)qctW0cIDgO;xp^+}8hxET*y_vMT4ARG(sog<8kdjFoW|t&;qar5_jR`7 zLl1tf*cwTomLOgQ#WAfX8h{i z*U|>oE3~F|RM?T?_NXw&Q%?7x*I19!tP} zL!tk5c0W&6KD?5LY!%LfLW{TAqQ*a0q<{EkLs1$*t8#i}=U>w`kTy^vY~ai(Xsijc z$>&{X8=JjgwT?EIHn3iywYvH|wdKLg(gwZ-g0C*X5zLtB9aC2}lQvKyY@j{bLU zi!Hc})hp3U+Q52+*4u2g)mr`R@9yyJBIFNdy2iS8TgzH@>?v)aMA$%kw1uz_OV(tj zmh@vSw)d4buwJ3HJk1+VTYh`I559?o_k$0wvU8coux@qwN*gE3`dC$rtp zGqDW?2S^)Ouh8Y@U1nx1vqk*%`a1&t;#k)+CYi0f%a$%;dr!8W(&{O zf%me3(gxNmw1($RS0*%<{e3OI;fI*JKfsUJ8S3T}fzk#_gblPuTL^E%1CrU;6Lqwj zP3$(X-V`kx`hn395d9f*m94q8%66yUKxqRd!Uo!-EreLkh-6m#ekQ#|I(uJ%AF^Jd z1^s5jz;Uwz3O`!UCQg%%ut4aXHm z*}&ST&sBEgMN@rC9e-&9CBg>Uqb-CtSnHG7!H-LI_qRQ9T*-Qc7K~#J&ku}9f-6qz zt89AYY~3T&TiQU0uz~hy3l-(vzGU|C`7u3^+0Q|&S7^ccsNs2z(OYnD;Bl4tc<$Ge zcXyLEP$F!gJ=#JTS4WcB)vwR>->2H=60BEf!Mvj3e1(y2u*#@%m4&vsqhJ5nM%qA$ zuz~hy3n8ZHTr%^zlf`KHsDbP&tXF8ktR`2Jg2t#oh%j}%%Id98Yvk(FP})F=&_a8( zg^E(O*j4s6IKQENttkmyvC?{}J@}q*jbwK7Z9SvQuI#c^xQ-TDX99m{<9hCt*FlVd zg>P+DyULnhtYsKO@<|&g5jJp5EoiJsQ8quh&YJITVr2REqr47cy+SL)w2b=A`b(q@ zj2DLQ74^T$LUJ}T-cCv*ZJa2GuBI;;P#ol$A(U(yEFE41()P|z4#4SA4z zud*7EZH-JN8xkbddzT`=xiq zu(p$Xr$GF!mdre&`WdrUGfALC)Qf~D4=GYa&$0O^+}&*-a+Upv8DN~vmoF88TC#=i z_B~l(UD6?mWp38Pcwc-26LsM(FhYy&^|Cs5K7IS5rm%YbmgPD-bf&v8Wa&mppo9{l zjJs{X+wgVdx<;pVmp`!Z1o5gHG3-jnj z8TXcfNGBtit;-x>#8f+%ia;%MUoBsGl{N7jXv|8OCGUh9d@iaFE56Pm>cxExs6E(E zW_2=q6dY*8t?X$Nbx{IaC4R@&LZ&xdIg`@{8e5c;@~+75P!Ts`CXRUJk8fQvPNOc6!h9J;3d|&O3&bkK&@r{3<^Q>~ZEz376 zJ?qmnj)|6h9h;U#H;j`{SWDH<$eNZD`@>bPwvRn6HJmSd{zC2nff7oH@}_y|*tB$l z_*Q)%tC%>9R~j@yKKZ2tYKiB*%VuU~)z9|?;(675ECz@cL3RQqv|dr(_c#OdoG*wG zU?Y3BVSLaGL)xGOY6%-}3T9{7=GFzGG5FC0h;=b`0wuIwQ63PSg}rGgh!C)$<_qGt z<|?vJD1lnSMvm*b+5C`vK%4>_y@62Y*$I@;dPRASM@}|8k05q|jUtza@HO>HOB<9x zEny?%&w?yN$$M~~p932li1PLA1WIVVqWry1eslNjd1B$T*3zq<~|9-rBq-G@F_U?!L2Ix(n%hL{LJqn2oGx!96$-CqWMmE)i{I|@WzAgIKdaJD0)@O`ai-(ckm-K z5bJ@U5@*8Uxek7W^cu@s40e-#;29-ag(F|kg+}IOh4+hdP_^m*qbzY)k;phXBzP2r6+V9G=&J-u-LCINrHKM(GF6KB86V zlb|2($iapm67!V}{744E69_7CCLEq8K&vvQ4d;jJWHAwfMlI3WsW4w{zbI_v1kVL= z1_&x~CLEq`gH|PM4&ku{Pnu?G(JJ&w(BI2vWr456++Gtr-wA{P1eG`w4$mt-h*v|h zM(~#d&zcB9qn2oG;hkC8!>_`|X7D@=h}A$)i8JBw{3ZBd^b6&^J54fO)kLfC>LX~J zl@w(s5J!P%0tA&f6AsT0L+_3~7QsC$z?(8smnfr_Xf4jJ@Z1MH9|uHdAgIKdaCq+b zX$E`Ne=JY_H?2x%OS&2mEySy~qTIB4v$j`4`S$wBrWF8fA*~5=`@)kTm&}hZ$=+Me zyExatUY&&vq#^PQZ1@2YnnF;m z7F871bUKL+HOH@X~Rt9 zguRd=tqIZw62b>+J9h|NH}4GZK&&W)BfkPtR- z)hBEq4bPT<_zc9vvvz`N)i<80HM@jK8xBJBZmYY2eCD>ta;=Vpuz{;rVFPK1JqMyC z5O-4us+BhCiCUsUoV4K}*33y_dp`y8A?qxbMYBh+G;N=#Eeb7UyP@8@;ZM}+7fD`S{V+&j?B;tcU!J^A~OGRjs1Uoodt9h$@9l2A;C4cyZhl}yBn8a!9s8+ zSnvqMuwYSwyTjowNp?5L;c&RS1cJNUzj`+F%eVL7&%1kXUaCG@T~jqJH9a#|G7J=} z?`jq#au*w;6U#^Ln?WV z=bAZkbC!#Ac7Fz6;(H1Y6qT=xx1d(Sxh}dNMZTQ2Bkm_qh5opg*qf`pLTv5rp%XJM z#&e`KP54~puP%9s8gA(=*mm>@X?j9>>194D-$0=iYN*&iS|uK3xy)BmJhHu>sCb@c zd!X+5kEkokS)eD2Z(8}c8Q!A9wFB`OL5y?vCoOrvC@0>cugt`MZdiHVFmF*a)6sa8 zAh9B;B@ZMbODjoC{xY54pW-V5GDj%{YK@rIls|gs%(o1ageMV+M7;eN6^{}mc1*Pq z&pJt>9nIS(%nB4;idRwy)QWR%z<=FL%{|9SVsTKR@QQi)o5r}I_IpRz`?G7F?> zUwGF`d@m6Wc0@bRsXX$?bJpNqMu9XvSxm%IB5K+Z^F1c={)gVOdS}uIq-h552jb}P z06zW8Cst*Zqd=N!WJD|>8#U}~NQ82?lcfFkBB^WM3oo)_()d=p1)`!N17@u$$pHtBe3s6nx1LsV&*=xy+z-+VU}I2 z3m;U{iC@@tog>k5PbZ$bmlJOtE_=9Jea*a0jJH_&ahL@qNT_{cTzov=JjYwKm=dZG zsI~rOd%hx-Ge7G0FWHz;e;4;+!^J-i9W5w9LhTcC`^2!i?LtIU(eCD}=9YZ;^3*){ z_kTI-+gQJf8caIFyS{J9)1OGqdq-a)8>y;xW?NTN)*P3K zSlYZ7yR#@nO3fYS z-y|aQm#I9*3SUw7S574!c%~n|?!f1)bLOi$NE;RVPvgsCe8sxjIV~tbqRN1F{Np`m z-YApwJl})jyuqeGkvgBZ841+F*3x^`CYR*Vivq>=;a+BxAc1Fu-WFQ73r~77R{Wc% zm<6>kniwal$@DJC-4_Q6x8|eGNT8N#Bl5^JJ~h%;^f}?ALn24`uI z60_5`wE0m}65U_WJLsN{6&06fj7I{sa73kS-`bNsToNK`Pj_?0F$!rM?Wh+$J&*ad z2oaNu)rv==`wgaFwd42(jx^0Oj?dMJr++;)lOO*3X0b`sGwi*X zOCd0?kfx_h5AEXPO~b|AnYAt0%V0b({&auv@9o^}+Hi5=Tt$VzITg~H=68JuZ%4$7 z*R1?4&95rVf2Pc@aOQ+G?Sb49!yGz=i17Mzpqu zEdOK!wMJk5#N_PNHW&R9fm$8Q|I&#@wKmXI`zHdm%B^?O&tb)9@;aY#V-_nJ93)=E zy=R-djOFDDe_;DgXAvWFhVtF#pEBQhoi_}B%0@rRMZ|E|uDtTav7*eBiVA^R_uo$9r^>!%y>DeAB1pvYyCa5)>E()9 zaF&Ym&xFKqe!c2rcI|RbBKi*7$@9${E~4CBEGR)jwGm?R=94e@i~28fF(gn6Tc~Mn zEzG<#&B*E;9igo5a0aN(6HjYqK6;I}I6QK=1tmy0U+Bpjc&6gd?t18>Q#Y}Spg+MKJ{c)?aVBEuk-;o? zhhR}6^$CSQt$8=caI4ohw&YAYA`XrYVjDe!MT4{S_BxOt(bH!LcRKQeg$e0-(RA&Z zL+)U4y#0NJK&{&jBl-9KU)is|8HlLVK8O{}5+XtljbdzLSH5kK6K`mJ%g<%^B4Ro*q8Ec3%)(R;;Wg+MJl zZ}e`e(W6*#j}Q?bRhr$))sef!)BR=d$2_90JCC{H%wKvv;n-SDo3(o^OG|T~oOy~X zeju^vM|wV{9twe4=o7s)BDNn3pB^Gc{oJjrad2IOt)-_L zvxc+&Jwm9$GQorrB*f{KJjdwNeE7Ee)T)ARZP}L@A>!z`9}0n5=o78g@|WUOXvLCl z%F1|L?m9pB#jKR@|-mw)kl|PC1 z6=$MFc;`~&NtKe)eXL)x#O*PBv1=SA9~~B zo~b>bIg~04X zn)X1x*u@KU8!iTS_-Mva7=2P(RrFam?znTTcsjE#LkaqU_UI|u9BHdRY#JomUeCdQ zcvjPA$gwm-#@TYoRuy@+6W`dhqUq@xyt=SoT>1(@!tGdYjuIqP&+iYMUbk$PV6kEQ zH--diT{M;Ej{7v;dZe5){4>30{K1Vu!sBo{juIqrq^4)Ev=y;?3I~gUL7x~BsD-lu z+Kc1lRG00bZ>D*ol-c}D08*{Hv2-Mn{Ek9p+$%&`W@|Ie)a(7}}vHT&z_wxpZ z5+u~oxqY6Mb^LmUh-M9<6auwyY^V48EKQ3286F}|hmBGQ)Cyafi%-4g%$)cxrhvm;O|G}85d z>u6i6q>avY1Zv?rn)b;obrx>hGqJ0cx`>6=a9*!OWz)&V!Q$!LFupvtiYaMQuxPz6 zoR3LYyGogU!PKfX2b@L2teM%}JY5v6EHA>iQ*eVS0W0kZ_Z&Waz{%2VgNMIDq;U%4 zkBeM#t-Co`AWhY%nXdd!wKJxBbLdSWptZp#z3v>>S z=B3$Ku~W=#I!BMO3;Rs&$<9Acm8TLf2sXn4X)ne?)q$q_r*(ZVrHrixb9}y&w zrn?y#$A~rI_1W5;^EqlY*dD>>S3haW@FdWVxPR0~tQhai5?Q1|Y+4b)7d@PB`m0)y zK$_k=_-u^0-Q=Xn$8WYm{Av@yJ3X&p8uU0wAWgl`i!tKy>l3E+17~y8nlLwl-)z^? zC+B7IiAx=g`aKDA8T=}#hfizuFV|>IikHxMT2G8V?5fOaQhq6@? zV`!%)5PO?P@ScQG7=8%dEw0>QS|?WpWEPwUXFS@)k#};)SBPyUz`F z-D$WTktKlf>6f~QGIc&HgzLOWKDk~ZbNo0|AWe7TMh5XgYduBW)HfWp!rMf0w|;k+ zsq-*9qM-Kxe%!5*IQ2NMNbC^FU;a4E^4%IG-tCFx_ubC189zpdeUl?-m3e}BG#N#H zyc)~+!SH6{`@`IdR*@qSJgv)lR>yIq9T7XV0T240(sUO&aSYEjsinBz zJd@Ji6X_y(m7iDHvmL{QO7u8gfmbTmNwhzcN+Hm5r0M%=-Nx`D-)e{!JCh>D{cjrQM4v}j^L-3#Ije*?TPr#CVtGX zirC+~nnEn5@A4iB+|K@`D-LOzEw$^<+h(sIF0ZdHP|Iy)1aIfMiA6W@wIeDWD9e|0 zFC$(QG%3VC^TYYGnt!vIG_oR1Z*ToMns?ijUu?WlU!c~re&KxDw54qPRX;moc4NW& zc@`1Z66y=oiftFcPb4j2TTa>&Wk$R5KAUog{MlM4MAhoye3IX6_UX94K$_}_-TU#~ z&9aJ`OIirjGNq5;mtrGX@k(Ruh$wo)+Kp}*MB|z56k>PkaGoap4Ay<)Sb;Rvcaui* zznXpL_v?EI)S7iOjDHCaW+em1*%9j>Fg|dvqX>TKAr!6S;oLGMh1ZusS63&k`@?aIW*%LdzmFD%6 zF7n~O`YFV($S@wAxebf>9w3mWZ^fVQMfW!1_^YE{0=1eA3*$wH)npr&2HFwf&HD1h zb+Nq89@?D=TA$m5^UeJ#vgcIKRBa^ODaC6#t>Jt24O0kf+b~|ObwQSoR{KcP`>#5N z^WbXqN`?5L0=34}3FCZ!D(17=o>=(Vm2a3ii>IA8LZH^+65-sTMk-b^+Mbx|T9&de50CbC=eM0l3)I@^9L}p`-e#&+#-4a!F2#Ff zthC(ooIZlkO-vFAZNCeNE%VRV>Xc~ps1pSy_(wlw49Yzbl;a>OdORCvsl|-=MZ9T13x#Oho@Ps3Ixw?; zfZa9N?Sr!jExnlM*wsRy7GB$EkKS8rPAz7aGV|ybjTGYcoCsdKVE_xQHO{VQcwRoW zcoS>pEy5ZJ)WUuc?NKE)V;WI{-g@$LfJr4_G(cL@UZ-j!YPNjKUq9cW%*b#ShAU)x zN+_g_=>6n1?;W{=qZY1;Ric%9YjNlJeg3h~afO)CFp3A~KE|#W8l|qhwPHtGi&vBH z@eHevan!<9G1{Ydv2JQ5y11R=m)74>2)qW7rkzgtS_@O9v;5!uw>WCys#qmVxm$^D znw9VKdaV$6%_B{B+=E()5g9Bz^Ql)HwQ!BA5`AX16pM4M=X>UBN?)@0WdyGh6~p|) z`~}i<7n$C%J;Cj7{-LQRPzzVZDsif4OOeAG!z13MQ3%X2q&02o$d=+r;TZ0=HjR>3 zxGGkOMrT@xLdC}N2bVJ`1YRph)2`wSEk%ze{^WTk<@&%?u}W;8+Cn@}*P7mkD!90Y3QO{=eWjIi8<~qM7sq=dEPp?6axD$r0HIfe+!YeY*Ah$eJ-WH z!WFAZ)F{(JB-`vEkysVVQkE~e9HKNt2>nlO5H*XdLCygb1}a{U=0yzs(xf>A&%^hGwnN_ zU#T?Ws!=7fRxi)9o~?*FJVul5=j{~ zas6>xQNpv5GNZ?SMV&Kb9g;(MUwF&6FDk3_CAfmX9)rFHb@~_gI`)~@n_EkHi@NT547L++4SD^zi^Y0wupAZcp?0e+Yw?TJNtk&~1DO@UkON@;hSN z`;Pw)VbD@bzPDKBTTXg|o|=g$`5h5`(B1|T#9X&~R7dxX+>C@v^s*e^0DdRe$fdq-;GkO8!95n~iM${!0LDmc5;{ zQMOx@oeh-yfv~fI1RR@XZzpYdT~DyHfs#KEb~ccJW3%k-q>Ta}AKTeL$sY(i8%V&h zS@w3)Mx#%T@(mmMKik~a)@BKi@9|$`eNWig0_IAII2TJ}x*x5h=jxDmclQ#aFS19=dVV74( zz_D5OcGAXwuMd>`fv~fI1RR@XZzpa1_c}+(9|$`eNWigK_IA?7fBP$x{DH8ufdm|z zW$!9&Q2$8Zg0TIwU4tn39YMV-yOHmX_a!T}49V|^M^U9!Lbrj0JeFFL{(k+w>9w_lO6WEWiD3_k+nLI!gl+=~c`UUg zoiKWV$>(EnmC$V%5~C$ZbiVvM8%W4wsU_)NC-RvN2ma26Au(ElL^}7fYO8cVkdVhx zOVW+jtz7lF{qJlT5~C$4M6u$R{eNcziAL*eTFJEekACP9TT4{pkAD1*AV17TtLVI$ z{}>NlVzdN_KgQ#Kg#2CO>{9&Af6OagB5l|cf6S}@5%PD9ETKF$|MB|JCDMjH@yF}q ze}w#9BirfPw8(2yUU}*@Xh@_DdqQ5pv}b!ni10sM#I*NSDC>T67VrKjl;w)=CJNr3 z#jEaE&N5Z(CPeXBJja^l?3z`sYfZyL#LR5MRN{3gL#>W)W4I@MD{^=1K6XUWXnGD{ zsROH?t+_&^c{_`bkKV!Fzv(QHrl+uHg@_D+Nv1JVTQSrcoNX5GR_+d~657*_I72%P z3oUKLE_eKDLPEBX5Bi6d-_uDTO?98h5K$m^TXt#TD-&wTmW23zVD532u5bu5M3f^E6>2*tRvT z#CgX#{NRgb>_8=VF{9NSo-jWnn-|cWS~cihh#1tghbjLqFB59T(l>((b+~N0vayvN z!4pHoy@i@-VAgvIG5^VIo<6<^8@9cjK$>>^4ha#1^JioE`wwQAKN#mGrDFKw`7fDA zM_B`SHabL9*muR`^mPnFtx`TQ{8ICGtigo7LM387L&S}lzHC*qf(n6If;2s8@grDV zD8JrPcd4`9DkB>{Y>VO5PJdwM;(G~|SU|f==S(T!I;gLsLfm^C!{f?+Wae(&1=932 zox8!p>-#Rto6}!RsP*}540rDSk+o0kVMnyR5+cg?^Dy=P>dY`67-u}w^!=z)AtGZ^ zJyVEReui3SM$hKOn|iQlx}sEK5M^SeJ>yLyC>xQ$UIJ-)H&v}b@glO4HCL)>Cal9@ z407zB$q&wX%w|=j`W(GwGelIpIMZ~e(=w%Uhw(>R(?ZLJh|1;qo1SG}r4VD9#qgva z@od|H0d{@KU)O@g_l;#V1M9e*yp?a&hV+k)6+ zN;yV9o;^eqo0hfuom5*C0=3kbOCoQ@3Du?(ff6L@(dhhZ^>WK4eRS?XPXcbLwy9dG zrn3|RwbXOfo`@RVXYL%;WR@}mK%xiD49Y(WwPd210X>~bBPYKwY{&5QBNYO*Fi!N{ zK_bSlXtJw&x{*o*kvL2JN@x=g%S7r|=-mnN)L%Jn-g$C@t3sfb+WWL5B2}BdyGjv( z5+oMTSmGI1#L}I{68bXG%@9$qORb%m-Z?7-YGEGRh=F7GR0}2oB}l~42$!S%W%CId z;pqL;??Qz0o;lSA?q6;~0=3j^mqh++<7+fLwA_ReB&yRDwZ+53{6fE?7W@nmFYZLw zc-r-{D-x)MSDL0p(*2J?g}%o3J#&P~J?7tX+_cC&=Dq1&NZf)%OC!1$f_bcI4hw=s z__YbUE!i$B*9Y!US9g*-6LF`GY43upDuG(+zVMIpgGFe8g0-^cR0-5lcX|IJBA3UM z-6dUA0=3jV+fLM~f#0lqmfE!nwbUKhsfp_u+A7pi zcSrvqqHvnOtN*m~1GUuM(UPb?xlWDhbcYK2E7Vf=I)5O-a&d9ZT6Sj_wbZ@NGJ;3f z58X4@&U4gKcP^(RVt%Gwdv;|}TZLNcKIG5Ts<|zT*X)`@B~VM8z$VcPLa#K0-*YMAW^)WZGA^af=j`s^*XYrkCtQEStz2tM>j z8S_b>AnF<96&15$*Y0h0R}^Y}T@%5#b^Y7CtB@qVlZ`=(tJYX&*DBOnbu@w(DCuCC z6C6l{Y?bHKi#spcwFvyuO^&gk) zN2{Q8yU*JBfm)W}NZw~vh$TGt*ks~<{R+F+*b%7J@=_$feJ{pxFu;$9Z`7(znfFwm zZRa^^y($vL=iFXyd7IrgnONauslLXJK&{*{QT*zFyA4lVslMDUcTvl0b~KNue%5lXg4{_iV=iYIeeGj~5b8u1E8pWuLQNg{6(z z$J2|}{|M3VSybA~+WMEvJ^qV1=H%C37P4yKRh!)m@{=POGaz34q~B`fz6 zrL&(`2-L#e_?q^v8{@aE{lvs^=ahZ=NW|ri;=LVSu}->;eLeg|wXe;&bE&Kxy~VTp zp4K?UJYTUF3Gxo_;p?Nt^flwT*Zs;IB}k~NqV@4(MHfpQK5xxWh6HM0j7{gT1I#HGlbu-kxK4KQk1N};^XtygBO`*eL0!yov)W8Wuq5-O2<1!YN@QG8yl=Vp{3vE*V5@BRKG zTeP<``4OGqE3P(}#y7WbtPrS$t)*vQJsR?bF++s6!&Z(tin;6CHi}O+y<_n^29k{j zKZo!)9R~|1=k**VNEGZH%@+o~XCEKR-2IxdB42uPggA3xu0o(zqtGaR>fT58S7k{o zycWpEz8fxfT@2tTLE_1-D89@2D{DSq?iPui(2%=Krmq#Oo5WFq#Q62md{);l>|&TC zYMc}Nwzsc{=+;ajQ0vs~C|-2JcQ*Ei+*$K#-w^)q<}u>h5Lb>8Br+vN^VdhevySB? zk)?lm9=dj{NY^@tLZDWcR5Tj2`^lE{>O(}UCm}rhdV0p=uYVXykjPRznwJ^(i!D7Q zufg`&1Yh)HtSCR=CPN7lEayx<$oi8lJ0giYGwbuDq5&e#rMg0()-4{*=Y9Rf78jNG z=re5`%<&>^?t&o{0j?8kQnYWllT7i zjae7SYp_-7^88_gvEtjsLRKVDt8hd#Z@Tas8+TUjjk+*^@gWa|NVV0%=W~xW%9MFFsndtl(xv2@%5uRJah@iD;38< zyjCY?Y@+w1c|{_XY!hZ-?GkEBLjsUR3y} z8b=8d6?V_$8FqYSM@q`8c18X4qWbQR;zs@(3<=c2%%`3~q!R<$d5G<`ZZVV~kt=Z~ zAF$y&bJedw_s8kPkWrn)`7cEj0<|!Y>CHy((u&a;JjKseB^XMOsGl*0r>^#c9qcTx z!Qtc5iO@@(MC^b>GZLtUc}(xWT9j4{@8>C=^}lOI2@-Y7$M9WEzO(zEPg__mC_y4qqZoei+ZX1(R$ftcW~UX^{_P;no+_+l zJ8I!|L;I<3r4a|3bQBdQ6;`e&BvyOI@V>)8GMB-!wzM(OU3AQmM&xq$B7*krc3$6vqXdb7 zbhKl>+XZaB7@QY;erZQGx`{2I+auitb`s z(d?q)*?5KoYGGDVjjUZ8alTOw(eavKhpcc&$bZ-3g#3~my}Zo)WWQ!=U6_q z7E2rD5(k=AW+*`dXM^-Dh;D5}$pX1VoQGyc0<|zJ>D?j`t;M$5xyAVhkK$2+ggU>v zeyg>3Tr`*HyP>ZI3Dm-@qzD#hEzVcWEw&x*Z9xeVIG@wBhuvC>A`Nqj=Jn4g1Zt_- zzIuHtamY27SaAPe3rdi{Sth+Dt+JmO6*`pf&i6rCP2dUwGlrg<*fLhQ^q_aMO*_C) zf&{J;=zH7K{lvljqxsgF@d|-jm@)Lk`lkbyMt&S$ zT~Q%W3tLD}H4@=MM87o^6HtQ0&>a=@n4i2RZCrI;Vp*8vD;5lzU_}D80c(B5y-OplNT8P76(~Ko z?ebpotU!X5{D`a}60q&3y$k7{Zync3pgns2oQQkRCUGkfC_&=OlR~=ZaSP-OAffIf zYXJH2vQb8bKrL(`egA`qR&;%2AOa;w)MQ0;&u6@pHje+SY|TMy&dj4dtVp1i+^Z-( zx9vS2M(s}`Ki-l**!Dvm^Xi_zNYh!MJ^F$q5hEx|788LIBo05$t9#zAh@4+Fp!U}y zKeCZONT3$Bkj5w?{-tyEkO-6@vDr7j?)m#Z(ncpgPwRE&D+aBtst~9pcTh^tZ9C%2 zm+F#mn_~X4+7m0b{YZFD-Sd*Cy9l&LU%Me<&(lf#e)T6-lpv9+axUHTH@D>KZawAf z1MpJ4TyL}L_;D_f<(QixpmL4WRNrDQ~Ug_e)5eyZ=4hYwdB4|>A7v6 z{z~en%2CXBQNM+4&t5yb?s?L_ZUXIT+GZjalIJgpKnW799%k1)_dg&jUW2G-dry9h z+0jlRPzzf~y(kfKG-yLT9ZHb68kbY|{LWQr9xaVJ^Do?f3N%Xpg=EPQ)WRSJCeeSWtpQwL&(}B~5RQpwX;4`SGS{ zq(Yz;wvgV#LZjI+I#-D_x}gM#_djyzp4)5;^oX!Fdrxl#iob0}0=0~19c<4uw3VKd zAMHOLVAyu!ELisT5@?V18W3@p&Q-<_2N+6_FwRKDt+MV@p8PmTeuOuRR0!0<7HV1? zovWI3uC6tYWGF$x@bAbxX`=^u?na((j=ya}0<{d!ZO?xsQ0^`!KLQp-acsMh`4d+4 z`CrU!evBvLE1jzgL|{vhFs_1KF|w+bnR2%s`Qf~yokE}%wvfI`Ld0G=R|~hd<0wJG z$muivq>WpY?f+7?@0hrnA%R*(w%eYrDNFrTM(W}Gsz2e_cB8l3H?ZITu5+6o4TuOM z&wCPqEkVNQ`8v4EC-od@9H;r4=$L(@LZBA5ke&^v9QRLqsv5VE$6zb z3V~Y2sAhXI>;kWDpV95+sZnj(=`hhbu;- za!c}~aHEV0fm+x?dVeAj8Hiv+pacnHzGB@e_br{InM^L4$z&Vt!I3~MV0XNEox)_0Dn~HHt=M7xH6Bnj#8; zTG&FWg%fdwu8&znpacnHj(UBrJi9-WXRr4!jpRt6mN9#^J!N{0RxCNmk0ZN=3T(Tv zdXXzuv_~~E8ppTN>h3-fC_%zl$=KGl2WV72M}90?T~Q%W3tOmZdA7B)cBgYyh6t1( zVXRAR>snZ`a3oO6Sh3iieKnuGZZ=U(Kfd5ZZmi7GRu{NeqvxwA7wRR#6YefRKh&$r{%zBKe5NNn=%VG@>R~fk=C@tkTTZ5 z;{IZ8F;`{wYFyiL#)>rcyZPO$7aIDD6PI0-S)b7l%9$S0nl|QTAM5BY{$jGr31zlq zj2Uu&dXoydDu#sml)%#oLL}EUqy8Dvo;#)Pg$&KI651I9FdJ<+q?v9 zD5IM3yK*Em2-|r6{zV__IPxRA%L#^~fzft30w7I0ALv}2rE|6QvWwD-8s|s$oJdno zJ-&=}1jS=maaX1HF=8Nl9Hc3)Qev)LwMLxfm5MaI(N!D;kF9P!>v4cEcNOd@)B~pTf;h(LC^GoqVAyCWk!&X)6Pecdu zd?}qTlptaFXY1jp8fAE{_g6;k4YdrZy@HEo>p}HQ3gU%k}v-B2a=v^IUFv%x$CE zE$1a{5mlqY22J2dpq6~9RmR-bx9^}iXm0X@)98$Ce_67f?zx=Fpgm1{L&R9RK0cM~ zqDYYF`A=KhDpjA!%%wT#HS%LMjn4R6sD&-0r&5T>LFcLu5hy|8Qmnh~xosxn(8z)N zQ8g;l<&hi-)RNB(OV4fN`5T&pHX}cJ(u@q-p47!t_gv0i(H`x;B0|nyM-zb(B+R!v z>7LtWebZ&Eam0@}PGz zrkoShl22qy&uw!!sz!rpbCSnzN?(n>TB0=Ky-EO+)wwZn% zYQK!&eDVi>3$?I?npTyFl0^6uff6Lrwd<;TZdOpE&05=^xQUY zuT5DVL4Hi59LBc4a_y~qE?22&kM3F$F_?(iM4$wToeO&Dp4(P;Gbm@XlOK+h!$_bO zwoua!5n-n5V;K=BLBi*D58ZRyDs{m=e?E@ZYFBBkh6HNKw+TqkZELk<)K9f0Kh{vc zg>7FI-B+o?5X@XtA7uv-h;-bIpoIxs<2?&3wG(J zdoF7|XpeTi5K)DQ??j*kiAfv!>Ym#wMY5LYOn&5~u?h*)!WL@U7a~5>|1F3>2@(fR z*gUt{sP7TMTT@M@ecWw&wmIdTpqB9lBHJ9!oBXIseq{S_z=CZz&VsB!qCNV;5fO8V zh$aFhNErUvDv)2v2l@Y{W|0bkTG&EOdr8{zTzw(}B}f?l*(#7N$n%!u`SaM@W+YI{ z@Z2`votvDyPiX~)Z8tJsR-Mrv)yRklrux-BB2a>ak<+%Sb3Mx4668lBt=W)3Eo>px zWQZtA!~-Hwf`pONwyJZEIaB#RlOA69c^2KNx`qU5VGC(J z==zBJ(z)7B1WJ%F<}0>4ip!H{GPg!~Sdl<2VqXlFLM(1PNn~YP*Z2DiVPbB#b$#?JhFR zUad%=mN9#^-AmoIFp3`~KZZ~h9oufKUgU}u?a}vGXdItQ=V}rWC_%zlm)O>|^JpB; zMSirTyWvQn7Pe5+3eY$%>(q%}J8V%aED)MN!j9sQ`)a0B#%4))hfm}hT#Li(q*&(V% zg?n~WX5mJ@%9%IPw4XYp3?EI^j|NozFtT0F=#6Vz&RCJAogDeyxU8`3r3#DDGsu~+ z(GSX*9@3h|UiRU>RK;meRUD%il`}|V%#brAq-j3`?Nq-=)u?O_TPgDrV||3i9z&=)Xv9PI$VLogkApOQ%_Ak|%2jK`Szf6~ z(|yjAyi&5=$R(NKNYfW2wR!YKf*^6we4F7neeqjM&8vm;z|)V|?7aD?Cb(r-EGw2L zSX4Z}mZ4VNY%_S8!;jdzj`@X3JUaW?H0dUNNx6r{k!V?KI&a_S5qoz_ispTDx8t7O9r=O=^SGw9eqrT4)4aunp}k#E zYeiB^9yrR0XK6Lhju`TNIv+g6SInC+MW^st{ zD{#pbweXwXD&b0X(UCOE=#^X-&AFv1FSNag{w_6noZ(7wi|pq|GB;jbD@1P>%S*&` zB4`DsS2+!dti2h8JeGf7k*6pT&1p6Ch{g}9nf!+^v}CVctzb)@X>BedN)eH~`qJy7 zh6I0C9?QQkT#%QDz6Z{l2GB0Oh5nQEx+oHcmLzQN3d=%7?PNdX>PSkG+s@?3nS2%) z*khWOpNLW9dGBN*x$O!8=Zc7iN z_++*ZrqvM=sD&-0QH_WrM9d}vB}m9oTl!bB&NZ@e;zwm(f$E~|lk1|!IYBKsI!n)O z?>3x4?cYp(Tql39?Q%6KJzt!0j|uJ3JGO}EL4>RfqXY@LPL!S()pk;=!l?aL^5Yiy zg9K_}3#lSZ#6u#Yi9iVwa)u-QJHK%Q*%(ACNV!X|a&leNI47tjXEM@r+Zz`vP|kKH zKV;Tp+hqkodcN}HI1}2_w2DO3B;pPcC_zHj2Bhah=lfEt)=|z%Kl&usMU8WUTG&GR zW*8C0==yl)VylZ99wH%UgYxf>3k@L~2dQc>mZ}CTlIx-dfm(9bCq1{l2XZ;}Q^pacn750d^>_WnliXq0syS=l~9t0N>(3tLD# z2Z)gS`aG$pLkSYH9whxM5ci5~{Gz((5vml$Cf7xcbAnoOhAcg|y`8c%jZLxSM~39O zsNt=w6w2cgj}{d}dnt9%tI2gy!$Txw)lmN3(q~~Y*{bT|1O1Lv|qQ*HvExDSIp3CEZ?a@_BL`5QIC)Y)jW3CX8(`MSaOu74!qWC?z zE@}{{g)O9KOo)(o0SeJBR+JzCR{`08Y}Z$i$uW;dEy#8vswDSUmy_$F(sSz7%+TAJ z(H_13iU?2g{6=zJRQf?ZnLb?#v@rQmCb=$Z5U7PM)U-WB+^2I@DY-5x{h*%A zj0E(FWCMCQy)J4Hs0BS75wql|On%TPt=C1R=QNU;VT4oc(K9AQY$qZyxh^XGpwUYq zVC*6r-pOOsrsTS)L7*14kiOfOJPyiADoT)m(T;4usHPC81)~}fH)&K}L4JfM*F~l0 zGpZkBkU;4`fVoT~tPp zW-JN;GaT~cD9vQb(M-mDl&vmm5U2$+86u9+s637QC`CI>vF$Jmw_potM+y;~h%!W= z1PPdgrzsMsg)OA7C@0T%BZxo=5-_VJ8!&s-D=gA;n%A093udoGETK`k zG5N6~xh^VWPOB6PtX?c=k7gM}L=&+%xh^UrNGlVCfOQGkxJ~1@Tz_~`l@ospwXlWs z7Qy5-&iLfIsPuzYCdzslRx)G*RxEm@$RJP)RxCt3KXcv0s4lu8xh`s(<7C12saud% z2z@=6Ofb-5V1v<@Xc{eJ$EYq^oW6es9x{l59npY`^K*y^H^kTWl1e3df`q&01dn;&nSyh{&9dV`Q7vTvcG}|nvvEth`Dmr zLYyr~D|w}4J7k{)X}R-pyuSZY9>f+3<@L``V_l|1(sPQo<1baC_2VxmLRmTbdaOcd zQp=G1jwrKrrb_5GkdVhxOVStmjc2Az;VPlqFeHXOByw+zQ3>4!67pDTNjhDwZmenG z43*Gr7!so;NMtn4Rten(67pDTN%}zMnk;eJbd}I;7!so;NDQkyMw}FH_mRgc7-u|5F_kI`>qa{fE-VY??vC*p8jY3VokB1>K zT7tyysF=S1dS zBAUy;*G_oK{%RjcM3prTqSwZ5B2AHfI$=nVxYo#*KYR3my)Pq)A?q9jYuHV^{^G^( zw@^#|{q)#ZY^Ikd5sQf^PDJ@+!jK>#kNwvqvFwEu^UlrkZKTJm_W!$Ee*NyhwH z4?6)$Q+2@+8gL-_gjXW8Jb zvQ@7t^bo0BfASZO!3u#|^0-r`e_2cxX`@-Cwqomq?4m^PStgVq@h~!oC(gORLUKsr z+{fnPV8epKQfib5B}gpn62N=>xXzZok*zYfZ6K!4E+rleU#k$PC66z~US&D*N*je@ ztBO74YKtn4`%EZ7BK|48XUO{&YgAAY{7f0~wqHHr=(yN~5+pE>Y3?(lusE5&nfUbT zs6wEYJifZ-9!p(R+US2HSeUNGvr$v`m}I`jZ@$5n7o5W6@z-iE*x!#nnPkQ!o=aj& zvrVU&r6igXF@^|~*b^B|U)j8a^6NuGkNAlCHNtr2MpGFQ^4QRl@vj;Dfo*;oMuayJ zJefd=J+W#)Dt@4SIwI!1>MMeR?(^{MHyIN0*wB*Ej98}ei;AVamM_hP^;#aWE;I*6LLM7hGB#T-I`bci(L}@%v6YCwi9m@x5!x>^4?8RGv6MYu zMm%wF6^-}QPzXsIS~7x;mDBSx*JFq%M??}4O^85=JrTCsg?qKnON0;gi4Dhli1zfA zZY1Qfp(T6KD^oJ@9$jYx(SZn**b}u==i=Q?6d=NjvSe)=3tJMjSkEh;b*GruxqtP% zGIC5tbI*fo?7I6oA_fo#_iN!rko(cBXBmW}vuiEPMB)QDI}1WN3Q zluV4JEE$kKp9tRgQz0a6Xvt`%{q~)iUSA;_G827>2qXd}_C!i17Nab&_?m<`kzda% zUm`?xt|UGl|dh!jU1EF%;0;P1v+J-9!?Si zh{#I>N@QLkVPuc3znWYlg1fua*YnEwElC?%GMdj?US|!o%w$7m;tV3%5P=eV!pI&? zi=r%XPDtbhvMx~wNgG-+noVjvVh5i{8!{7LS`&F;B2Z#aq-5fL%94B;^NTD$FDQhh z4J{eX(1Wkp#(i1HhRnngL}VZWCH91oJ(^aWvczQv6PLC)=y_%QmZS|W8O=enzp!Qf zvyu&&iP@70l-Ls~nHWr25;do@SeuYT&nx4%ByDKP>}gt2%|l2|vUVXI3Q}vWLq~L=q7wk$HuLkv%kf zr7WrTA%e3ndG)+9eoNAZmW<|?QD@n|9sVL4a^$Q^L_H!~Y`nk+qsDZ7d<;0ue`uK#4t(l8LhS@$9sp75gWjo>yb6 zTiD_~9re62a!f{ZZ8I>`Yd1d^Tqzx?@O-sQ`tYn)`WJ6|R4I=6h zff9QnB@<=uGi5>n@%mP}{291%B&K#4t(l8LhSxs-<9d(PYx zLehqojAlwLLuTS(BBm075_=*g6BAx#5K#?1#L66(O-R_+OHx*MgQ~vdJLmQhb1OD6 z?WBym8#w^In&CoXZ^%|=lj25EYe4iS&H z4(HGBx7B-ULrW4yMNlQiQ9ZHT=Bzxt*N?jRyRx?E-+Bw%mOq*!O?%adC{0A3&Ohp+ zmVGtSut#srrn+eM;QDOz;IaxK$B)}H*0H-eqwVUVlK2)>pLrE5t5;GDElC(vRkWvR z)i*kb{cD;he58q->}5*l^s}4}8l@jEU6;u^xJjViS6+x3Y)PGWB+URS67dfaUx<*` zvmuc*63wTix4Q52r8Vb~OJ#)9smckZW-L|+NgG=7ifY%OizTqxaI#?`B0Uk6h(L)w z@nlqLYpIdL$;PVh&Bg02SrQsO2vG=08(K2kI~-_Yi7VhuHZ~J+pNMiqpv0b7ALC#x zd~g8S=>4XzIR5COb--+<5Rx{uWbW>>R=vy|cN4~Ze8BMBwS*b>5p`CzforG4nZ9;E0*@_Z-B2SLY)`+C` zM0oEhBU;U=l`ycZd-@_olzkq zZD`48QdQMTwO1l85|L*3ZEHUwP-0IUp77I>{uCqP!hRo-)jZ8wFWv_EjgsOm}5srtGuy>G{NrggiF1WcE;%+d@@t+Kb~!@t8Zw zB$n(FXiN)JmU1ZmQfd#=PjLgHa_ykE)%_pjffB;_7j1U7J6!b*|ibv=~A1%yZ0i3%Zq*U*yZ zEz7D*{L%xt<5$MqL_`1)D6uC}Vt$_Du{vE6-;-2NAtY^R$@5l!SsH$OXCm2<*Wgkj zP7#3;dm<&~G9Cj~Me^O{U+60@guKT_GfGXvy z1x4hI?R8ONPo%{B7{w#J`4b*=YLY@o+R&2cE$zBA+;94MvT=ck0Ypr@H>oa4>YH`Pz1x~3-N8#e0@xfc$JffX4q}UXv*_ecS<&XZ|_#K zE#|>QtS15`_C!j|=TkgfR~8WM8jMv4NgG=7yp<9e`8dz@WMcslwTY-h1WN3Ql$gsa zs#S?39=W@=LP*-slIP9GEj1rrdL`L7PQ*AOChe)Mk7|a*o=AzgjK_(ck^EHd2WI>& zd2DFOGyT&1i+K)MNH%25%|uio0wwl@5m~BPUJe#-o*!V7Tjf&-jHZmB&*ArMdH>s# zB`qm}gSVPQy&ie>naudRE_{7_E+v}syw#4(%saGnp|MuRyekn7M4&`Q(1^eMdrHh_ zP&{(g&nHS9`l?6J_$}0u=WTbNbll}#*b@A8?kgVo#*RyzeFYu4T^zmOf&U9zo-`F#a-vQ?$1%B<&K)5*d#vmurc!ulnf` zT;3)#U(nw+$2FoU&s%)q^n8%11+}U*5wnPhBLXEdf=C!~(zIz5k43M#}2Me(j#d67RFyj@ZRF*tV$o5CA}yf`}0*553|qHBlx6QT5fqiS-%F2 zXv*_8u!$3IonZnIy_1RiM4&`Q5Q&tS&!Kn>Jf2lpoct6*(uS5iZ=2u$Wd3pfWMeuJ zqloxG1WN3Ql$gs1cA0aTFU(j=AtY^R$@BKS$a^-p+%U2siLOK}CITh)gb^p(YGP;7 zBtAIfJw1ZPZ%NwFl4rWbm?U=mNFTCso+7xHhzUfX#GWwXMC;lM!J>DIU2OHKyb6Kw zml5C*Qi_U6C|KC7fB|o3Y_SUkySodqz)qwDy9>LU zx4U+CCpKcYUqzJvz55us`~02r_Z-i8hkHMB@64T@+S!>skL4`Iw}B08McV@r4+NE1 z6B#kT3GoCrQL6H`XzaGI67v<11 z)4@g;h)3@(dHC^4DS8C^*LxuE8g)gFpok`xTl=#&<%O-!0f8~^2E+;=s01TOiHw*> zLp)Bj`oMb5x?muX7Ft+tQynhJl~a#_4UG8}Af^IACDuen%x^(F-UsetSE3dg2&9D; zmfK4IlXAbkhrtHM`~wizfuIs=A|vMbL@jjaz&Z!|8VIC?7M64f?EO1&Y8TkRkxVQQ zK|oN6H6h|8N&T*b^2$5n-FF+_v5upLF=&+i zl)QY)3q67&npkf0YaEdey-EZEV;%@ZZy=}yX-Z_o9G|G_eeSY9yPoM06lozXw6NU1 z@k4T%8@Iql3=rNxyaR$ttci@6V?0*4t!AeWZ!{1{3oR@+n;yI54SO$w4J4KUaRdk| zu_iKNj`8r!)qo8c-oij2Ewr$tCnjx_dnX5B2uC2OghmtpE=nD~yob_V!jH1R=|A*% zh_t8{mcps1HS+l}$zTH`xD1HSKv0P_kr6>G-8|lrY*Lwn1_EiJg{3fj(^7f*BCJ<} z2m^vjtci>WVm$gfRc0#&^e_-e3oR`5>(yiBurJra1`>UMSONrK z5mdI0fm6~>>Jb!aAuY79+`b1+ljC8H*Al_QK#Tx_O00>Dm}8shQ_GcQ&ppyWAT6}8 zq?g-Ikgwl=k{&^CATj|#CDw$9lO(OV5Xx(}Yb_5>iq|73(xUOl2(B19MIN=_GT7(} z5q!~pGvnLJ>k&LVaF{%)nxh^;5lt+&w?X~oPagIVL5z745WYZA2}Y0-88M#^Pn2W5 zxy)QPhk-y^XkodHf7(r+SUoe?z^67V5T}8l5^F-l3C0W%!R>vTvs^W<>Jb!aAuY79 z+%~igl(%*L2|34@BjEuAl~@xQF~_-Dwqw8L$;&1g2&9D;mh|+j&E(r7u$ExV9f24J z1eI75B2I8RK0Jf>idT}Q*}L=zinM6_F@hDf0QuL`2VkQw#AE;L8LUq~Z#{xe_o~UQ zV{_>d6w$nfA~X}&z?gRiBJYBG zdOU>0n#hPb#v@1nGxFjtGYkZcKbG{Rj|FA7CEuZRu~*9u#4;eL#F`Lsg1Z?mh4LY< zvdXL8AJii#(xUOl2-f^uRPNpHCD`Z<@rc@4hplhqt4A>P@^@4F;Cy-nMKrP8Qo=u& z3cKcloMX)A1F;qeD!~X+A|vLw;-!@-%vv;YH4sP(EiAWB50Xr+6SIMhP#_inF#-rG zu_i>EEGu47&)&$-_C3)fDAGb&Xkoc|I6X8i|6v0*9zX>50HFXuCDw$9tYy7qTc&8) ztj#eHNDD12>EsF5Op!Hzr$2+cfH(*Ql~@xZPLh-lW_S0)PnkOWQuGLlv}pV>f)}gb zGu^QH05cW`L zk{&^k7Scis%dN(;Zl)Fa@j1s;&MrWhfuIs=A|vMb44(0=EVtb|&p;q8w6LUSC$=@c zT8U!@YEVCDtu)JGzQn)ZA*RK_m z*VnJ5N3c=9Ej6pHanU0vqKV}ucivFbt$bea3S(aQdNFx95LAK@q(nx{=RrJPx!cMY zD|r|Qq=goi+m3)$H4ojy2;!TDz80_G+c&{K}4&mI#Iy8fHHD%<>G1Xkxj2 z&C%anZKQYxQ%(7mEkIBSMvxL2F~?QT%bCBLPt~wQP^5*l(86*vE$L>S6Z=72*{<>I zg)#*QD!~X+Ld40k>!s?)1m*fVODihULRx5Hxy}3f#JuYyV!yaT$7mq#9APz#F`LsvczL;jdIH43zk+? zq=mH5!jkTj<&wGoDA5ld1L6e`RANntIKkdpc+=1+tiRc*nwUmsVyC!si2bI&B5wClFL(O^7(bSuYTeaY-+g%l}zMG9oRcg%+0E znej!HdRxU<^a~IlfuIs=Ld40^s}+feP&y`CMlvETq=goibkZ?5WyL2Pi{dl*V_t;P z5(p}>CPbXz94}ZSQ#Kqow^^_1&!9+)#vdaHBN?-0B!hb<27a2R{h4su;Mn( zG9MJt#B%HXt&bAk6-&1x5RpLG?6u4$gaji<2@xmD+@N)r_G-jo%WOgrH2zp_MdP|C z2ZC`vI1?fm4#W~5sKlBOak4yvFY^{v*Lqh%sLa#55qN z#F`LsvPAHg!zty>0?TYdq=mH5!ji7^v9VGt3Fm`2lKBsa*FaE-H6h{zC%3?CV!${D z#eT{mJ%S=F8h?x+%qA4eY@##7qvZ9Cs!NUv`bb7z7^9R?Eo(9&npkcH;SSw)x5S!E z+O>^pb|9z(BS;AmC(Hai+-8niVytCGFVaFK_%9Nh?688hc%hb+bSsI>~`xB6lu};V+3JFuUKaE z10aH*ew@LvZ^N1LRx5HNhda(uS{KX18u-F zXa~d$AgIKe5OIQ85k#=fxt2=RmK*g5inM6_F@mtFrdU?h20}c}W__d9o#v`PgXJAg zDzE1x=@Ass#B%d6Y09W$m~$k~0Z|VKD!~X+Ld3~3vMg8fh+3-aPkm)uq=mH5!g7mm zdQh=ne;aJz%C-*><$$0PYeK}yvceMGGeUiT&a$#C(n4BjVYxYu-KlJta0zVS%62#q z?|`5ZYeK}y@(kv3s-zaG($hd7Ewr$tH#uxnZZ12K9>L5&xBx*V)`W-?dZR<;$($~L}zofl-IHMwJXS5!0TzEXDZRXu_tnpkcHpWjfly64j) z7zac%AgBZ*NC^=q%MOUPz3!-G;-Bjg6lozXwDfW-cTrjL9N)3vY@$98#etv_YeK}y zGO`@mVU;?1*d_ykw9vwG%QyOj@+Bq#Y~ZTeWFW=@K_%8iM$B=Ita^$1>VuXo4Fu9c z3rpHDSAw!-$!@d(L=_7M8k0`3p*$<14@hMsPF`9f6<{Ya%0pLt%|<WYn<&zv z(ZnYTngQipc6|GaD=f>-dT84A2YLjjO_tQa)Kz)}MKrP8d`A9M&hTYG;OuTS5GoK< zf)S)dM$B=fzw3{r9q7N;Kp-u&u-xkP{it}xEdU!)Kx|1TsKlBOakA`ZI95SZi|m@N z$6Ta^w9vwGJ6I)2$yYfFY~T}h4TxeuP>D5>5p#@38OMR@?asvw1kyqaOL}{y`^x*q zv%v<&JSz~_fuIs=Lc|GfUWD1*nhvX!{q?))5fo|B_+tbMe!i#-&VoB2a6f}n@zUCf zl?i$T2mQ8JrFETOSQ8>nmOVwq51m&71A6Ka6lozXw6NUvF8-out%iXO z+=Wych;~3wi8VoD4)JI?W}G@pbue=p&y;V27V><^h9MXdF>)Sg5p~ujE9IOmYewgN0NpD zkqE>qAgIKe$cQ=iQFW*0(q6}mH4sP(Ei5b^>+>q8boXVohYk9G}5+8>gx@x;@i(0*bVd7Ft-+;`<*G+lb;u=TjC!=Xrb-=$_d%wFup6w-XWFo1^KlKj(-V7 zcm-MtYM~7=W`r}ghS>6e^3K}k?S+I5ouFFyTa0R;H&~s@cCq5xtf0R+|4Rrh^eW4# zcS=3i)8JK|2ci75qar`ZVL4+K`n?K6EUupWPUl(~a4jJY|CWao%R;a?e0s z7EYJ3CWIFLU3^g|Ne95I=tY_w^UPI0BSm~mf?kO)QD~mvyQ0B=ST~O@eAe3;`nO%; z%OLb>PFexhH7-1XdMHV$E;c;7M+aWB?LIvplo0u#-oiJd@HS(r%Mtlk&ZI+VU3?#b zUWu%;hS)ccUVZG7lMNa< zTK7tL2&Zgbu;VQ+wBSE_O#X)uTIiL?ADs2_ER^qmw@vPKwxHf7iv7mumDsJUNAT}X z^4RV_*}GT%{B*?=x(%@x9K8zp&z?N)0X?9%7>(A4+Z2pH3TIiL?AM9v+ z9?E@Jt&{tmW)`o~_t2tOVh1jICA@|Ewj+PCl6x6HU*nZ-L+o!xuV%EA*l~~Tx>v$O zn5$*7=g0an{CN|M73JO1uzRj%CmPxp!vA|L3L$e$$T3AW>FmXzR~X64Xr zh+c-;KtiM>Nj`5v`H1E1-i9SxiBAMCm7~K^t+PuCu=H8Rc!dsUsZJ*VxJw_ z;7zv5vF{}POZJRD>QRg>w{x=N*ZWv@g;7Fip;w}ZgVVpktKav00XKbN$8c> z-Gp8VZ(;6yKb6gR@|a1ep**d4E_qa%WrQU5+@M!t#}0ZWyoEXEvEQs(QI$37vM@W4L3ti(PN^h)ePL9c|j zaHpR3ht*se$8zLvrP~mDe9)^ej^46Yk9@jU!b7+rueA-|S#&Y06WHt@LTI5^B7d-6 z0#EH{n=n(Z6$!dmVs8X`C3aSzSHfGkmE=kq>pU}%m2(f&ZHRp<=+%l$pH1d`uDVyk zLrGeFB@3VbvNQYBCg2}JXrWgke{fgIc!@XsmWds(>!=fAX9e2mSz)9ppk)EwhOh@G zDA&!x4?EhkDHYoPLkKOjA-sjV$>9u$&-J$XMch21=Ulvz#+-}y*_d-tBJkGIEfe22 zuY&A*p_6Vy>=r<;hUUrQIo7G5?v?NmM*5pGbJw!I^0J$jd{9DYp;sb*a6umQgG=Xa zNm%+;74gvDvZ7bw9W8n#yoLFBhfF-*rc7$%869-5#2fJRc$h^zz@8b)4emHRnu)K@ zUQRhV(2@^I2rcwVcq>UcU=)6&NvQd1eoHM8Zw}Eb@!m1LtkT~JFFz>pqIm+RyRAmFN{bABuR+g@^E^g+mrzVMPbEpk3R42%&{u z32))NC1`z4{BcrRT(z`5;tdaaCEgFASHfGkF{E@Fi#w~RkJeaPAMy4Ly@Iwx5pAOI zP?9Px$-?_CU#OPP-(2^K5<&~T68VD>8MM@;Z}=$n!YnPdcx!=PiFY38mGBnEKAwMA z@5#^A@hdDXwRoe1UO~I7i2g%(2=8l)*zkUJj;OQp)YrYDgwR5-gtu^`4wTi-Q|*-{ z!IoZ4%q`I?v5t>k32))4_4>^=%(c-X4p@3M@sWJ=nBEskoqk-olBQB6=m(NYE?ctt71~lFII9 zYM{MpeL=S&)~wL0;}^55vCk*#UI`Cj?4#Q8;QUO>=YHcKLTI5^B7c%p_}w3NYjQI! zF)dyv#2Oje5a;_)doThxYRi**`)k~B+dqWx3T+5);qsEmOuVRF5U;ba8pE{2S=Xo~ z=Cb&AF~^mp7IvBWvLY3f!L|SGaYRdvgy?{ew;@ijLajBq@~S%) z)zfFM;+!gYy97ilAl!gJPlUvp*nP!GomZ=t471cjrTL?gURsN=xdsAhp@pk>;+!f; z8U@5XAQ%u-Voij^IjUice8I-=7mfIzJ$ba^`Fa@$q=go);)!#rBLT3GYNIaOG%M)M&+)`slS?NU)YrBIEq4ArSK;eN9@`m_h~u(-m46o2@N!tM4`)1{))QP=Kfj1eI75 z8RuW6K+IR$7SP_W&SW5v7Frma`Ps6o$W)H3 z6iVQ4p@p$2kQQ1P&0L++ zl;Jk(zy{W<=0J=9f=aB3jPtLsmi+0cD9^jD)K3r)X(27Nu$G7wJ@~E&Vt!y~M{QHW zalL)bb+mwbmS| z1kyqaV{_t39@YLsUa*1nsvQuyw{6zX{SXpsBBNgYfS5lXcHg~XZ=bphU( zz$pbKVvi{sA}bgOTF0=K^xgPb8J0X3Y(zrLPn_(eeVN}vuNgIe7Ep(HZ1BUFiyDKm z2@iKs4-a1h=liV1dIiMH1ugV5eT2lC$f#F?A?DFjYH6dh_!tOU$1pZ|T=J@wH!lYp zy@6N=M7PX7W-75JMD3BJpAhrS-8{78Kl2(0q=gp7X7te_*>K%jLo8s&gz#O%T1PgH5CYN zAgIKe5VZ&L0Wpt%#qkBU<2#bBp{|2 zOE6K1HIY%T++hFJlhhN+#UGM^pfv_-NrU!Zl|sJ?gN>i}aPtXF%0Xa@w9&^m^H&!|^JA?7(I%9?*?2LnO1Fg7uRoK(%m z25ew0$qht1AgIKe$f#F1dTo(hKuh_WsMiva7ScisWAmp*Hnm9bAILejJ^?_ueM{71 zE+p1OM!gDvm}ifDp%$vX-aybghOueh!A8~MzkrQ)Kx6|VHxN`}O^CW+8D-ooJWric zsEL6loIOI#C~$ z3xyQ0F%M$?aCU&!wc${`mWX)`#$41GjE$I!z&8y*JON@H5L9AKWYnvX5cBZ?HMPU* zTN((Yg%-v}%tc@w4v0`7&H_Ot)`X}FlJo^)o_C6imKI&sKp-u&Fg9W?0`poR9D%q4 z1eI75qV`x~UU$x8waK|uy_SfykQQ1P8!;Dwl~kxD4T0zc1eI758TAU=5_|hO>b71> z4Fu9c3!^FKB9?lUW;aKT1cFMe2~ig;;}SX8tW+s~L$4(wEn3I0mb_J7DP!N~g{L+< ztjRq7b67c2c%lC8PK;|&ON?HS&KUb3Vd}hF;hpVe)DrV0>Y>rbBv{kG;A>WX)y<;Y z5d9qzv>z1qB&i&%!~IH0PzINB({Ei6Z66Y%Zd0}_pa9JN67gYxC@&SREv5Dqa`5lzU^K>Pzfal?Jlp!9BY5RZXy z0)k2?5ol9F&w0RSTd>hN?-tbt@-YSOKc@uMq8>_8S0J#KtN?;aDDfm`Nj>LyFFLG+ z*Uh93-w@1a-x{t`f@;mWQeMw_z5g5_dtaKVJt!+6 z)&LO;1eH+Y=c__`&YiA51Fxp~Ch7SY0e9Y0f@)C@Vf7q{XOQ#pKu`%Ks>wz4oa1fO z&~yH-q?Q~U%%_iNr&5Ay^=(s9&$;{emq5$`|F=Ot?m>R2@5kG^={aAPeZQI7vk+Z? zcnbuTP~zlEH$CS?C0tt?4E|$2wnBa=LA9udP)mTw2DPLI5L7~mZNUZgoWm{WU}MXe zAoZpk%zJOBVj!s2kE2EOocFz_0Z|_6Y(4t_lF&FA=4#`)a4!5;~jktp$ z>IAo7zWtMpfuLG*I=JgOFViU!h!|+6?m|AsL%T(N&s!s}p7W9W(h{gWSn&eF9*E08 zPzfcPJywc!bFt6HtC&E52zzwoL8IUfprlLO=Ku|5}p(KH}Rual;Zleg9N+?0{2R2B~O_ZQo zBIiAh4+UZ?)Llo&2lVTV`c7)TiQ0qrwdv1?1_YH*f;LJub zAn-Z=y{k2&5=xLd4K_$^mnlKDNNoqg9onm#kn^M7uNd{6w00(H4|eGR5eUR)AgF{A zq#XkrtDwEY=e$DREe3*WQ4gV410pBHyetq@LJ89Hfeq5a83?LHS~wu)L$8M8_NQ;$ zIrW|Na3*R`lBNK$3y2p$PzfbS-vu^WLLZeC@-e|TiBW=TQ4b|)91zc;tYUzm5=xNX z4s2|KUhNk2YP~j8F%VRX^lCsnfL?hu@@)5H4yWFpb|=u@rn#9 zkkBi?fP6rH3|+`476XDxC_%=kkn@qyE5C(&EVM6TAgC7g5N=Ed0_Hb-77$cI2{J|n8)Wp# zC_%Nz=oN@?=#}e1&e!c7#HsIO_99bzunREx}5fVh46p4l{M4Bz1~g^^jDOtmO&AoTg5nD-Ga zh0qG@h_AO&Id^Ofw|5?Gm`#uvSP{L4{829a7{l`fbux^?Nqsd_T9N|8N~@DRL->(m zeumL2dA7}zhTWe98>`prhVY16c?_dI(hiy_4SQ1G_fSW52;nh#&KX8aq|Y!@T9Pi6 z9--ds8^VL1H#3Y&ME{B-3ra)V-gt~!e^3aQ;2-Us1%W-X_-z@N5F3VGjihT5grz?x z`H*Sc??E0afNTlxKj8w)E&O<}`)miP_d8x4e4=@JR2s`S!oIwczoKp!U@HdvBg(#bPC817on0C(RmcC{g zQ=qvY-n>V1iv)VuVFu=WQG&ZE)9)}1ZK0MRsFwJRr65V`FKj<_eb89#LtGy{U26ih zXc@wZCvR{1-K^Y8+n6I+#k54EM7rn+^$>l5o8NA1R%Ztc|0m}nw-sWiu;C?!o1SEj z1+SLmjW)IIyf6waNNw(Oi-gAO!M4L^_Eo!(<2ni+HK|b1V z=_c3Bi#Fa4nrAM1-k)i|#~BE!g*J}ntR@es6bD2z*PQZ%v~KKA+*q9u5=wl6d~6!S z?7!QzO-1UHi`Bl_(#iJ=p)tgD*b1=Fwm$)X&7brWs+MhoT0306{dS7(nYN@ot$L* z$#IOPBuRx_kC{XMxSF-sVFnwNFy>=w=ttA?#WQ57T^OelO5kr%hH%38`A@7_e0RR8 zPCmay^M>)GB0G5mZV^~Bezo}f8P7ZH$SRH@5?n3=WF`%CF?5j+-053 zl$d>D0=u;ArhFxJ0i!g0Jpgy)?tnXTuYN6VqFVI6TqDu3WgUKZQ%T;hE=ult$5S8yxjHI{sgK;@3J)#e)l@? zzE^DcJ>Pu3lqf%E5(~e5MsELQ0i!g0>0Pc159s`d1-oocpjz`6W!#Z#Bx2w9=Lugg zvn4A_8i>9#C$qU9HTmQF1^SJ*;)Y%L2CH&^UZTNuHmF9~LsX02eoO5^e|~#358e{N z&ONJdro>h6DQwK*{qnsx3mBy(sWRMn+lXyoD_^^ss21KpD{j9v60;IR_@$de+2b`% zW=h~2EOD1DrC}tKJb~X_Rfw%#GA)4;^Jc*p9JRO04PGx`l$N9w11Iu57jm&G3%(^# zEqa%&kyy7YjBnguUk+RM+d#Zu4ml5umruP~px<9B?#qSI(%vw>>RWBO_qNPts)aq7 zxXYH>gS)m?e`4REEjd_nu9>zawg=&^T4+}u`^OvF6-nB=ITN3}w-aBsxuco343xMy zXAIji{E57@P&~HOQ*-eoQycC&dZ&S)TJ-ssq}T7p^Ct39nY$HG`^}!E=eG03n@lM& zL;u~k!YTH&#w<4L@?N?A{hMGT8Hgw#8UR5hlu&L=*NLh%P61K!+X$}uM6!O%@)-%D zRjKhzcJ#tgd6La7ARK@gS1pol0)k3tx+|Yg(}~JKXyZpfcV6G-6+3hztAU_emrhP+ z+wNSH;~JukTy4Aa4_RKZ6+lo4B|dka%C-Yx3P&4nw>9L0>U!{o4ZkXspjrzKO=Ux- z!;Ro;(8g~df`F(31eH)?RdYBO35bc;(8kVJCHc<*wRqbq7Yqc|@~JUdkNN9dw}FTU z;tvoVfS?jeB*jeBiQ%PB17TZL;!_TG;$N;WGZ0kk#knzht?WJ*iNU)<`Bl?V`RS@W z%Fs$v^_sD4AKZ;io{u{Zr|2;+a(Dv}?Usk}cyoPuUC>Q4l~95{n=md(n816kD8xGc za8@WmwdnINNmjsNC-~O|K<4LiRISW5OJ#>9u71 zr2UZd&OkhbdbQ%wLWN2wLF)qCz3c{OAwkQK5*%Y7s8*W-uwo2tN#%uTqcIRZK->j_ zN+?0=0(>RZ3eFvbw&cRCnFfMty^o%(N4BsTZHxh;01#(@pb|>Zx&UkX!y54l&@!ZI z!wdw~S}29-wIt;o+E@%kJs_GM8KzJPC5-WC(4#a@gO*_qYh)m(R`kcQddu*$>;bS* z9|&n+EglI3l~97lAHGm%or#}?wq#di0Rus`Xn!S1eS9bKxzK-P_DND`pFwL3ZRg<| zULb6tUNuL8^cj?(wFkbB@)^ZPL(C^-PBaiyi?;KUv=4|rK#T%{N+>~V4}AF&+Jk?F z{$u>hiw1&f(RLnY6F?M%TCxZTDxn0eJ+R8T&tLC9js)*F5LAn{^UxarQ4wm%G$5#i z614WfPL7kM^jgwx`XU2CwP?=(^AAE$2_FCPFXHS+X4ZYfcp1wEsjN>+P3!R`^{_kDc ztT#`rhyjZS9lkqh0$;niw1Gey6B_1W*9W>Xv>|9{MF;Nktsgjn7nxFCC#Y7Qlsqio zg}he8HTzkIFK?U3zr|$zhnV4;lkK=#O(z5mU+@gMad^OpFy3Rz4Bg)cT^v{{pQvlO z?#jlV|7y<~xPF$$U36dr>_$UP9A5Cu;Q_Vx(!PBP0PUsWs!An1+6bFNqzr>@oa0J`_&n4Vwua?v*tq<>R!#PXU~>2iee*g z{U?jR!|8ji9ev$@hw*~ZZYC^6q1ChEH+gV-d-me|JS(Dh^ZADzABXYttJ4ew(xMb7 z4P&2Ag%d`-2;RRuM{P4LwTUKfsGZMG*R`eZoAdDB@Q_E1gv_vUw$@%-^ zA$$PLg3uFDt7#3#zl(Y-Ne^4>^F4EaB5zyP#t?IihbUbnMEqgg?!NW#*Zpwr@|O$x zQ$)2yY>dQ&d1=fwp%V{?+G%JRHguS#w-P^tQVgvG%~cX!}8lK;M~qUz>FI zC)BHQT}$%sLu&CFFJ2f3szv7vl4J*j^Uzwn91v7Oi9-pq_4$X#K(rxcYsg*vJ$U@I ztSTj_7M;mRQVAfE8+!1~Ku`%KKAxVd&!eJqp^fXyyYaj^Ua_f_3mOQjMdxtP;{dTN z`zsa-1eH*tWz%{37;eJFA7G6I=)ElQk^?_i4P{=aNMKK>Fy3+aFxpG+f$mir$zgaoxHF)Q|u$#22r|A!D-NQc+( zmQzcV{vU*ppcW;rH)$yQmznhc5JC&-{$*#%DK%h(AQjH!qg`R%e2~*jy)6-KIBk7= z_nwiLHh&|#RO<#ra8@6!OLcEvw{X;O`qj<#r>F(X!Fxs>m239_j?@vhd6cd zmt3QUvrY&aPL25Gqn+wknKv$xOK%fJ?~GoFF~g+>N%Db?Zmg-g4&FOgdFHL{I9Hk5 zWiF%>LaT7G*K*It?riL<1+tO2z0yZZO{l~#)blhDY0uxwuS*qUT7!u)rQsCwKi=Bo z#43E4jlCs@X<68$Ur+Ts2@i{YzAk^6=*W6Cx&mHxaP!d~jj77N4|*@_WkLus8o)dW zT9U#(d21^+ROJq)cLoA!QC3I@8g3=Y=BHK8UY6fDUeu6}ci%tCr6WtQUljvonkSe$ z2m5Fv3RmGCi?SO^cUs~@dCZDDtm4iD*_e+lXRB#n!z=N}3ykrgB}!@7Uy|ELdo#+5 z=YL>{x$xIIAENJqd&8Tw&`zi2=KFf(FpLvvK4|>$IfwIJZfs`D0)}gyQsP+Zy{D#+ zYH>b#{-VFX4}Obd`ATdsWy@O}-+|u=H|6WIo~8JW(5QqG_*)yf*fjdPClDRpbu};T zGk~qEF!mopXl3~v$KJebZYs1K3HUcDaL{_SMEwz3db(!xD&0f#?EacRBQK#IM%9RuY|DnNcdb$ zH2JCiY|V$iUg@Qn?uiLKF_zWJ#_P=sSO1W&<_OguLt0(jSNO$tF=|m7_N4az&(v$l z3^_0$On9ZIi(2*K*R1`~#*@>OB&orgL*_s4T}`dth8b*7!kCXf9!aKY%VsEDg2FT^ zp+ve@>7|?W4$c=n5h>T3HdOf%8OJ)MZI{Qpc<>IlV%bNwRUSFnncH-WW6g>mlC#=+ zKw0ff3gvhD#>ks54pXRv5`{O!vc5g`%hN|X1MzG3Snhlxkon}AZXl@Eh#Rr&c)sKE zO3|=#quXr59sxF?cPzfbg6o_SWS{;!;_d^?*1`p-lYj?35TOthv)yn&EKI^#r zg53Ef+VE~Slvi@y&EC34DO5s}3(|3ZaIC^7j<46C{Bx?F!8dR2SJH@0zqSAJ{hN+nN;Sxi~_ zO8)MXjaPS@&DO4ZE!Uf$lMk#lhy7gmT(;Sg6$lU8@9f&juDpNXN`*=&v0?dKw!LVQ z{9o2wKorjJ#*;ra;icQ}H4s$mW8H9;Wptu^D++Bqb$8=6-ZtS)TI^M*gc3d1&STTl z9?8dlI04b9sW<=Q=*`WECk+JE>fji`KACRI9^=tQz94TtRr2OdFPv1Ugc7#~MY3C` z@5me8ppDhfoAB8)T{$0c-9S*Suz8W}S-#71{Q+ph;d2x29qh_Gwz#fP2_-IljACb2 zUXhAcIC>;FHAe|z(7!~HOHdZ*^;N^^#tv#TZs)&u;m7Alg_LAHu6#4P<9GKT)WJ5*y;?vvH=q zvi)QVBj{tp!@p~Uf%^I7=< zo8{5((8k>#ojHsD!lpcOR+~FSvO6_T%FUl;=5#jUeiLRar7p=$zGnua>hEs6O}1C8 ze3v{bl~97tcVM*ixiMcc!WHJVwg!S~m2Ml(uC}-(S9Qt)HbV9f<^Rpv&D`ya8(IeX z%+q#Ek{)Fr!Yfxg$TIg?ZfLJ4@pD})JHPa_d~JLouu=WwDBcoUm!V7i4FuJyQ!|cT z?t4@|8dVsGB^Sr?3yp%LFu+J=^z65W@^vG>~&TVON(>tt#j>$-r$r9-x?Hz zZ^;&{HxN{-`Su7_wiJxBdm`ZjJ6QL-c=O8Vb}6(~qgu2jg8pNzH}B>Et?1TW3YAcT z+JlpB>ow&L3tV~8!~+I`YSETRk~Rl6%>SnKlHm>=*VJ2s#3wEfLfbHkP}e3S_hU?NO+N5_F6Lvx$*#Vy{Dt ze8O#ufuLH(7Owl)P=4@Fq+ET?W`#;9LC0D!uXUcte~gZj6YU*T+KLuj6~%IHh?jp} z$;@dB4(}%NPUMX{M9aGhIjB@Zi6O(InEmNp@))4u?b5q3{OyxK=9Fx2AgC7Yi6rUe z%P~B2-5}aq9*v>*}h7kZIXukrz+W01% zLI2VC!FvNiwde>(l6H(}!kfc0829?UVI)HdV~;Z`&5MVmdhxPP?ivWHMMrAzUhRh$ zcg*6=x4pV+7?Dw;bkrQ?KI@@8wF35P-I84SnB*pW@3bREf@skZrzE93apim8G~sz> zA2Ez9X}aE#v)H^X&*Zf&(Z;FNZ|uLgt~@Awt%0CgURh_d22YaZ)AwwFxb&+aA9A}9 z-#c@wqP+-b_o}><@7~JK*Efh@rzXCTlWw?j+CIXa7B>oVo~bcU&9%uuP%YXX!|C5% zZoKrjCfpUyR;MfuLG+L=N?;^aMUhjgo8EFRIeDN&0-y z=MkRTG2?lw`bTA#LnRCZUFD=Sd}&c9jj4w_@xzS|D0KasmM&ehhFceYePhdJcI6Mp zZZr_PV8>3o;mLA|DVaE>p;znmjdeTTm8S--G0a$K%`isrqdUa>QdfR6$9lN7IHNXD z8%Dx>%9U??)r24FbxNWBQkvE=XiFMc*7Os)y*3b3i>{=@TKGXPUh$6?AG_|QLbd4g zVI;N{YRGTF3cXXjy-LT1REyGZlBefjJ}7<{TT{K=iXT~`KHW8q6;AA+xc~Qq z1x=pG9tJj3YJB~{F51mtb9)U|4(*blWk{92vkARgYi-QSR4SoF>-V$R>7b!Xsb+c$ zm+cetZ5p68F1f@&P_3&zGvU;bNlNWx8?Z6?!YAf7C_vj+cafU&$!vCG-U_A1oZS3G zvDxfWg;?ctKo0)&=Um2$EK+uV$Jw?y_%j<^H9%Vuyhx=IN|abXhb@{jQwc4W4T#*O zU3ixgwYB)eF$RKajr%i?Wv>;ZBo@pK#O8a>yk)Q2+WKuVDwR;;^SW?$V9jJ@Izt=F zyI188N|n_ zMH~6=bmqxTU#KC&yBi3qRXRL|jcF0AEWe62)Fz#Ih0ZV4{;RvIR6>bT<)YcJyls_r z_s~W_&B5Fzc!N5kW^DsOwW^Mp&+0eqrK~BM2Z%R^2l2U{o7DJawN)yi#4P6+meaYe z($>=vh?yV9aHpOA>hfwH27+ph&K}E(O=_jQ3_%;y=a1ok>bFo+uY0IeLW$kmVwipB z%1YT$XruY*i9BDP$x6#QZxu>Vt@r-1tU)`b)Vzr{F0P!&rvyhS{-56|R6>d6?_yY+ zx*kgL^JpXfXjfil;A_=uP)XINWGve_YK78se_@{KU@UViyj|IH4Bni+ieX(oZ%_(! z#aZfdzn*-_`v>a2yTw&1p+xQC^I4AAS@%AXtb9WsWx>-d{Hkp@3%*`TaSXwC zsSUSuMAYDl~QNhMY5+aRP*EkzgW%+(Ja;U%lu8V;Rl~YFj#LjKgs+HygL19 zJP#f|MY%S(j7lYxDEm5!4c?ebX*2}etLM4L^1c(YsgGW813|Ue!U(pu$0u{hniQ~c zL7Tt>k3=e`-{n?mx-`y|hMgQq6L_IFla&3{bE{NB30h;|d*_&7-h66vHK|ZF13|Tx zwTfc70z8$Eo|umTZ-V*gO8)AXwLU79P=eNcSjE{skRMvKQ9XUNoq?cQG@9_0X{kYc zk?jVxS42CNN+>~}U`bl$--#DGl%#gvp_84oQoE+BR6+^bqQYr!zEyZitFl_Q+>r)?YJEjpp%#`RP5I)V$rw8wjdJ zdpmgVTy6-@_jZF?<9<0quSN-)8Az#XBm0wRY5LAnfiQsF)oL<~NxU6;@2r8jO zr|%JLcH~-R`F9tvanIj{=UZJ{ySyUOKu|3@8kD4>i(UB1Znd>@8zK#(K1#HE7tS{I z-J~=)gEpq^{>=8a4A5+cEHn^Q%X8cuw!6wE<%pUeh$e6|Y1)ryC1-8uLr4wxxgN)k zHJzf^Jubp&9h0P4sc@rC@MMK&o}^F-C0tgvE1QNOSQm=dj^7P z(K-g-6-^z>3tn%eW{JO}Pzfd6o#NQ1UUACLd}t$a^)B% z!d(Z%tL8DzDwP-rGG39SXEt3qoM^5dOOp)*9o5h}1~>gJ@5-ZRC8^)%%PN&nf{t+D z8T4$zw>8ME+2rYNAgC6tW0JISe-oZ2R%P{KI&*F=kn*}WVZme?eVJS}Q6|KiGdc7LTt3BPV^jlrbK(yEy$HpF9t*mTjq~WXh zslVBTa;-Jz=xFuau(>RAlAjK)u0@myGZ0kka+YZJ1kR}+cLj4EliP3HBmChjOGf1C#SihP! znt%Q=Q@y?YtU?K@MdJ^rCv6J}A6Xp<1+F8HpG5ocZ45TH2R63k_o*I;x?o z6q2;PgD1Zc>7x}Lxmcx=13zaoCr^_SU-&1Z<1V;kzc7?tD#442y(0+y)M}72}Fs|anm;21(hXiO( z;C?6C3)5$UuI|8|i4tE}Vy^%#sjjj0p-(M+y7b*tQvLRQSleM^`Jj-qe|Ij@U5t76 zpOs6)9>}Kp9>}sOLwq&@(Em~PlR_*sA!esOPUqWb=b2umOy&j!VU*B81#cr(6zF!uCN@%+HTkM*J zUafAdkEwGzrSgU_ZcPZS3*XQF-TiBcV9l=WluAHQ2~8J&i~YhD;&p>D{QcBvDoW_S zSFv*y_YsP}!xx}-^SzLGmrhVE=N7~CovTIyt-J!_gB3yR7!rbpv8auY)_c4+_sQGU zuu~Sb#O_%7T>$LTOYzpEnclql+0HVRP~xKNS^3k7WI4PZd@Uq-0P%d9H~;9?%|K8s zYr`7A9d|j~erNt}Pjj6R5=!9j zn2|qBNs&lIF4&%s*{c$-9Pj%NA+%DmEMPX_KTQp%BZ2=qUUTLr?lsr<){6bq)_bdw zPB!6K)b*@~-wsD-eq%rjoe&aA6#E^=0?Pd`HTFf~=y=bBepPz$b-9vN;V-5|weasj z{+Z>_Ur03YT;uoWeh*&9_nl4%2_;5K3)rm+ndM7gk!aCiQNpD!VZ2s1*hfv$qFS#r zFJRvXWtJ%|xIycHsBP(ny3fxpGybsLj_kcAB)p<3y-O@H%YAi!T;LWy*Hgn*ngQC5@?ztIMi zo9S;nCQ(92Xu9}Y{N0idh#(U&7ZR$4Hbg7&FCiq9z~AEUmUyhm?yPlzrY2CpcHF9JCBnLes_H@N_Ab=Og_&*YG*FCWKb{lcrdnbIf}u$j8Zh%|%=L_bH;! z2YP5}MVn>cD8H@xT|F?it4;_>dJO*3&>ovDE%i!hcQbia(y-kXzGGTQ2(9!s#%yVK z(_01&y`wo4ze!t?o{#j_MI2}%Cx;slPu~Snhfxm?oT}^C zQXGzy1se@vh2^=uv-V%f)&>G;p+#3)B#8s@9*8eMP>D4W+Ukljx;ff72rETXT36S) z_L^iMkQQ2W%}J6D5rRsriFoCXlJ6t7yUSr6ZvX36+5(&ThSeyfg%(|(gOws6?f@|v z2r98ARuq4v1a3qdF*~pOB`*l&_xx|kO{>plZF(fhpRX3=_`CD*CvyK5MY(V8In4fK zlKiD@K_Fh%&&y749nU*GeJN83B}U~6XDgDQ$WH?CP4$kxcC3@#1Rj16zPlr7QLRQ^ z;cUXiBsta%cP@7ik7X-sj^x`9zm}j65a-57{?>rOb zuT9Xa?Ws0=U5)nqOUFwFf@;y-LU0FYnm0eMdhrd{w#wc$=d-2K6}fuh!kq5?=}UsgJl=lFZZ$^&xbk`f%fZ35@>>}g*f%E||b z9YEX!f=a9jWymqvZ3~VpuP8x$O;rcpr%GKDCGfYAJuHBfk0YlVXYiq@~+%Rw^0~~LO}QcK_%A2yH@w)4VTfzjU1bpUEFYf zz}`Kq9)1wok{SCA1kyqa zTZxw09?2i|ar-%lhfAV8Pwh}xue%~@7!Og8X}Q6T2tecqA`J*Cu_nZ`3HOFWJb08h zuYS6Xfk0Yl(Q<=!7l=AQR0M)btci^0ya>c&npY5CJb$8rKw4W!%e5l1l6Kn^T164??>@vQ({>Sza0jGYSC|uU|(OZfxKY&S!T1>OQ!jtTC^TpTG7qB zH?oiiCk-~J7XB8`4ZO$Ee#_0~PUIsNjx$7%M$PyP`sNtStEU`cMfiRb^@R2Y)E*3r z%RBJ*B?I}K{5LE$F}?QDx@+vC%>0G?GANWcFR;*r)<@S!lwY?i&#_*K7RTt-<3um* zI;`=&c(X>Hv-Gzdb!@aU`uGNRBkYcx&$+lVA!Y}w@cf4C1b434KEcx|+up6J-8t{0 z9W?JY5UrzOjST2KH})B5_!4PWRV|{ukM=Y)Q9di%>so;~POxh3PvoxKJ(XXtR7PpI zf%s5W?N}Bc%{5n&f#~Xek+2$^P)7gi9oCd!qtkPZ^kGMCqdu8%5L@Oq)Ao;eN#QRiDng8?sLE7Sw*w`A6ai5R#o%;e;+YG#Q*~n0}K>tkT|mj z0|Y??LB$rki*B(%I_*FO3~a@Kv-jBDdE1I&2cp>V%)Wo$`}(Xo&wpO7_v_5roY`w; zuf1k1T2W#Q7y6tfg#(o=?`%B_c5^F#t_;Zmtm=8L1q|(fh3q}1P58%KGMi~VsM)e4 zfw-aW0y>9O;4`-t#Wa6!@V5sm?qxwIR;B<}9lv7;=Y4MxH|yG3#IbNo=JM2nhSW+B zh?8AAfSX=Th>iXYnC7+gzV=|>PFPZZ-$j5`y(;t}eaJmxnS59~Ow7VDxO+H+&!zctRsR+v_-??aV;^Im6# zHB`KQqKLixa`UCl|i?aw7gp zJPnF(O$zQixL^w=o?OU-j0vpzK0FsLe%efYoIN