From af7bee97f16a390459df3bcab2074fa4c97f43cc Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 8 Dec 2024 14:30:27 +0100 Subject: [PATCH 01/39] linearizing motor displacements near an initial configuration --- gait_generator/scripts/generate_leg_body_transforms.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/gait_generator/scripts/generate_leg_body_transforms.py b/gait_generator/scripts/generate_leg_body_transforms.py index 2f73b16..35f1bfc 100644 --- a/gait_generator/scripts/generate_leg_body_transforms.py +++ b/gait_generator/scripts/generate_leg_body_transforms.py @@ -7,7 +7,7 @@ theta = 2*i*pi/5. x = r*cos(theta) y = r*sin(theta) - z = 0.05 + z = 0.0 qw = cos(theta/2.) qx = 0. qy = 0. @@ -17,12 +17,12 @@ print('***************') -# generate initial feet position in body frame -r = 0.25 +# generate initial feet position in base footprint +r = 0.085+0.0455+0.096 for i in range(5): theta = 2*i*pi/5. x = r*cos(theta) y = r*sin(theta) - z = -0.05 + z = 0.0 pos = [x, y, z] print(pos) From 06f029a201185ba34c40f0dfc8ce7c245f8253a3 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 8 Dec 2024 14:30:44 +0100 Subject: [PATCH 02/39] linearizing motor displacements near an initial configuration --- penta_description/config/general_config.yaml | 41 +++++++++++-------- .../penta_i2c_actuators_node.py | 21 +++++++--- 2 files changed, 39 insertions(+), 23 deletions(-) diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index 81327b6..92f2deb 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -5,21 +5,21 @@ max_v: 0.005 # meter per sec max_w: 0.05 # rad per sec legs_body_transforms: [ - 0.085, 0.0, 0.05, 0.0, 0.0, 0.0, 1.0, - 0.026266444521870536, 0.08083980388508806, 0.05, 0.0, 0.0, 0.5877852522924731, 0.8090169943749475, - -0.06876644452187053, 0.049961746444860226, 0.05, 0.0, 0.0, 0.9510565162951535, 0.30901699437494745, - -0.06876644452187054, -0.04996174644486021, 0.05, 0.0, 0.0, 0.9510565162951536, -0.30901699437494734, - 0.026266444521870515, -0.08083980388508806, 0.05, 0.0, 0.0, 0.5877852522924732, -0.8090169943749473 + 0.085, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, + 0.026266444521870536, 0.08083980388508806, 0.0, 0.0, 0.0, 0.5877852522924731, 0.8090169943749475, + -0.06876644452187053, 0.049961746444860226, 0.0, 0.0, 0.0, 0.9510565162951535, 0.30901699437494745, + -0.06876644452187054, -0.04996174644486021, 0.0, 0.0, 0.0, 0.9510565162951536, -0.30901699437494734, + 0.026266444521870515, -0.08083980388508806, 0.0, 0.0, 0.0, 0.5877852522924732, -0.8090169943749473 ] init_feet_pos_in_basefootprint: [ - 0.25, 0.0, 0.0, - 0.07725424859373686, 0.23776412907378838, 0.0, - -0.20225424859373684, 0.1469463130731183, 0.0, - -0.2022542485937369, -0.14694631307311826, 0.0, - 0.07725424859373681, -0.2377641290737884, 0.0 + 0.2265, 0.0, 0.0, + 0.06999234922592559, 0.2154143009408523, 0.0, + -0.18324234922592558, 0.1331333596442452, 0.0, + -0.18324234922592564, -0.13313335964424514, 0.0, + 0.06999234922592555, -0.21541430094085232, 0.0 ] init_body_basefootprint_transform: [ - 0.0, 0.0, 0.075, 0.0, 0.0, 0.0, 1.0 + 0.0, 0.0, 0.158, 0.0, 0.0, 0.0, 1.0 ] gait_parameters: max_gait_linear_speed: 0.035 # meter per sec @@ -33,12 +33,19 @@ tracking_linear_velocity: 0.5 # [m/sec] tracking_angular_velocity: 1.0 # [rad/sec] i2c_actuators_params: - actuator_angle_bias_at_joint_zero_degree: [ # considering the motors are at their midrange at 135 degrees when robot joint is at zero" - 135.0, 135.0, 135.0, - 135.0, 135.0, 135.0, - 135.0, 135.0, 135.0, - 135.0, 135.0, 135.0, - 135.0, 135.0, 135.0, + actuator_angles_at_initial_pose_degree: [ + 135.0, 135.0, 60.0, + 135.0, 135.0, 60.0, + 135.0, 135.0, 60.0, + 135.0, 135.0, 60.0, + 135.0, 135.0, 60.0, + ] + geometrical_angles_at_initial_pose_degree: [ + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, ] dir: [ 1.0, 1.0, 1.0, diff --git a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py index 3e688f8..d4dd814 100644 --- a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py +++ b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py @@ -60,7 +60,9 @@ def on_joint_states_callback(self, msg): self.get_logger().error(f"Joint {name} not found in the current message.") # Calculate actuator setpoints in degrees for i in range(self.joints_count): - servo_setpoint = self.dir[i] * (self.q[i] * 180.0 / math.pi) + self.initial_joints_bias_degree[i] + q_i_degree = self.q[i] * 180.0 / math.pi + dq = q_i_degree - self.geometrical_angles_at_initial_pose_degree[i] + servo_setpoint = self.dir[i] * dq + self.actuator_angles_at_initial_pose_degree[i] max_val = self.servo_actuation_range_degree[i] self.actuator_setpoint_degree[i] = self.clamp(servo_setpoint, i, 0.0, max_val) # Publish actuators setpoint @@ -94,7 +96,8 @@ def declare_params(self): # Declare robot geometry parameters self.declare_parameter('limbs_num', 5) # Default value 5 self.declare_parameter('joints_per_limb', [3]*5) # Default value 3 - self.declare_parameter('i2c_actuators_params.actuator_angle_bias_at_joint_zero_degree', [0.0] * 15) # Default bias + self.declare_parameter('i2c_actuators_params.actuator_angles_at_initial_pose_degree', [0.0] * 15) # Actuator angles at initial pose + self.declare_parameter('i2c_actuators_params.geometrical_angles_at_initial_pose_degree', [0.0] * 15) # Geometrical angles at initial pose self.declare_parameter('i2c_actuators_params.dir', [1.0] * 15) # Default direction (1.0 for no inversion) self.declare_parameter('servo_parameters.servo_actuation_range_degree', [180.0] * 15) # angular range degree self.declare_parameter('servo_parameters.servo_min_pulse_width_microsec', [500.0] * 15) # microseconds @@ -112,16 +115,22 @@ def format_array_to_string(x_list): self.get_logger().info(f'Loaded limbs_num: {self.limbs_num}, joints_per_limb: {format_array_to_string(self.joints_per_limb)}') self.joints_count = sum(self.joints_per_limb) self.get_logger().info(f'Total limbs joints count is: {self.joints_count}') - self.initial_joints_bias_degree = self.get_parameter('i2c_actuators_params.actuator_angle_bias_at_joint_zero_degree').get_parameter_value().double_array_value + self.actuator_angles_at_initial_pose_degree = self.get_parameter('i2c_actuators_params.actuator_angles_at_initial_pose_degree').get_parameter_value().double_array_value + self.geometrical_angles_at_initial_pose_degree = self.get_parameter('i2c_actuators_params.geometrical_angles_at_initial_pose_degree').get_parameter_value().double_array_value self.dir = self.get_parameter('i2c_actuators_params.dir').get_parameter_value().double_array_value self.servo_actuation_range_degree = self.get_parameter('servo_parameters.servo_actuation_range_degree').get_parameter_value().double_array_value self.servo_min_pulse_width_microsec = self.get_parameter('servo_parameters.servo_min_pulse_width_microsec').get_parameter_value().double_array_value self.servo_max_pulse_width_microsec = self.get_parameter('servo_parameters.servo_max_pulse_width_microsec').get_parameter_value().double_array_value - if len(self.initial_joints_bias_degree) != self.joints_count: - self.get_logger().error('ERROR: actuator_angle_bias_at_joint_zero_degree parameter size mismatch!') + if len(self.actuator_angles_at_initial_pose_degree) != self.joints_count: + self.get_logger().error('ERROR: actuator_angles_at_initial_pose_degree parameter size mismatch!') else: - self.get_logger().info(f'Initial joints bias in degree is loaded: {format_array_to_string(self.initial_joints_bias_degree)}') + self.get_logger().info(f'Initial joints bias in degree is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') + + if len(self.geometrical_angles_at_initial_pose_degree) != self.joints_count: + self.get_logger().error('ERROR: geometrical_angles_at_initial_pose_degree parameter size mismatch!') + else: + self.get_logger().info(f'Initial joints bias in degree is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') if len(self.dir) != self.joints_count: self.get_logger().error('ERROR: Direction array size mismatch with joints count!') From bc4c0aa081bda95288d6a58bc849f4dfead0b8f0 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 8 Dec 2024 14:41:07 +0100 Subject: [PATCH 03/39] wip --- commons/include/commons/transform_utils.hpp | 6 +++++- gait_generator/src/gait_generator/gait_generator.cpp | 12 ++++++------ 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/commons/include/commons/transform_utils.hpp b/commons/include/commons/transform_utils.hpp index cc66e10..115e4de 100644 --- a/commons/include/commons/transform_utils.hpp +++ b/commons/include/commons/transform_utils.hpp @@ -52,7 +52,7 @@ auto get_direction_from_vec(const std::vector &vec, double norm) return output_vec; } -auto interpolate_transform(const rclcpp::Node::SharedPtr node, Transform target, +auto interpolate_transform(const rclcpp::Node::SharedPtr /*node*/, Transform target, Transform source, double linear_vel, double /*angular_vel*/, double dt_sec) -> std::optional { @@ -65,9 +65,11 @@ auto interpolate_transform(const rclcpp::Node::SharedPtr node, Transform target, double linear_displacement = linear_vel * dt_sec; if (norm < linear_displacement) { // almost near eachothers + /* RCLCPP_INFO(node->get_logger(), "norm %f is less than the discrete displacement %f ", norm, linear_displacement); + */ interpolated = target; return interpolated; } @@ -123,9 +125,11 @@ auto interpolate_pose(const rclcpp::Node::SharedPtr node, PoseStamped target, double linear_displacement = linear_vel * dt_sec; if (norm < linear_displacement) { + /* RCLCPP_INFO(node->get_logger(), "norm %f is less than the discrete displacement %f", norm, linear_displacement); + */ interpolated = target; return interpolated; } diff --git a/gait_generator/src/gait_generator/gait_generator.cpp b/gait_generator/src/gait_generator/gait_generator.cpp index b97ae0e..bf5cc50 100644 --- a/gait_generator/src/gait_generator/gait_generator.cpp +++ b/gait_generator/src/gait_generator/gait_generator.cpp @@ -81,12 +81,12 @@ void GaitGenerator::cmd_null_pos_sub_callback( body_basefootprint_.translation.z = msg->pose.position.z; // consider the rotation absolute (initial rotation must be the identity) // body_basefootprint_.rotation. = msg->rotation; - RCLCPP_INFO(node_->get_logger(), - "Received nullspace translation from equilibrium (default): " - "displacement.x=%.2f, displacement.y=%.2f, displacement.z=%.2f", - body_basefootprint_.translation.x, - body_basefootprint_.translation.y, - body_basefootprint_.translation.z); + // RCLCPP_INFO(node_->get_logger(), + // "Received nullspace translation from equilibrium (default): " + // "displacement.x=%.2f, displacement.y=%.2f, displacement.z=%.2f", + // body_basefootprint_.translation.x, + // body_basefootprint_.translation.y, + // body_basefootprint_.translation.z); } void GaitGenerator::update_phase(double delta_t_milli) { From bb8f812cd792c12ffcee7a74f0958cb6db8d50ef Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 8 Dec 2024 15:01:17 +0100 Subject: [PATCH 04/39] move initial joints angles into geometrical data --- penta_description/config/general_config.yaml | 14 +++++++------- .../penta_i2c_actuators_node.py | 10 +++++----- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index 92f2deb..0a842ff 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -21,6 +21,13 @@ init_body_basefootprint_transform: [ 0.0, 0.0, 0.158, 0.0, 0.0, 0.0, 1.0 ] + joint_angles_at_initial_pose_degree: [ + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, + 0.0, 0.0, 90.0, + ] gait_parameters: max_gait_linear_speed: 0.035 # meter per sec max_gait_turning_speed: 0.25 # rad per sec @@ -40,13 +47,6 @@ 135.0, 135.0, 60.0, 135.0, 135.0, 60.0, ] - geometrical_angles_at_initial_pose_degree: [ - 0.0, 0.0, 90.0, - 0.0, 0.0, 90.0, - 0.0, 0.0, 90.0, - 0.0, 0.0, 90.0, - 0.0, 0.0, 90.0, - ] dir: [ 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, diff --git a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py index d4dd814..5133c8d 100644 --- a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py +++ b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py @@ -61,7 +61,7 @@ def on_joint_states_callback(self, msg): # Calculate actuator setpoints in degrees for i in range(self.joints_count): q_i_degree = self.q[i] * 180.0 / math.pi - dq = q_i_degree - self.geometrical_angles_at_initial_pose_degree[i] + dq = q_i_degree - self.joint_angles_at_initial_pose_degree[i] servo_setpoint = self.dir[i] * dq + self.actuator_angles_at_initial_pose_degree[i] max_val = self.servo_actuation_range_degree[i] self.actuator_setpoint_degree[i] = self.clamp(servo_setpoint, i, 0.0, max_val) @@ -97,7 +97,7 @@ def declare_params(self): self.declare_parameter('limbs_num', 5) # Default value 5 self.declare_parameter('joints_per_limb', [3]*5) # Default value 3 self.declare_parameter('i2c_actuators_params.actuator_angles_at_initial_pose_degree', [0.0] * 15) # Actuator angles at initial pose - self.declare_parameter('i2c_actuators_params.geometrical_angles_at_initial_pose_degree', [0.0] * 15) # Geometrical angles at initial pose + self.declare_parameter('joint_angles_at_initial_pose_degree', [0.0] * 15) # Geometrical angles at initial pose self.declare_parameter('i2c_actuators_params.dir', [1.0] * 15) # Default direction (1.0 for no inversion) self.declare_parameter('servo_parameters.servo_actuation_range_degree', [180.0] * 15) # angular range degree self.declare_parameter('servo_parameters.servo_min_pulse_width_microsec', [500.0] * 15) # microseconds @@ -116,7 +116,7 @@ def format_array_to_string(x_list): self.joints_count = sum(self.joints_per_limb) self.get_logger().info(f'Total limbs joints count is: {self.joints_count}') self.actuator_angles_at_initial_pose_degree = self.get_parameter('i2c_actuators_params.actuator_angles_at_initial_pose_degree').get_parameter_value().double_array_value - self.geometrical_angles_at_initial_pose_degree = self.get_parameter('i2c_actuators_params.geometrical_angles_at_initial_pose_degree').get_parameter_value().double_array_value + self.joint_angles_at_initial_pose_degree = self.get_parameter('joint_angles_at_initial_pose_degree').get_parameter_value().double_array_value self.dir = self.get_parameter('i2c_actuators_params.dir').get_parameter_value().double_array_value self.servo_actuation_range_degree = self.get_parameter('servo_parameters.servo_actuation_range_degree').get_parameter_value().double_array_value self.servo_min_pulse_width_microsec = self.get_parameter('servo_parameters.servo_min_pulse_width_microsec').get_parameter_value().double_array_value @@ -127,8 +127,8 @@ def format_array_to_string(x_list): else: self.get_logger().info(f'Initial joints bias in degree is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') - if len(self.geometrical_angles_at_initial_pose_degree) != self.joints_count: - self.get_logger().error('ERROR: geometrical_angles_at_initial_pose_degree parameter size mismatch!') + if len(self.joint_angles_at_initial_pose_degree) != self.joints_count: + self.get_logger().error('ERROR: joint_angles_at_initial_pose_degree parameter size mismatch!') else: self.get_logger().info(f'Initial joints bias in degree is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') From c4fd676786f95a91ec8985e1d65a34944b70495b Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 8 Dec 2024 15:04:35 +0100 Subject: [PATCH 05/39] fix print message --- .../penta_i2c_actuators/penta_i2c_actuators_node.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py index 5133c8d..e541ad9 100644 --- a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py +++ b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py @@ -125,12 +125,12 @@ def format_array_to_string(x_list): if len(self.actuator_angles_at_initial_pose_degree) != self.joints_count: self.get_logger().error('ERROR: actuator_angles_at_initial_pose_degree parameter size mismatch!') else: - self.get_logger().info(f'Initial joints bias in degree is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') + self.get_logger().info(f'Actuators angles at initial configuration is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') if len(self.joint_angles_at_initial_pose_degree) != self.joints_count: self.get_logger().error('ERROR: joint_angles_at_initial_pose_degree parameter size mismatch!') else: - self.get_logger().info(f'Initial joints bias in degree is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') + self.get_logger().info(f'Joints angles at initial configuration is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') if len(self.dir) != self.joints_count: self.get_logger().error('ERROR: Direction array size mismatch with joints count!') From 1de426568c340d6fd52dd4f93d9fc7475f2b908c Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 8 Dec 2024 15:12:45 +0100 Subject: [PATCH 06/39] fix message --- .../penta_i2c_actuators/penta_i2c_actuators_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py index e541ad9..14714eb 100644 --- a/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py +++ b/penta_i2c_actuators/penta_i2c_actuators/penta_i2c_actuators_node.py @@ -130,7 +130,7 @@ def format_array_to_string(x_list): if len(self.joint_angles_at_initial_pose_degree) != self.joints_count: self.get_logger().error('ERROR: joint_angles_at_initial_pose_degree parameter size mismatch!') else: - self.get_logger().info(f'Joints angles at initial configuration is loaded: {format_array_to_string(self.actuator_angles_at_initial_pose_degree)}') + self.get_logger().info(f'Joints angles at initial configuration is loaded: {format_array_to_string(self.joint_angles_at_initial_pose_degree)}') if len(self.dir) != self.joints_count: self.get_logger().error('ERROR: Direction array size mismatch with joints count!') From 1f4d0c26a26d37abb01e0eaf3cb7eac2dbabc2a2 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 8 Dec 2024 20:11:32 +0100 Subject: [PATCH 07/39] remove twerk for now --- penta_pod/launch/penta_sim_rviz.launch.py | 24 ++++++++--------- .../launch/realhardware_bringup.launch.py | 26 +++++++++---------- 2 files changed, 25 insertions(+), 25 deletions(-) diff --git a/penta_pod/launch/penta_sim_rviz.launch.py b/penta_pod/launch/penta_sim_rviz.launch.py index 2373075..8335d96 100644 --- a/penta_pod/launch/penta_sim_rviz.launch.py +++ b/penta_pod/launch/penta_sim_rviz.launch.py @@ -35,24 +35,24 @@ def generate_launch_description(): ) # Include the null space cmd publisher launch file - null_space_publisher = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'null_pose_publisher.launch.py') - ) - ) + # null_space_publisher = IncludeLaunchDescription( + # PythonLaunchDescriptionSource( + # os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'null_pose_publisher.launch.py') + # ) + # ) # Include the twerk action server launch file - twerk_action_server = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'base_twerk_action_server.launch.py') - ) - ) + # twerk_action_server = IncludeLaunchDescription( + # PythonLaunchDescriptionSource( + # os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'base_twerk_action_server.launch.py') + # ) + # ) return LaunchDescription([ rviz_penta_pod_launch, penta_pod_launch, gait_generator_launch, joints_aggregator_launch, - null_space_publisher, - twerk_action_server + # null_space_publisher, + # twerk_action_server ]) diff --git a/penta_pod/launch/realhardware_bringup.launch.py b/penta_pod/launch/realhardware_bringup.launch.py index ccfd767..be9c69d 100644 --- a/penta_pod/launch/realhardware_bringup.launch.py +++ b/penta_pod/launch/realhardware_bringup.launch.py @@ -43,19 +43,19 @@ def generate_launch_description(): launch_arguments={'mode': mode}.items() # Pass the mode argument ) - # Include the null space cmd publisher launch file - null_space_publisher = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'null_pose_publisher.launch.py') - ) - ) + # Include the null space cmd publisher launch file + # null_space_publisher = IncludeLaunchDescription( + # PythonLaunchDescriptionSource( + # os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'null_pose_publisher.launch.py') + # ) + # ) # Include the twerk action server launch file - twerk_action_server = IncludeLaunchDescription( - PythonLaunchDescriptionSource( - os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'base_twerk_action_server.launch.py') - ) - ) + # twerk_action_server = IncludeLaunchDescription( + # PythonLaunchDescriptionSource( + # os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'base_twerk_action_server.launch.py') + # ) + # ) return LaunchDescription([ mode_arg, @@ -63,6 +63,6 @@ def generate_launch_description(): gait_generator_launch, joints_aggregator_launch, penta_i2c_actuators_launch, - null_space_publisher, - twerk_action_server + # null_space_publisher, + # twerk_action_server ]) From 5a7cdc1453666e65da5be3abb036b004e7502db1 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sat, 14 Dec 2024 22:57:59 +0100 Subject: [PATCH 08/39] calibrated parameters --- penta_description/config/general_config.yaml | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index 0a842ff..92cd672 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -41,18 +41,18 @@ tracking_angular_velocity: 1.0 # [rad/sec] i2c_actuators_params: actuator_angles_at_initial_pose_degree: [ - 135.0, 135.0, 60.0, - 135.0, 135.0, 60.0, - 135.0, 135.0, 60.0, - 135.0, 135.0, 60.0, - 135.0, 135.0, 60.0, + 135.0, 146.0, 87.0, + 135.0, 138.0, 87.0, + 135.0, 138.0, 87.0, + 135.0, 131.0, 91.0, + 135.0, 131.0, 83.0, ] dir: [ - 1.0, 1.0, 1.0, - 1.0, 1.0, 1.0, - 1.0, 1.0, 1.0, - 1.0, 1.0, 1.0, - 1.0, 1.0, 1.0, + 1.0, -1.0, -1.0, + 1.0, -1.0, -1.0, + 1.0, -1.0, -1.0, + 1.0, -1.0, -1.0, + 1.0, -1.0, -1.0, ] servo_parameters: servo_actuation_range_degree: [ # servo angle range From 850c8bd6ba83444f60a21523b3f3744048886366 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 15 Dec 2024 00:58:29 +0100 Subject: [PATCH 09/39] change gait patterns --- commons/include/commons/transform_utils.hpp | 8 +- gait_generator/CMakeLists.txt | 2 + .../include/gait_generator/gait_generator.hpp | 23 +++ gait_generator/package.xml | 1 + .../src/gait_generator/gait_generator.cpp | 164 ++++++++++++++---- interfaces/gait_generator_msgs/CMakeLists.txt | 27 +++ interfaces/gait_generator_msgs/package.xml | 27 +++ .../srv/SetGaitPattern.srv | 6 + penta_description/config/general_config.yaml | 7 + 9 files changed, 226 insertions(+), 39 deletions(-) create mode 100644 interfaces/gait_generator_msgs/CMakeLists.txt create mode 100644 interfaces/gait_generator_msgs/package.xml create mode 100644 interfaces/gait_generator_msgs/srv/SetGaitPattern.srv diff --git a/commons/include/commons/transform_utils.hpp b/commons/include/commons/transform_utils.hpp index 115e4de..1a565fb 100644 --- a/commons/include/commons/transform_utils.hpp +++ b/commons/include/commons/transform_utils.hpp @@ -52,10 +52,10 @@ auto get_direction_from_vec(const std::vector &vec, double norm) return output_vec; } -auto interpolate_transform(const rclcpp::Node::SharedPtr /*node*/, Transform target, - Transform source, double linear_vel, - double /*angular_vel*/, double dt_sec) - -> std::optional { +auto interpolate_transform(const rclcpp::Node::SharedPtr /*node*/, + Transform target, Transform source, + double linear_vel, double /*angular_vel*/, + double dt_sec) -> std::optional { Transform interpolated{}; diff --git a/gait_generator/CMakeLists.txt b/gait_generator/CMakeLists.txt index f7e3d0d..aa8adbb 100644 --- a/gait_generator/CMakeLists.txt +++ b/gait_generator/CMakeLists.txt @@ -16,6 +16,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(limb_msgs REQUIRED) find_package(geometry_msgs REQUIRED) +find_package(gait_generator_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) @@ -34,6 +35,7 @@ ament_target_dependencies(${PROJECT_NAME} std_msgs geometry_msgs limb_msgs + gait_generator_msgs tf2 tf2_geometry_msgs ) diff --git a/gait_generator/include/gait_generator/gait_generator.hpp b/gait_generator/include/gait_generator/gait_generator.hpp index 70c74e8..380cfa1 100644 --- a/gait_generator/include/gait_generator/gait_generator.hpp +++ b/gait_generator/include/gait_generator/gait_generator.hpp @@ -5,6 +5,7 @@ #include // include messages +#include "gait_generator_msgs/srv/set_gait_pattern.hpp" #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/transform.hpp" @@ -21,6 +22,8 @@ namespace penta_pod::kin::gait_generator { +using SetGaitPattern = gait_generator_msgs::srv::SetGaitPattern; + inline auto double_to_string_formatted(double number, int digits_after_point) -> std::string { std::ostringstream oss; @@ -35,8 +38,26 @@ class GaitGenerator { std::vector q_state; double current_phase_, max_gait_linear_speed_, max_gait_turning_speed_; + bool is_walking_{false}; int feet_num_; + struct GatiPatterns { + int active_gait_index_ = 0; + int gaits_num_ = 0; + std::vector> patterns_; + std::vector get_active_pattern() { + return patterns_[active_gait_index_]; + } + bool set_active_pattern(int i) { + if (i < 0) + return false; + if (i >= gaits_num_) + return false; + active_gait_index_ = i; + return true; + } + } gait_patterns_; + std::vector legs_body_transforms_; geometry_msgs::msg::Transform body_basefootprint_; @@ -58,6 +79,8 @@ class GaitGenerator { rclcpp::TimerBase::SharedPtr timer_; geometry_msgs::msg::Twist cmd_vel_{}; + rclcpp::Service::SharedPtr set_gait_pattern_server_; + void create_set_gait_pattern_service(); void declare_parameters(); void load_parameters(); void timer_callback(double delta_t_milli); diff --git a/gait_generator/package.xml b/gait_generator/package.xml index 733f927..a5609d4 100644 --- a/gait_generator/package.xml +++ b/gait_generator/package.xml @@ -13,6 +13,7 @@ std_msgs geometry_msgs limb_msgs + gait_generator_msgs launch_testing tf2 tf2_geometry_msgs diff --git a/gait_generator/src/gait_generator/gait_generator.cpp b/gait_generator/src/gait_generator/gait_generator.cpp index bf5cc50..6d09da6 100644 --- a/gait_generator/src/gait_generator/gait_generator.cpp +++ b/gait_generator/src/gait_generator/gait_generator.cpp @@ -50,6 +50,44 @@ GaitGenerator::GaitGenerator() timer_ = node_->create_wall_timer( std::chrono::milliseconds(static_cast(delta_t_milli)), [this, delta_t_milli]() { timer_callback(delta_t_milli); }); + + create_set_gait_pattern_service(); +} + +void GaitGenerator::create_set_gait_pattern_service() { + auto lambda = + [this](const SetGaitPattern::Request::SharedPtr &request, + const SetGaitPattern::Response::SharedPtr &response) -> bool { + int pattern = request->pattern; + if (is_walking_) { + std::string error_message = + "Can not change gait pattern while the robot is moving"; + RCLCPP_WARN(node_->get_logger(), error_message.c_str()); + response->message = error_message; + response->success = false; + return true; + } + if (!gait_patterns_.set_active_pattern(pattern)) { + std::string error_message = "Could not set gait pattern to " + + std::to_string(pattern) + + ", make sure u r using a valid value"; + RCLCPP_WARN(node_->get_logger(), error_message.c_str()); + response->message = error_message; + response->success = false; + return true; + } + std::string message = + "Changed successfully to gait pattern: " + std::to_string(pattern); + response->message = message; + response->success = true; + return true; + }; + + set_gait_pattern_server_ = node_->create_service( + "gait_generator/set_gait_pattern", lambda, + rmw_qos_profile_services_default, + node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive)); } void GaitGenerator::cmd_vel_sub_callback( @@ -83,8 +121,8 @@ void GaitGenerator::cmd_null_pos_sub_callback( // body_basefootprint_.rotation. = msg->rotation; // RCLCPP_INFO(node_->get_logger(), // "Received nullspace translation from equilibrium (default): " - // "displacement.x=%.2f, displacement.y=%.2f, displacement.z=%.2f", - // body_basefootprint_.translation.x, + // "displacement.x=%.2f, displacement.y=%.2f, + // displacement.z=%.2f", body_basefootprint_.translation.x, // body_basefootprint_.translation.y, // body_basefootprint_.translation.z); } @@ -114,6 +152,7 @@ void GaitGenerator::update_phase(double delta_t_milli) { current_phase_ = std::floor(current_phase_ / (2 * pi)) * 2 * pi; } } + is_walking_ = (w == 0.0) ? false : true; current_phase_ = current_phase_ + w * delta_t_sec; } @@ -125,41 +164,44 @@ void GaitGenerator::update_feet_positions(double delta_t_milli) { double dy = cmd_vel_.linear.y * delta_t_sec; double d_theta = cmd_vel_.angular.z * delta_t_sec; double b = 0.05; - + auto gait_pattern = gait_patterns_.get_active_pattern(); for (int i = 0; i < feet_num_; i++) { - auto temp = - foot_pos_z_generator(b, current_phase_, phase_shift_vec_[i], feet_num_); + int foot_index = gait_pattern[i]; + auto temp = foot_pos_z_generator(b, current_phase_, + phase_shift_vec_[foot_index], feet_num_); if (temp == 0.) { - double x = feet_pos_in_footprint_[i].x; - double y = feet_pos_in_footprint_[i].y; - feet_pos_in_footprint_[i].x = x + dx - d_theta * y; - feet_pos_in_footprint_[i].y = y + dy + d_theta * x; - feet_pos_in_footprint_[i].z = 0.; - final_displacement_[i].x = - feet_pos_in_footprint_[i].x - init_feet_pos_in_footprint_[i].x; - final_displacement_[i].y = - feet_pos_in_footprint_[i].y - init_feet_pos_in_footprint_[i].y; + double x = feet_pos_in_footprint_[foot_index].x; + double y = feet_pos_in_footprint_[foot_index].y; + feet_pos_in_footprint_[foot_index].x = x + dx - d_theta * y; + feet_pos_in_footprint_[foot_index].y = y + dy + d_theta * x; + feet_pos_in_footprint_[foot_index].z = 0.; + final_displacement_[foot_index].x = + feet_pos_in_footprint_[foot_index].x - + init_feet_pos_in_footprint_[foot_index].x; + final_displacement_[foot_index].y = + feet_pos_in_footprint_[foot_index].y - + init_feet_pos_in_footprint_[foot_index].y; } else { - feet_pos_in_footprint_[i].x = - init_feet_pos_in_footprint_[i].x + - foot_pos_xy_generator(current_phase_, phase_shift_vec_[i], - final_displacement_[i].x, feet_num_); - feet_pos_in_footprint_[i].y = - init_feet_pos_in_footprint_[i].y + - foot_pos_xy_generator(current_phase_, phase_shift_vec_[i], - final_displacement_[i].y, feet_num_); - feet_pos_in_footprint_[i].z = temp; + feet_pos_in_footprint_[foot_index].x = + init_feet_pos_in_footprint_[foot_index].x + + foot_pos_xy_generator(current_phase_, phase_shift_vec_[foot_index], + final_displacement_[foot_index].x, feet_num_); + feet_pos_in_footprint_[foot_index].y = + init_feet_pos_in_footprint_[foot_index].y + + foot_pos_xy_generator(current_phase_, phase_shift_vec_[foot_index], + final_displacement_[foot_index].y, feet_num_); + feet_pos_in_footprint_[foot_index].z = temp; } if (i < static_cast(legs_body_transforms_.size())) { - auto point = - applyInverseTransform(feet_pos_in_footprint_[i], body_basefootprint_); - point = applyInverseTransform(point, legs_body_transforms_[i]); + auto point = applyInverseTransform(feet_pos_in_footprint_[foot_index], + body_basefootprint_); + point = applyInverseTransform(point, legs_body_transforms_[foot_index]); limb_msgs::msg::Pxyz xyz_msg; xyz_msg.x = point.x; xyz_msg.y = point.y; xyz_msg.z = point.z; - xyz_publishers_[i]->publish(xyz_msg); + xyz_publishers_[foot_index]->publish(xyz_msg); } else { RCLCPP_ERROR_STREAM(node_->get_logger(), "No transform available for limb " << i); @@ -182,6 +224,9 @@ void GaitGenerator::declare_parameters() { "init_body_basefootprint_transform", std::vector{}); node_->declare_parameter("gait_parameters.max_gait_linear_speed"); node_->declare_parameter("gait_parameters.max_gait_turning_speed"); + node_->declare_parameter("gait_parameters.gait_patterns.num"); + node_->declare_parameter>( + "gait_parameters.gait_patterns.feet_order", std::vector{}); } void GaitGenerator::load_parameters() { @@ -195,14 +240,14 @@ void GaitGenerator::load_parameters() { }; // Helper function to validate vector size - auto validate_vector_size = [this](const std::vector &vec, - int expected_size, - const std::string &error_message) { - if (static_cast(vec.size()) != expected_size) { - RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); - throw std::runtime_error(error_message); - } - }; + auto validate_vector_size = + [this](const std::vector &vec, int expected_size, + const std::string &error_message) { + if (static_cast(vec.size()) != expected_size) { + RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); + throw std::runtime_error(error_message); + } + }; // Helper function to create a transform from values auto array_to_transform = @@ -299,6 +344,55 @@ void GaitGenerator::load_parameters() { node_->get_logger(), "Loaded gait_parameters.max_gait_turning_speed value is: %f [rad/sec]", max_gait_turning_speed_); + + // load gait patterns + load_param("gait_parameters.gait_patterns.num", gait_patterns_.gaits_num_, + "Parameter gait_parameters.gait_patterns.num was not found."); + RCLCPP_INFO(node_->get_logger(), + "Loaded gait_parameters.gait_patterns value is: %d", + gait_patterns_.gaits_num_); + + std::vector vector_gait_patterns; + load_param("gait_parameters.gait_patterns.feet_order", vector_gait_patterns, + "No init gait_parameters.gait_patterns.feet_order found."); + int assert_vector_size = feet_num_ * gait_patterns_.gaits_num_; + std::string if_error_message = + "Size of gait_parameters.gait_patterns.feet_order must be " + + std::to_string(assert_vector_size); + validate_vector_size(vector_gait_patterns, assert_vector_size, + if_error_message); + // Populate the patterns. + int count = 0; + gait_patterns_.patterns_.resize( + gait_patterns_.gaits_num_); // resize to number of gaits + for (int i = 0; i < gait_patterns_.gaits_num_; i++) { + gait_patterns_.patterns_[i].resize(feet_num_); // resize to fit the feet + std::string log_message = + "Loaded gait_pattern [" + std::to_string(i) + "]: "; + for (int j = 0; j < feet_num_; j++) { + int temp = vector_gait_patterns[count]; + if (temp < 0) { + std::string error_message = + "Foot index at gait_parameters.gait_patterns.feet_order[" + + std::to_string(count) + "] shall not be less than zero"; + throw std::runtime_error(error_message); + } + if (temp >= feet_num_) { + std::string error_message = + "Foot index at gait_parameters.gait_patterns.feet_order[" + + std::to_string(count) + + "] shall not be more nor equal to the number of feet, specified " + "as " + + std::to_string(feet_num_); + throw std::runtime_error(error_message); + } + int foot_index = vector_gait_patterns[count]; + log_message = log_message + std::to_string(foot_index) + " |"; + gait_patterns_.patterns_[i][j] = foot_index; + count++; + } + RCLCPP_INFO(node_->get_logger(), log_message.c_str()); + } } } // namespace penta_pod::kin::gait_generator diff --git a/interfaces/gait_generator_msgs/CMakeLists.txt b/interfaces/gait_generator_msgs/CMakeLists.txt new file mode 100644 index 0000000..58edd4c --- /dev/null +++ b/interfaces/gait_generator_msgs/CMakeLists.txt @@ -0,0 +1,27 @@ +cmake_minimum_required(VERSION 3.12) +project(gait_generator_msgs) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Werror -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(std_msgs REQUIRED) +find_package(rosidl_default_generators REQUIRED) +find_package(geometry_msgs REQUIRED) + +rosidl_generate_interfaces(${PROJECT_NAME} + "srv/SetGaitPattern.srv" + DEPENDENCIES + builtin_interfaces + std_msgs + geometry_msgs + ADD_LINTER_TESTS + ) + +if(BUILD_TESTING) +endif() + +ament_export_dependencies(rosidl_default_runtime) +ament_package() diff --git a/interfaces/gait_generator_msgs/package.xml b/interfaces/gait_generator_msgs/package.xml new file mode 100644 index 0000000..b6115d8 --- /dev/null +++ b/interfaces/gait_generator_msgs/package.xml @@ -0,0 +1,27 @@ + + + + gait_generator_msgs + 0.0.0 + TODO: Package description + mohammad.safeea + TODO: License declaration + + ament_cmake + + rosidl_default_generators + + std_msgs + geometry_msgs + + rosidl_default_runtime + + rosidl_interface_packages + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/interfaces/gait_generator_msgs/srv/SetGaitPattern.srv b/interfaces/gait_generator_msgs/srv/SetGaitPattern.srv new file mode 100644 index 0000000..34555fc --- /dev/null +++ b/interfaces/gait_generator_msgs/srv/SetGaitPattern.srv @@ -0,0 +1,6 @@ +uint8 pattern +--- +bool success +string message + + diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index 92cd672..e4ed37f 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -31,6 +31,13 @@ gait_parameters: max_gait_linear_speed: 0.035 # meter per sec max_gait_turning_speed: 0.25 # rad per sec + gait_patterns: + num: 3 + feet_order: [ + 0, 1, 2, 3, 4, + 0, 2, 4, 1, 3, + 0, 4, 3, 2, 1 + ] joints_aggregator: joints_update_interval_millis: 50 base_twerk: From d7a7b3c7354b1a33fed72e0e9432d26d8947a0de Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 15 Dec 2024 01:23:51 +0100 Subject: [PATCH 10/39] wip --- gait_generator/README.md | 11 +++++++++++ .../include/gait_generator/gait_generator.hpp | 2 ++ gait_generator/src/gait_generator/gait_generator.cpp | 7 +++---- 3 files changed, 16 insertions(+), 4 deletions(-) create mode 100644 gait_generator/README.md diff --git a/gait_generator/README.md b/gait_generator/README.md new file mode 100644 index 0000000..373fc0a --- /dev/null +++ b/gait_generator/README.md @@ -0,0 +1,11 @@ +# Gait generator + + +Generates the gait after listining on /cmd_vel + + +To change the gait patten, the following service is used + +``` +ros2 service call gait_generator/set_gait_pattern gait_generator_msgs/srv/SetGaitPattern "{"pattern": 1}" +``` \ No newline at end of file diff --git a/gait_generator/include/gait_generator/gait_generator.hpp b/gait_generator/include/gait_generator/gait_generator.hpp index 380cfa1..2a0bfb4 100644 --- a/gait_generator/include/gait_generator/gait_generator.hpp +++ b/gait_generator/include/gait_generator/gait_generator.hpp @@ -80,7 +80,9 @@ class GaitGenerator { geometry_msgs::msg::Twist cmd_vel_{}; rclcpp::Service::SharedPtr set_gait_pattern_server_; + rclcpp::CallbackGroup::SharedPtr service_callback_group_; void create_set_gait_pattern_service(); + void declare_parameters(); void load_parameters(); void timer_callback(double delta_t_milli); diff --git a/gait_generator/src/gait_generator/gait_generator.cpp b/gait_generator/src/gait_generator/gait_generator.cpp index 6d09da6..3aaa33b 100644 --- a/gait_generator/src/gait_generator/gait_generator.cpp +++ b/gait_generator/src/gait_generator/gait_generator.cpp @@ -82,12 +82,11 @@ void GaitGenerator::create_set_gait_pattern_service() { response->success = true; return true; }; - + service_callback_group_ = node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive); set_gait_pattern_server_ = node_->create_service( "gait_generator/set_gait_pattern", lambda, - rmw_qos_profile_services_default, - node_->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive)); + rmw_qos_profile_services_default, service_callback_group_); } void GaitGenerator::cmd_vel_sub_callback( From a81e6543677d29ce357f0a3991fb51b390233e51 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Mon, 30 Dec 2024 22:50:35 +0100 Subject: [PATCH 11/39] wip --- .../include/gait_generator/gait_generator.hpp | 8 ++++++++ .../src/gait_generator/gait_generator.cpp | 20 +++++++++++-------- 2 files changed, 20 insertions(+), 8 deletions(-) diff --git a/gait_generator/include/gait_generator/gait_generator.hpp b/gait_generator/include/gait_generator/gait_generator.hpp index 2a0bfb4..bd5b956 100644 --- a/gait_generator/include/gait_generator/gait_generator.hpp +++ b/gait_generator/include/gait_generator/gait_generator.hpp @@ -56,6 +56,14 @@ class GaitGenerator { active_gait_index_ = i; return true; } + std::string active_pattern_to_string() { + auto active_pattern = get_active_pattern(); + std::string log_message = "Feet pattern: "; + for (auto foot_index : active_pattern) { + log_message = log_message + std::to_string(foot_index) + " |"; + } + return log_message; + } } gait_patterns_; std::vector legs_body_transforms_; diff --git a/gait_generator/src/gait_generator/gait_generator.cpp b/gait_generator/src/gait_generator/gait_generator.cpp index 3aaa33b..a477630 100644 --- a/gait_generator/src/gait_generator/gait_generator.cpp +++ b/gait_generator/src/gait_generator/gait_generator.cpp @@ -76,10 +76,14 @@ void GaitGenerator::create_set_gait_pattern_service() { response->success = false; return true; } - std::string message = + std::string info_message = "Changed successfully to gait pattern: " + std::to_string(pattern); - response->message = message; + RCLCPP_INFO(node_->get_logger(), info_message.c_str()); + response->message = info_message; response->success = true; + + auto log_message = gait_patterns_.active_pattern_to_string(); + RCLCPP_INFO(node_->get_logger(), log_message.c_str()); return true; }; service_callback_group_ = node_->create_callback_group( @@ -165,9 +169,9 @@ void GaitGenerator::update_feet_positions(double delta_t_milli) { double b = 0.05; auto gait_pattern = gait_patterns_.get_active_pattern(); for (int i = 0; i < feet_num_; i++) { - int foot_index = gait_pattern[i]; + auto foot_index = gait_pattern[i]; auto temp = foot_pos_z_generator(b, current_phase_, - phase_shift_vec_[foot_index], feet_num_); + phase_shift_vec_[i], feet_num_); if (temp == 0.) { double x = feet_pos_in_footprint_[foot_index].x; double y = feet_pos_in_footprint_[foot_index].y; @@ -183,15 +187,15 @@ void GaitGenerator::update_feet_positions(double delta_t_milli) { } else { feet_pos_in_footprint_[foot_index].x = init_feet_pos_in_footprint_[foot_index].x + - foot_pos_xy_generator(current_phase_, phase_shift_vec_[foot_index], + foot_pos_xy_generator(current_phase_, phase_shift_vec_[i], final_displacement_[foot_index].x, feet_num_); feet_pos_in_footprint_[foot_index].y = init_feet_pos_in_footprint_[foot_index].y + - foot_pos_xy_generator(current_phase_, phase_shift_vec_[foot_index], + foot_pos_xy_generator(current_phase_, phase_shift_vec_[i], final_displacement_[foot_index].y, feet_num_); feet_pos_in_footprint_[foot_index].z = temp; } - if (i < static_cast(legs_body_transforms_.size())) { + if (foot_index < static_cast(legs_body_transforms_.size())) { auto point = applyInverseTransform(feet_pos_in_footprint_[foot_index], body_basefootprint_); point = applyInverseTransform(point, legs_body_transforms_[foot_index]); @@ -203,7 +207,7 @@ void GaitGenerator::update_feet_positions(double delta_t_milli) { xyz_publishers_[foot_index]->publish(xyz_msg); } else { RCLCPP_ERROR_STREAM(node_->get_logger(), - "No transform available for limb " << i); + "No transform available for limb " << foot_index); } } } From cb2c36f2d32da252f28e27a55e309087fa21d6e8 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Tue, 31 Dec 2024 22:37:48 +0100 Subject: [PATCH 12/39] floating base --- .../include/gait_generator/gait_generator.hpp | 1 + .../src/gait_generator/gait_generator.cpp | 13 +++++++++++++ penta_description/urdf/penta.urdf.xacro | 2 +- 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/gait_generator/include/gait_generator/gait_generator.hpp b/gait_generator/include/gait_generator/gait_generator.hpp index bd5b956..5f2aa3d 100644 --- a/gait_generator/include/gait_generator/gait_generator.hpp +++ b/gait_generator/include/gait_generator/gait_generator.hpp @@ -100,6 +100,7 @@ class GaitGenerator { void update_phase(double delta_t_milli); void update_feet_positions(double delta_t_milli); + void publish_base_to_basefootprint_transform(); // move feet up (z up) calculation double foot_pos_z_generator(double b, double q, double phase_shift, int n) { diff --git a/gait_generator/src/gait_generator/gait_generator.cpp b/gait_generator/src/gait_generator/gait_generator.cpp index a477630..0a5d031 100644 --- a/gait_generator/src/gait_generator/gait_generator.cpp +++ b/gait_generator/src/gait_generator/gait_generator.cpp @@ -13,6 +13,8 @@ #include #include +#include "tf2_ros/transform_broadcaster.h" + #include #define pi 3.141592 @@ -54,6 +56,16 @@ GaitGenerator::GaitGenerator() create_set_gait_pattern_service(); } +void GaitGenerator::publish_base_to_basefootprint_transform() { + geometry_msgs::msg::TransformStamped transformStamped; + transformStamped.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now(); + transformStamped.header.frame_id = "base_footprint"; + transformStamped.child_frame_id = "base_link"; + transformStamped.transform = body_basefootprint_; + static auto br = std::make_shared(node_); + br->sendTransform(transformStamped); +} + void GaitGenerator::create_set_gait_pattern_service() { auto lambda = [this](const SetGaitPattern::Request::SharedPtr &request, @@ -215,6 +227,7 @@ void GaitGenerator::update_feet_positions(double delta_t_milli) { void GaitGenerator::timer_callback(double delta_t_milli) { update_phase(delta_t_milli); update_feet_positions(delta_t_milli); + publish_base_to_basefootprint_transform(); } void GaitGenerator::declare_parameters() { diff --git a/penta_description/urdf/penta.urdf.xacro b/penta_description/urdf/penta.urdf.xacro index 22ba5fe..ce2c466 100644 --- a/penta_description/urdf/penta.urdf.xacro +++ b/penta_description/urdf/penta.urdf.xacro @@ -13,7 +13,7 @@ - + From 80a71dbe73e160d5e2b47501a74f9115954d649a Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Tue, 31 Dec 2024 22:52:04 +0100 Subject: [PATCH 13/39] wip --- .../launch/penta_sim_full_rviz.launch.py | 58 +++++++++++++++++++ 1 file changed, 58 insertions(+) create mode 100644 penta_pod/launch/penta_sim_full_rviz.launch.py diff --git a/penta_pod/launch/penta_sim_full_rviz.launch.py b/penta_pod/launch/penta_sim_full_rviz.launch.py new file mode 100644 index 0000000..2373075 --- /dev/null +++ b/penta_pod/launch/penta_sim_full_rviz.launch.py @@ -0,0 +1,58 @@ +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.substitutions import FindPackageShare +from launch.substitutions import LaunchConfiguration +import os + +def generate_launch_description(): + # Include RVIZ launch file + rviz_penta_pod_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(FindPackageShare('penta_pod').find('penta_pod'), 'launch', 'penta_rviz.launch.py') + ) + ) + + # Include the penta_pod launch file + penta_pod_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(FindPackageShare('penta_pod').find('penta_pod'), 'launch', 'penta_pod.launch.py') + ) + ) + + # Include the gait_generator launch file + gait_generator_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(FindPackageShare('gait_generator').find('gait_generator'), 'launch', 'gait_generator.launch.py') + ) + ) + + # Include the joints_aggregator launch file + joints_aggregator_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(FindPackageShare('joints_aggregator').find('joints_aggregator'), 'launch', 'joints_aggregator.launch.py') + ) + ) + + # Include the null space cmd publisher launch file + null_space_publisher = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'null_pose_publisher.launch.py') + ) + ) + + # Include the twerk action server launch file + twerk_action_server = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(FindPackageShare('base_twerk').find('base_twerk'), 'launch', 'base_twerk_action_server.launch.py') + ) + ) + + return LaunchDescription([ + rviz_penta_pod_launch, + penta_pod_launch, + gait_generator_launch, + joints_aggregator_launch, + null_space_publisher, + twerk_action_server + ]) From e24abf8226f3ffd404746aa5151a7b78a48ae1d8 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 10:25:29 +0100 Subject: [PATCH 14/39] wip --- .../base_twerk/base_twerk_action_server.cpp | 20 +++++++++++++------ .../action/BaseTwerkAction.action | 11 +++++----- penta_description/config/general_config.yaml | 4 ++-- 3 files changed, 21 insertions(+), 14 deletions(-) diff --git a/base_twerk/src/base_twerk/base_twerk_action_server.cpp b/base_twerk/src/base_twerk/base_twerk_action_server.cpp index 7576294..9e2bcbf 100644 --- a/base_twerk/src/base_twerk/base_twerk_action_server.cpp +++ b/base_twerk/src/base_twerk/base_twerk_action_server.cpp @@ -66,7 +66,7 @@ auto BaseTwerkActionServer::execute( auto result = std::make_shared(); double mag_displacement = std::sqrt( - goal->rx * goal->rx + goal->ry * goal->ry + goal->rz * goal->rz); + goal->r[0] * goal->r[0] + goal->r[1] * goal->r[1] + goal->r[2] * goal->r[2]); if (mag_displacement > max_permissible_displacement_meter_) { auto message = "Action aborted for the specified displacement is: " + std::to_string(mag_displacement) + @@ -130,9 +130,9 @@ auto BaseTwerkActionServer::execute( while (rclcpp::ok()) { rate.sleep(); - auto current_pose = + auto updated_pose = calculate_twerk_pose_from_goal(start_time, start_pose, goal_handle); - if (!call_setpoint_client(current_pose)) { + if (!call_setpoint_client(updated_pose)) { return; } @@ -148,6 +148,9 @@ auto BaseTwerkActionServer::execute( } if (goal_handle->is_canceling()) { + if (!call_setpoint_client(start_pose)) { + return; + } result->result_message = "action canceled"; goal_handle->canceled(result); RCLCPP_INFO(node_->get_logger(), "Goal canceled"); @@ -166,13 +169,18 @@ auto BaseTwerkActionServer::calculate_twerk_pose_from_goal( pose.pose.position.x = start_pose.pose.position.x + - goal->rx * sin(goal->w * delta_t_seconds + goal->phi_x); + goal->r[0] * sin(goal->w * delta_t_seconds + goal->phi[0]); pose.pose.position.y = start_pose.pose.position.y + - goal->ry * sin(goal->w * delta_t_seconds + goal->phi_y); + goal->r[1] * sin(goal->w * delta_t_seconds + goal->phi[1]); pose.pose.position.z = start_pose.pose.position.z + - goal->rz * sin(goal->w * delta_t_seconds + goal->phi_z); + goal->r[2] * sin(goal->w * delta_t_seconds + goal->phi[2]); + + std::vector rpy = {0., 0., 0.}; + for (int i = 3; i < 6; i++) { + rpy[i-3] = goal->r[i] * sin(goal->w * delta_t_seconds + goal->phi[i]); + } return pose; } diff --git a/interfaces/base_twerk_msgs/action/BaseTwerkAction.action b/interfaces/base_twerk_msgs/action/BaseTwerkAction.action index df0d8ce..318a202 100644 --- a/interfaces/base_twerk_msgs/action/BaseTwerkAction.action +++ b/interfaces/base_twerk_msgs/action/BaseTwerkAction.action @@ -1,9 +1,8 @@ -float64 rx -float64 ry -float64 rz -float64 phi_x -float64 phi_y -float64 phi_z +# pose displacement +float64[6] r # [rx, ry, rz, roll, pitch, yaw] +# phase shift +float64[6] phi # [phi_x, phi_y, phi_z, phi_roll, phi_pitch, phi_yaw] +# motion frequency and duration float64 w float64 dance_time_millis --- diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index e4ed37f..e91e696 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -34,9 +34,9 @@ gait_patterns: num: 3 feet_order: [ + 0, 4, 3, 2, 1, 0, 1, 2, 3, 4, - 0, 2, 4, 1, 3, - 0, 4, 3, 2, 1 + 0, 2, 4, 1, 3 ] joints_aggregator: joints_update_interval_millis: 50 From 77a2f7e25c43a9ac20d09770f6e29f83b6daf160 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 13:22:13 +0100 Subject: [PATCH 15/39] orientation of target --- commons/include/commons/transform_utils.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/commons/include/commons/transform_utils.hpp b/commons/include/commons/transform_utils.hpp index 1a565fb..eb5b79f 100644 --- a/commons/include/commons/transform_utils.hpp +++ b/commons/include/commons/transform_utils.hpp @@ -147,7 +147,8 @@ auto interpolate_pose(const rclcpp::Node::SharedPtr node, PoseStamped target, interpolated.pose.position.z = source.pose.position.z + dir[2] * linear_displacement; - interpolated.pose.orientation = source.pose.orientation; + // ToDo interpolate orientation + interpolated.pose.orientation = target.pose.orientation; return interpolated; } From 7cd0fec0ef314a4ee2cd7e7fcc32f8a24c2db38b Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 13:22:36 +0100 Subject: [PATCH 16/39] compile quatrenions utils --- commons/src/commons/librarry.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/commons/src/commons/librarry.cpp b/commons/src/commons/librarry.cpp index 4ca31e7..f6a7c4a 100644 --- a/commons/src/commons/librarry.cpp +++ b/commons/src/commons/librarry.cpp @@ -1,4 +1,5 @@ #include "commons/ros2_utils.hpp" #include "commons/transform_utils.hpp" +#include "commons/quaternion_utils.hpp" namespace penta_pod::kin::commons {}; // namespace penta_pod::kin::commons From 1af913b4416219ea0d20898ec6e48ffc9c6aa535 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 13:23:03 +0100 Subject: [PATCH 17/39] calculate orientation quaternion from rpy --- base_twerk/src/base_twerk/base_twerk_action_server.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/base_twerk/src/base_twerk/base_twerk_action_server.cpp b/base_twerk/src/base_twerk/base_twerk_action_server.cpp index 9e2bcbf..12a27e8 100644 --- a/base_twerk/src/base_twerk/base_twerk_action_server.cpp +++ b/base_twerk/src/base_twerk/base_twerk_action_server.cpp @@ -1,4 +1,5 @@ #include "base_twerk/base_twerk_action_server.hpp" +#include "commons/quaternion_utils.hpp" namespace penta_pod::kin::base_twerk { @@ -182,6 +183,7 @@ auto BaseTwerkActionServer::calculate_twerk_pose_from_goal( rpy[i-3] = goal->r[i] * sin(goal->w * delta_t_seconds + goal->phi[i]); } + pose.pose.orientation = rpy_to_quaternion(rpy[0], rpy[1], rpy[2]); return pose; } From 9869d64f85e8dea2f64524dc987c879963af13c0 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 13:29:15 +0100 Subject: [PATCH 18/39] seprate source file into two --- gait_generator/CMakeLists.txt | 3 +- ..._generator.cpp => gait_generator_core.cpp} | 182 +---------------- .../gait_generator_parameters.cpp | 188 ++++++++++++++++++ 3 files changed, 191 insertions(+), 182 deletions(-) rename gait_generator/src/gait_generator/{gait_generator.cpp => gait_generator_core.cpp} (52%) create mode 100644 gait_generator/src/gait_generator/gait_generator_parameters.cpp diff --git a/gait_generator/CMakeLists.txt b/gait_generator/CMakeLists.txt index aa8adbb..31576dd 100644 --- a/gait_generator/CMakeLists.txt +++ b/gait_generator/CMakeLists.txt @@ -22,7 +22,8 @@ find_package(tf2_geometry_msgs REQUIRED) # Declare library add_library(${PROJECT_NAME} - src/${PROJECT_NAME}/${PROJECT_NAME}.cpp + src/${PROJECT_NAME}/${PROJECT_NAME}_parameters.cpp + src/${PROJECT_NAME}/${PROJECT_NAME}_core.cpp ) target_include_directories(${PROJECT_NAME} diff --git a/gait_generator/src/gait_generator/gait_generator.cpp b/gait_generator/src/gait_generator/gait_generator_core.cpp similarity index 52% rename from gait_generator/src/gait_generator/gait_generator.cpp rename to gait_generator/src/gait_generator/gait_generator_core.cpp index 0a5d031..b498c7b 100644 --- a/gait_generator/src/gait_generator/gait_generator.cpp +++ b/gait_generator/src/gait_generator/gait_generator_core.cpp @@ -132,6 +132,7 @@ void GaitGenerator::cmd_null_pos_sub_callback( body_basefootprint_.translation.x = msg->pose.position.x; body_basefootprint_.translation.y = msg->pose.position.y; body_basefootprint_.translation.z = msg->pose.position.z; + // consider the rotation absolute (initial rotation must be the identity) // body_basefootprint_.rotation. = msg->rotation; // RCLCPP_INFO(node_->get_logger(), @@ -230,185 +231,4 @@ void GaitGenerator::timer_callback(double delta_t_milli) { publish_base_to_basefootprint_transform(); } -void GaitGenerator::declare_parameters() { - node_->declare_parameter("limbs_num"); - node_->declare_parameter>("legs_body_transforms", - std::vector{}); - node_->declare_parameter>( - "init_feet_pos_in_basefootprint", std::vector{}); - node_->declare_parameter>( - "init_body_basefootprint_transform", std::vector{}); - node_->declare_parameter("gait_parameters.max_gait_linear_speed"); - node_->declare_parameter("gait_parameters.max_gait_turning_speed"); - node_->declare_parameter("gait_parameters.gait_patterns.num"); - node_->declare_parameter>( - "gait_parameters.gait_patterns.feet_order", std::vector{}); -} - -void GaitGenerator::load_parameters() { - // Helper function to load a parameter and throw error if not found - auto load_param = [this](const std::string ¶m_name, auto ¶m_value, - const std::string &error_message) { - if (!node_->get_parameter(param_name, param_value)) { - RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); - throw std::runtime_error(error_message); - } - }; - - // Helper function to validate vector size - auto validate_vector_size = - [this](const std::vector &vec, int expected_size, - const std::string &error_message) { - if (static_cast(vec.size()) != expected_size) { - RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); - throw std::runtime_error(error_message); - } - }; - - // Helper function to create a transform from values - auto array_to_transform = - [this](const std::vector &transforms_vec, - int frame_index) -> geometry_msgs::msg::Transform { - auto minimal_required_size = 7 * frame_index + 7; - if (transforms_vec.size() < static_cast(minimal_required_size)) { - auto error_message = - "Error, can not create trasform from array at index " + - std::to_string(frame_index) + - " since minimal required size is less than " + - std::to_string(minimal_required_size); - RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); - throw std::runtime_error(error_message); - } - geometry_msgs::msg::Transform transform; - auto start_index = frame_index * 7; - transform.translation.x = transforms_vec[start_index + 0]; - transform.translation.y = transforms_vec[start_index + 1]; - transform.translation.z = transforms_vec[start_index + 2]; - transform.rotation.x = transforms_vec[start_index + 3]; - transform.rotation.y = transforms_vec[start_index + 4]; - transform.rotation.z = transforms_vec[start_index + 5]; - transform.rotation.w = transforms_vec[start_index + 6]; - return transform; - }; - - // Load limbs number - load_param("limbs_num", feet_num_, "No limbs_num parameter found."); - RCLCPP_INFO(node_->get_logger(), "Loaded limbs_num value is: %d", feet_num_); - - // Load and validate leg-body transforms - std::vector transform_params; - load_param("legs_body_transforms", transform_params, - "No transform parameters found."); - validate_vector_size(transform_params, feet_num_ * 7, - "Invalid transform parameter size, expected " + - std::to_string(feet_num_) + "x7 elements."); - - for (int frame_index = 0; frame_index < feet_num_; ++frame_index) { - auto transform = array_to_transform(transform_params, frame_index); - legs_body_transforms_.emplace_back(transform); - - std::string message = "Shoulder [" + std::to_string(frame_index) + - "] transform in body frame is: [ "; - for (int i = 0; i < 7; ++i) { - message += - double_to_string_formatted(transform_params[i + 7 * frame_index], 4) + - " "; - } - message += "]"; - RCLCPP_INFO(node_->get_logger(), message.c_str()); - } - - // Load and validate initial feet positions - std::vector init_feet_pos_params; - load_param("init_feet_pos_in_basefootprint", init_feet_pos_params, - "No feet position parameters found."); - validate_vector_size(init_feet_pos_params, feet_num_ * 3, - "Invalid feet position parameter size, expected " + - std::to_string(feet_num_) + "x3 elements."); - - for (int count = 0; count < feet_num_; ++count) { - geometry_msgs::msg::Point xyz; - xyz.x = init_feet_pos_params[0 + count * 3]; - xyz.y = init_feet_pos_params[1 + count * 3]; - xyz.z = init_feet_pos_params[2 + count * 3]; - feet_pos_in_footprint_.emplace_back(xyz); - init_feet_pos_in_footprint_.emplace_back(xyz); - } - - // Load and validate initial body-to-basefootprint transform - std::vector body_basefootprint_params; - load_param("init_body_basefootprint_transform", body_basefootprint_params, - "No init transform body to basefootprint found."); - validate_vector_size(body_basefootprint_params, 7, - "Size of init_body_basefootprint_transform must be 7 (3 " - "for position followed by 4 quaternion)."); - - auto transform = array_to_transform(body_basefootprint_params, 0); - body_basefootprint_ = transform; - - // Load gait parameters - load_param("gait_parameters.max_gait_linear_speed", max_gait_linear_speed_, - "Parameter gait_parameters.max_gait_linear_speed was not found."); - RCLCPP_INFO( - node_->get_logger(), - "Loaded gait_parameters.max_gait_linear_speed value is: %f [m/sec]", - max_gait_linear_speed_); - - load_param("gait_parameters.max_gait_turning_speed", max_gait_turning_speed_, - "Parameter gait_parameters.max_gait_turning_speed was not found."); - RCLCPP_INFO( - node_->get_logger(), - "Loaded gait_parameters.max_gait_turning_speed value is: %f [rad/sec]", - max_gait_turning_speed_); - - // load gait patterns - load_param("gait_parameters.gait_patterns.num", gait_patterns_.gaits_num_, - "Parameter gait_parameters.gait_patterns.num was not found."); - RCLCPP_INFO(node_->get_logger(), - "Loaded gait_parameters.gait_patterns value is: %d", - gait_patterns_.gaits_num_); - - std::vector vector_gait_patterns; - load_param("gait_parameters.gait_patterns.feet_order", vector_gait_patterns, - "No init gait_parameters.gait_patterns.feet_order found."); - int assert_vector_size = feet_num_ * gait_patterns_.gaits_num_; - std::string if_error_message = - "Size of gait_parameters.gait_patterns.feet_order must be " + - std::to_string(assert_vector_size); - validate_vector_size(vector_gait_patterns, assert_vector_size, - if_error_message); - // Populate the patterns. - int count = 0; - gait_patterns_.patterns_.resize( - gait_patterns_.gaits_num_); // resize to number of gaits - for (int i = 0; i < gait_patterns_.gaits_num_; i++) { - gait_patterns_.patterns_[i].resize(feet_num_); // resize to fit the feet - std::string log_message = - "Loaded gait_pattern [" + std::to_string(i) + "]: "; - for (int j = 0; j < feet_num_; j++) { - int temp = vector_gait_patterns[count]; - if (temp < 0) { - std::string error_message = - "Foot index at gait_parameters.gait_patterns.feet_order[" + - std::to_string(count) + "] shall not be less than zero"; - throw std::runtime_error(error_message); - } - if (temp >= feet_num_) { - std::string error_message = - "Foot index at gait_parameters.gait_patterns.feet_order[" + - std::to_string(count) + - "] shall not be more nor equal to the number of feet, specified " - "as " + - std::to_string(feet_num_); - throw std::runtime_error(error_message); - } - int foot_index = vector_gait_patterns[count]; - log_message = log_message + std::to_string(foot_index) + " |"; - gait_patterns_.patterns_[i][j] = foot_index; - count++; - } - RCLCPP_INFO(node_->get_logger(), log_message.c_str()); - } -} - } // namespace penta_pod::kin::gait_generator diff --git a/gait_generator/src/gait_generator/gait_generator_parameters.cpp b/gait_generator/src/gait_generator/gait_generator_parameters.cpp new file mode 100644 index 0000000..fbbf191 --- /dev/null +++ b/gait_generator/src/gait_generator/gait_generator_parameters.cpp @@ -0,0 +1,188 @@ +// include librarries +#include "gait_generator/gait_generator.hpp" +#include + +namespace penta_pod::kin::gait_generator { + +void GaitGenerator::declare_parameters() { + node_->declare_parameter("limbs_num"); + node_->declare_parameter>("legs_body_transforms", + std::vector{}); + node_->declare_parameter>( + "init_feet_pos_in_basefootprint", std::vector{}); + node_->declare_parameter>( + "init_body_basefootprint_transform", std::vector{}); + node_->declare_parameter("gait_parameters.max_gait_linear_speed"); + node_->declare_parameter("gait_parameters.max_gait_turning_speed"); + node_->declare_parameter("gait_parameters.gait_patterns.num"); + node_->declare_parameter>( + "gait_parameters.gait_patterns.feet_order", std::vector{}); +} + +void GaitGenerator::load_parameters() { + // Helper function to load a parameter and throw error if not found + auto load_param = [this](const std::string ¶m_name, auto ¶m_value, + const std::string &error_message) { + if (!node_->get_parameter(param_name, param_value)) { + RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); + throw std::runtime_error(error_message); + } + }; + + // Helper function to validate vector size + auto validate_vector_size = + [this](const std::vector &vec, int expected_size, + const std::string &error_message) { + if (static_cast(vec.size()) != expected_size) { + RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); + throw std::runtime_error(error_message); + } + }; + + // Helper function to create a transform from values + auto array_to_transform = + [this](const std::vector &transforms_vec, + int frame_index) -> geometry_msgs::msg::Transform { + auto minimal_required_size = 7 * frame_index + 7; + if (transforms_vec.size() < static_cast(minimal_required_size)) { + auto error_message = + "Error, can not create trasform from array at index " + + std::to_string(frame_index) + + " since minimal required size is less than " + + std::to_string(minimal_required_size); + RCLCPP_ERROR(node_->get_logger(), error_message.c_str()); + throw std::runtime_error(error_message); + } + geometry_msgs::msg::Transform transform; + auto start_index = frame_index * 7; + transform.translation.x = transforms_vec[start_index + 0]; + transform.translation.y = transforms_vec[start_index + 1]; + transform.translation.z = transforms_vec[start_index + 2]; + transform.rotation.x = transforms_vec[start_index + 3]; + transform.rotation.y = transforms_vec[start_index + 4]; + transform.rotation.z = transforms_vec[start_index + 5]; + transform.rotation.w = transforms_vec[start_index + 6]; + return transform; + }; + + // Load limbs number + load_param("limbs_num", feet_num_, "No limbs_num parameter found."); + RCLCPP_INFO(node_->get_logger(), "Loaded limbs_num value is: %d", feet_num_); + + // Load and validate leg-body transforms + std::vector transform_params; + load_param("legs_body_transforms", transform_params, + "No transform parameters found."); + validate_vector_size(transform_params, feet_num_ * 7, + "Invalid transform parameter size, expected " + + std::to_string(feet_num_) + "x7 elements."); + + for (int frame_index = 0; frame_index < feet_num_; ++frame_index) { + auto transform = array_to_transform(transform_params, frame_index); + legs_body_transforms_.emplace_back(transform); + + std::string message = "Shoulder [" + std::to_string(frame_index) + + "] transform in body frame is: [ "; + for (int i = 0; i < 7; ++i) { + message += + double_to_string_formatted(transform_params[i + 7 * frame_index], 4) + + " "; + } + message += "]"; + RCLCPP_INFO(node_->get_logger(), message.c_str()); + } + + // Load and validate initial feet positions + std::vector init_feet_pos_params; + load_param("init_feet_pos_in_basefootprint", init_feet_pos_params, + "No feet position parameters found."); + validate_vector_size(init_feet_pos_params, feet_num_ * 3, + "Invalid feet position parameter size, expected " + + std::to_string(feet_num_) + "x3 elements."); + + for (int count = 0; count < feet_num_; ++count) { + geometry_msgs::msg::Point xyz; + xyz.x = init_feet_pos_params[0 + count * 3]; + xyz.y = init_feet_pos_params[1 + count * 3]; + xyz.z = init_feet_pos_params[2 + count * 3]; + feet_pos_in_footprint_.emplace_back(xyz); + init_feet_pos_in_footprint_.emplace_back(xyz); + } + + // Load and validate initial body-to-basefootprint transform + std::vector body_basefootprint_params; + load_param("init_body_basefootprint_transform", body_basefootprint_params, + "No init transform body to basefootprint found."); + validate_vector_size(body_basefootprint_params, 7, + "Size of init_body_basefootprint_transform must be 7 (3 " + "for position followed by 4 quaternion)."); + + auto transform = array_to_transform(body_basefootprint_params, 0); + body_basefootprint_ = transform; + + // Load gait parameters + load_param("gait_parameters.max_gait_linear_speed", max_gait_linear_speed_, + "Parameter gait_parameters.max_gait_linear_speed was not found."); + RCLCPP_INFO( + node_->get_logger(), + "Loaded gait_parameters.max_gait_linear_speed value is: %f [m/sec]", + max_gait_linear_speed_); + + load_param("gait_parameters.max_gait_turning_speed", max_gait_turning_speed_, + "Parameter gait_parameters.max_gait_turning_speed was not found."); + RCLCPP_INFO( + node_->get_logger(), + "Loaded gait_parameters.max_gait_turning_speed value is: %f [rad/sec]", + max_gait_turning_speed_); + + // load gait patterns + load_param("gait_parameters.gait_patterns.num", gait_patterns_.gaits_num_, + "Parameter gait_parameters.gait_patterns.num was not found."); + RCLCPP_INFO(node_->get_logger(), + "Loaded gait_parameters.gait_patterns value is: %d", + gait_patterns_.gaits_num_); + + std::vector vector_gait_patterns; + load_param("gait_parameters.gait_patterns.feet_order", vector_gait_patterns, + "No init gait_parameters.gait_patterns.feet_order found."); + int assert_vector_size = feet_num_ * gait_patterns_.gaits_num_; + std::string if_error_message = + "Size of gait_parameters.gait_patterns.feet_order must be " + + std::to_string(assert_vector_size); + validate_vector_size(vector_gait_patterns, assert_vector_size, + if_error_message); + // Populate the patterns. + int count = 0; + gait_patterns_.patterns_.resize( + gait_patterns_.gaits_num_); // resize to number of gaits + for (int i = 0; i < gait_patterns_.gaits_num_; i++) { + gait_patterns_.patterns_[i].resize(feet_num_); // resize to fit the feet + std::string log_message = + "Loaded gait_pattern [" + std::to_string(i) + "]: "; + for (int j = 0; j < feet_num_; j++) { + int temp = vector_gait_patterns[count]; + if (temp < 0) { + std::string error_message = + "Foot index at gait_parameters.gait_patterns.feet_order[" + + std::to_string(count) + "] shall not be less than zero"; + throw std::runtime_error(error_message); + } + if (temp >= feet_num_) { + std::string error_message = + "Foot index at gait_parameters.gait_patterns.feet_order[" + + std::to_string(count) + + "] shall not be more nor equal to the number of feet, specified " + "as " + + std::to_string(feet_num_); + throw std::runtime_error(error_message); + } + int foot_index = vector_gait_patterns[count]; + log_message = log_message + std::to_string(foot_index) + " |"; + gait_patterns_.patterns_[i][j] = foot_index; + count++; + } + RCLCPP_INFO(node_->get_logger(), log_message.c_str()); + } +} + +} // namespace penta_pod::kin::gait_generator From 806954b282bf01200534d850ccad3ca947344261 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 13:29:41 +0100 Subject: [PATCH 19/39] update config files --- penta_description/config/general_config.yaml | 4 +- penta_description/config/penta.rviz | 113 +++++++------------ 2 files changed, 43 insertions(+), 74 deletions(-) diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index e91e696..a1f7cd1 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -34,9 +34,9 @@ gait_patterns: num: 3 feet_order: [ - 0, 4, 3, 2, 1, + 0, 2, 4, 1, 3, 0, 1, 2, 3, 4, - 0, 2, 4, 1, 3 + 0, 4, 3, 2, 1 ] joints_aggregator: joints_update_interval_millis: 50 diff --git a/penta_description/config/penta.rviz b/penta_description/config/penta.rviz index e02ee8c..d434855 100644 --- a/penta_description/config/penta.rviz +++ b/penta_description/config/penta.rviz @@ -3,7 +3,8 @@ Panels: Help Height: 70 Name: Displays Property Tree Widget: - Expanded: ~ + Expanded: + - /Global Options1 Splitter Ratio: 0.5 Tree Height: 296 - Class: rviz_common/Views @@ -59,6 +60,11 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + head_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true limb0_lower_arm_link: Alpha: 1 Show Axes: false @@ -139,6 +145,26 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + limb4_lower_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + limb4_shoulder_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + limb4_shoulder_motor: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + limb4_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true Mass Properties: Inertia: false Mass: false @@ -148,80 +174,23 @@ Visualization Manager: Value: true Visual Enabled: true - Class: rviz_default_plugins/TF - Enabled: true + Enabled: false Frame Timeout: 15 Frames: All Enabled: true - base_footprint: - Value: true - base_link: - Value: true - limb0_lower_arm_link: - Value: true - limb0_shoulder_link: - Value: true - limb0_shoulder_motor: - Value: true - limb0_upper_arm_link: - Value: true - limb1_lower_arm_link: - Value: true - limb1_shoulder_link: - Value: true - limb1_shoulder_motor: - Value: true - limb1_upper_arm_link: - Value: true - limb2_lower_arm_link: - Value: true - limb2_shoulder_link: - Value: true - limb2_shoulder_motor: - Value: true - limb2_upper_arm_link: - Value: true - limb3_lower_arm_link: - Value: true - limb3_shoulder_link: - Value: true - limb3_shoulder_motor: - Value: true - limb3_upper_arm_link: - Value: true Marker Scale: 1 Name: TF Show Arrows: true Show Axes: true Show Names: false Tree: - base_footprint: - base_link: - limb0_shoulder_motor: - limb0_shoulder_link: - limb0_upper_arm_link: - limb0_lower_arm_link: - {} - limb1_shoulder_motor: - limb1_shoulder_link: - limb1_upper_arm_link: - limb1_lower_arm_link: - {} - limb2_shoulder_motor: - limb2_shoulder_link: - limb2_upper_arm_link: - limb2_lower_arm_link: - {} - limb3_shoulder_motor: - limb3_shoulder_link: - limb3_upper_arm_link: - limb3_lower_arm_link: - {} + {} Update Interval: 0 - Value: true + Value: false Enabled: true Global Options: Background Color: 48; 48; 48 - Fixed Frame: base_link + Fixed Frame: base_footprint Frame Rate: 30 Name: root Tools: @@ -233,35 +202,35 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 1.7000000476837158 + Distance: 0.7511907815933228 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0 - Y: 0 - Z: 0 + X: 0.01839996874332428 + Y: -0.016720440238714218 + Z: 0.056901950389146805 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.6899999380111694 + Pitch: 0.49500012397766113 Target Frame: Value: Orbit (rviz) - Yaw: 5.414999961853027 + Yaw: 2.1449995040893555 Saved: ~ Window Geometry: Displays: - collapsed: false + collapsed: true Height: 800 - Hide Left Dock: false + Hide Left Dock: true Hide Right Dock: false - QMainWindow State: 000000ff00000000fd0000000100000000000001cb000002c6fc0200000002fb000000100044006900730070006c006100790073010000003d000001ab000000c900fffffffb0000000a0056006900650077007301000001ee00000115000000a400ffffff000002df000002c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000100000000000001cb000002c6fc0200000002fb000000100044006900730070006c006100790073000000003d000001ab000000c900fffffffb0000000a0056006900650077007300000001ee00000115000000a400ffffff000004b0000002c600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Views: - collapsed: false + collapsed: true Width: 1200 X: 413 Y: 99 From 083529e8f52cbda5d36ef5e79765797574e8e661 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 13:30:01 +0100 Subject: [PATCH 20/39] helper with quaternions --- commons/include/commons/quaternion_utils.hpp | 38 ++++++++++++++++++++ 1 file changed, 38 insertions(+) create mode 100644 commons/include/commons/quaternion_utils.hpp diff --git a/commons/include/commons/quaternion_utils.hpp b/commons/include/commons/quaternion_utils.hpp new file mode 100644 index 0000000..e7b6cb6 --- /dev/null +++ b/commons/include/commons/quaternion_utils.hpp @@ -0,0 +1,38 @@ +#ifndef COMMONS_QUAT_UTILS_HPP_ +#define COMMONS_QUAT_UTILS_HPP_ + +#include "geometry_msgs/msg/quaternion.hpp" + +using geometry_msgs::msg::Quaternion; + +Quaternion rpy_to_quaternion(double yaw, double pitch, double roll) // yaw (Z), pitch (Y), roll (X) +{ + double cy = cos(yaw * 0.5); + double sy = sin(yaw * 0.5); + double cp = cos(pitch * 0.5); + double sp = sin(pitch * 0.5); + double cr = cos(roll * 0.5); + double sr = sin(roll * 0.5); + + Quaternion q; + q.w = cy * cp * cr + sy * sp * sr; + q.x = cy * cp * sr - sy * sp * cr; + q.y = sy * cp * sr + cy * sp * cr; + q.z = sy * cp * cr - cy * sp * sr; + return q; +} + +Quaternion hamilton_product(Quaternion u, Quaternion v) +{ + Quaternion result; + + result.w = u.w*v.w - u.x*v.x - u.y*v.y - u.z*v.z; + result.x = u.w*v.x + u.x*v.w + u.y*v.z - u.z*v.y; + result.y = u.w*v.y - u.x*v.z + u.y*v.w + u.z*v.x; + result.z = u.w*v.z + u.x*v.y - u.y*v.x + u.z*v.w; + + return result; + +} + +#endif // COMMONS_QUAT_UTILS_HPP_ \ No newline at end of file From 90abfb941ea769108d6893584c435ec0f7b1bd93 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 15:07:23 +0100 Subject: [PATCH 21/39] rpy to quat --- base_twerk/src/base_twerk/base_twerk_action_server.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/base_twerk/src/base_twerk/base_twerk_action_server.cpp b/base_twerk/src/base_twerk/base_twerk_action_server.cpp index 12a27e8..bd475fb 100644 --- a/base_twerk/src/base_twerk/base_twerk_action_server.cpp +++ b/base_twerk/src/base_twerk/base_twerk_action_server.cpp @@ -183,7 +183,10 @@ auto BaseTwerkActionServer::calculate_twerk_pose_from_goal( rpy[i-3] = goal->r[i] * sin(goal->w * delta_t_seconds + goal->phi[i]); } - pose.pose.orientation = rpy_to_quaternion(rpy[0], rpy[1], rpy[2]); + auto roll = rpy[0]; + auto pitch = rpy[1]; + auto yaw = rpy[2]; + pose.pose.orientation = rpy_to_quaternion(yaw, pitch, roll); return pose; } From c172cce43bfe8b2f73e898bf740b91c7140106d7 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 15:08:30 +0100 Subject: [PATCH 22/39] add orientation --- gait_generator/src/gait_generator/gait_generator_core.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/gait_generator/src/gait_generator/gait_generator_core.cpp b/gait_generator/src/gait_generator/gait_generator_core.cpp index b498c7b..e342384 100644 --- a/gait_generator/src/gait_generator/gait_generator_core.cpp +++ b/gait_generator/src/gait_generator/gait_generator_core.cpp @@ -132,6 +132,11 @@ void GaitGenerator::cmd_null_pos_sub_callback( body_basefootprint_.translation.x = msg->pose.position.x; body_basefootprint_.translation.y = msg->pose.position.y; body_basefootprint_.translation.z = msg->pose.position.z; + + body_basefootprint_.rotation.x = msg->pose.orientation.x; + body_basefootprint_.rotation.y = msg->pose.orientation.y; + body_basefootprint_.rotation.z = msg->pose.orientation.z; + body_basefootprint_.rotation.w = msg->pose.orientation.w; // consider the rotation absolute (initial rotation must be the identity) // body_basefootprint_.rotation. = msg->rotation; From 9d39d7cc4e75fbe49ecd7d2fd625bf638e858d98 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 15:08:55 +0100 Subject: [PATCH 23/39] increase update rate --- penta_description/config/general_config.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index a1f7cd1..5357ee6 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -39,7 +39,7 @@ 0, 4, 3, 2, 1 ] joints_aggregator: - joints_update_interval_millis: 50 + joints_update_interval_millis: 10 base_twerk: base_frame_transform_update_interval_millis: 20 action_server_service_call_interval_millis: 100 From 606c5fc3677c5993eeed58a70ef3a695e30ceba6 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Wed, 1 Jan 2025 23:04:45 +0100 Subject: [PATCH 24/39] docs to calibrate the motors --- docs/penta-pod calibration.odt | Bin 0 -> 150574 bytes docs/penta-pod calibration.pdf | Bin 0 -> 87116 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 docs/penta-pod calibration.odt create mode 100644 docs/penta-pod calibration.pdf diff --git a/docs/penta-pod calibration.odt b/docs/penta-pod calibration.odt new file mode 100644 index 0000000000000000000000000000000000000000..67ec8bbeaf2f643b8273ead515297809da8c0a5a GIT binary patch literal 150574 zcmb5V1#D)$vLza3<_>n4nVFfHnVFfHnVFL>%$#(XnVFfB4tDVMf99UiJn6jq=9aZ3 zYsXa8)1SY2Lb~6=llB$$kx)<)Wy@m)X>4f#?si( z#nRr6-p$U0&fd`3(wWZQ!PL&g-q_XF)Xs&@#ni(^;r~_HU;O_TtiL&7dpk2rb62N- zRpZP=?_zInV`S(=|35>S+1MMpnEp>ue^qq-@7u!u4;nhyJGeUh1O0Dw#QhIALt|r8 z8`HlXwg2z*{7)_ZGbRp(cBVG}!xkN!?9H7_ot^*ZeROs)baDOv!4dq2K3duunwvV) z3t76@8ag=tm%30;Q2*l5-}3)k;Qr=p4ecz=Or2fmoJ`E7lc(*18IVG5c|uKR)&%Im z!JQ~3I;`^hSi>~H>3?UT?EH#LR#PmgyvScVtQBM4jcd-nHpCr^ZUpqJuozR4PDog^ zoKtgk(RGw=a&4@&QWIq1-CG5h=2LaL+fi}qr-jn8!`aL>6;XI(J@CkP6ZJ21I7+~c zG{-?foE5({*_H zVIe}OSJ;2Xt_BpwrB1}DWIc2`%#JjJ6&hlF0KZGAQ^0`4Pz_ZS?ox;# zMi%9sMU=q13^5dGB~*cX8jmln_?*}@S$XTqi{%gk4AERE9)+75)3wI<+qhtxXoQvB zL{pV;INTU#yW)_G|8&nUp8JbyxUs`GbnDaNb{%(aJFYP0lbK-y8bZw5AWhLk8ZgE5 z67UByh6p3w{eqIw#4WRq&ccXJW2zT&F+-j?MUdAGgHZY5pE)KMXeQ^Qrfd5`8!&J0 z_2gS7^1~Va%7+r&aDafF^7{+QYEwzjWaVKu&QL1 z%U9Sy8$5yA^R6;iv)lLq`416SL%}7O)!Gl}31DjemT(IA{&F)-E(=hOn&$9M|!x9`=Z zRM*F7;P3*rZBJTFT|^{LB~B=eYR}PA#}}_TluxB+_t&i$4+&R@SIHRpdEEePeUITB z5-+Wcn406@^K-eeHeiu&2X0w()t!|-5AUk3?T|@!@dp!SSM474sy@e*evR7t^H$xg&*(cSyiG~c#06%T%pGRoQL~e? zlj=5FL)RLDOf_PMJWpd&P0+0T?2HslFC<^Ct^c*w_2HjCehcButONofj1bd5l9d^( zu}7q!4H}({U18qOEhfX%oI!Qb1rr~kQO(TnM;WE#I${if=gS&eAv3%of_3TLnLW9+ zyj6`^$&Hn1R-fHX4X>8v_;hd1MUu2rs0irkUofp-HTw3Oh9h}B?6@m}2T1zSs(q?xjn>YI0(rK3aD z&V$_f*B9ArnZbYyLjk4tLE-A(5D9P@#}mO<0%7fb5n}cAyw$U)g-FU}G&(nhHj~3` z9GZ{L2tAwjeN4UFjAL{qSuv#FA%u^}F}C{D$pz%R8SCQ&K*&Ee>cAkA`Gz|)RB?jcPxQ(XjknU0T6LTKd} z3<+(|*@q*(U2kq@OQR#$NfJzoAmy~I)MUCe(r8YJ%fzb)XTcACHeRf&Xej{glB_`_ z^bL`<&}(E;TJM9M4Rqv?BIp78!YbNd*hBoKFjHYs$$?yt6_!Q*tSkFI8lsGbHB;ix ziYIdQEhsA=bxe#xqW_B!qR+Ha$(fwET6kEc*apZ$J8(}DL@_^{ZCOvRmlUlj&EZ|p z@H6vwtl2G+7XERD(pH5gVFn`aOJ4%`5yv)=m0d=|ZE6=&Pl~{wxX_=F_Dny5IDCo> z{2oP)ngecvmU$ixIZO_g5ZrXZUK8yhej=&s8I)|S0Z$D4s;X}ASs7~;p(fN^|7=mPR%ml@LvSMAX6?G7R_ zkk>Sf#{R>5rZR|v=y6P!SE<(6Ht23%tl8-c_BM`GufbIf#Oi zhyqr|X}t9HQ+GBypFFnB$|gVu?GFXA?E`$X3tV%)6bVUf&CC2IV>L1}nB#bRew5TU znne~Kk701?E3jioTo?G82-Ccv*6+9^lvpDOd4yCy<+x{cre$uum?X#-fBr{TA^(+Wh=&@#ggCnOu2*hm!lM0Sg1B; zrF!n^S8)jv!_c(5;2-X7hI+cC!jOP`)(ORCwolKdB2_)Gr9)ij>(yOMWzQGpGYNY< zibd+Dy>(Xayy`>M>@wCpEURM&{aSoZ1K5nsSiG1GgM~4ohQ<_c{e(&UAU`~lWWm>( z39hX595_j7^esu`o5vDi;ExPZ#Av4-sLmY)c;IPfw_Z6M+MB1wS$b?_Opz0Qp|tX* zO04O-BQhPfl+HG$5zJ4tWie>?_K)~|6D$;HKNVcxKd6lXLKghNd_%onci=A@EL%HmOO>mg#Zn2d(u*Zqjsd`yU%*YiYyd6tXh z7ofJ5_f^JB%Sv}v&)D6_$^RtYCop~9oq{+wl*HTTXP^!0=Jn_N((QGwj%6w^9sUddlhg`oT!!F)6Y?ek0*f$;L;QG9#(E{BD!+CGR@g#Ov5IT~iap zigx9AExZrCpj5rKQB#CL8DhrW0+EZZj)!5JPyvR6YjP(7|ERQ+kr+9~w~oiY;^4)I zKdDOem;T`i|34;nCn+|L5)ugLp7Gzl*1xwr8Nc!2jP-zk{`vmdrKniA+8WszTG}|% zyZk##=U`_ZsURl~4}%T!w+OtXgoqLl5U>>x5C{;|U!x6_6S(341Oy7CAfqA*3=9kf zhYW{;g$4(UfeeR*i3x{6h=xmoz=?oMg@eiq^n>FEE)gXj83P3j3?(iQ1r`Q76cjH8 zC^rrc85Ix}5ia9TFeVaw8ft118Ww6sYAPl!W*Qn!MoI<-23mGOE< za}ZJkQZ6AWUNHp;P!J&$Pzfw7O=u`pOdu6BG${%YQ7#}QLJ%=BG67ajQ?b8KvP5D<4vOk+YqD|!YeCMIDqAOSUODIrcJ2|f`K5n*W+X(cUHSuqVoDRp&q zISpe?T_asXGhK5>Lv>k0T`fa>19Kx?M{`~CzhdKT?d0WTWA5Q(^3=;tjlMam<41^wuj+zb(1AvBUfkv$YLTdt|4FDp}0wM+g6SV@v zOhCiTL8FZV5siX)2SxdWB}PL*MWCZ+K!B&Apj1FWlp-NDK|yt4V$~4*EGHuFA|VZQ zw+;4j9fX4FLqb{x0p0@v3Jvgy3~-AM_D&46=g+$ zazHhpq^hc_sH(ZRwxg=Hp{~BJvZ14?y0pEqvZ<-5v9+_gqo<>#vAd(CtE;QJt-qyv zsB2)nXLP>5t$L`td3>OAVXS9pXlP(~d}w@XVq{=yY-n*j3t_u0zq$V#P|(Jg6cJSM*tqUN)X`S= zBc~$2H`|mnPkwq!wmz34Jij8TYpS!?+udCCnri1B(u3Q%md@m$l2cU|+T(}IY)zio zJh!PbfRpL!cY{U-!OcdROpE!{46!9#XH2she?>%z0~0eG3bERX>K_Z1A(%FOblJK6 z=y)6CKO6$%agImo?CkWP`P|w4%-ijCj)RjthNWVH27$JMwyKa&kXDcu4bu82QK2lM zEGZ=xr2Uhkz*@jsR7e1%e^V)uAgv%R`agjGZ^*v@e<5l37qH^Uot_rhX&1LM9sTfY zKaH#j1}E{#8~r*hn~E=6@9?zWUBo?csxumMg_X_kMXFV zpCQ{0NqHAwr^IN|K3c*}(*Y8$gV$!&o zqvx>wH$&-%hPQcMclXgJiSS3gt_`nyHVIY~>?wS2#syy`pOs(J>t6kuGHzdY8&F|f z0i43S+GZ{_O7e(&{-U~Zt~4w zx{MME=4sl7z@c7>CFB;Sy9madLqZrmy7y6vR{UyP@lGOah7 zcy<$OhtH8^B6ylK=F>Ot^N*X{h!b4gFE^Gyn%41<)b}(dK?ZXL78NqOcmf0R{ZPI_ zg$9ZdpP<((312;IpDr_`xMFHJ?hoT0cpCAYxWvbQbH4glrG5!X4V??&A7+AeuDhi0 zyw1BBM-wm)SU1`qZcR#b-6MU))pA1;$?~;o-__s4t#`K#doYnnxyBF1m%iOhr@a)_ z&m6+-GJ$C8*fVYz9A@86;B&jup4T5<+v73f!}p)2EM`VDCouDADU|2S&RVTgty3`z z={AmDn8@?dz9UpGf#OT{z@@{q=Bhrcfcp6Mz%~IQ+HF`Zp zH0^9Tco2%aUt$e$8#9TY%=>MQG-kS9>GgWg*iPA9ZPYRqqeqMru1NXilZymZGeiX# zijY}BDA!s3VEu|%Tn%CbfS3Wc>) zqytp}e$2$rKz}`6P>ZqWqwvaIS$=?YDg2!G57<`3s>y8s zM4PGn$UJpM)w!G3dNMRzOUBtJ6U0mFFB6spXLMjYc~X%IKfL@|1VqR=D4SLUJMS^r z%@iY=Y*YCpvw83rT=S`4MDM(CtN^;(3AJGYR@1uCcH0)X+CAG$o2QGGs=Wm~EPWb7 zi1wXb;qN+`XFlKu{nA%nIeG%NiU6F#;@9sCfn1-g=2*2451VA)?A(woG%c>BY^N17 z0ofAl8>o*L;HB4EqG&GiQ%krfM~Iepf^%V2m|cGl0TJ4r9pVb>( z@`jZCDi6#dS6ZDt-pnh|S1odH8bYDmKI&~WD;Qd&7ol%xIE=^uULV`m(sT78kxl~I&FD8BR zyNDd1P~n@JY8j+QJ)?$VDNbCr(tS*gHEhJYO|YlXkiBqR-ASiN1=I=GGw)mF*#zsU z2E{e5}A`F);c1%#uI4V3*`a=D?d0jt@wOf8)x&?xAK zNM&;T-~^8RSl$2_NTYPtFkU;#&S+s=JU}JBSLTspy^@V4g2}FhhCDB5L&}AHEh4?< zzyxa~Qz6(cEU9i>jrS?UW}D#`d1EIHw;;n;*}V@`f>U!7lWGi;mZy0L=>Km_JOJf@>i{fk0l*KTxg6k>-CW7;+vSLISTXH69S$~W z%~_Xuhn&S))(qO$PAd-UPOhonJRMWL*($HGJeS92u`%b`!qpwDj5iD)1i|j7?9J9= zB`)6DLsw9iQ`G8xq?0V$j#8p^L8v2nUA#sk^?z%8FT|0p4pq^F^OQTQQ%9MZU~$6M zf*hEPqs<^7To48XCi4Tb?u;E#9s&_|Syskv{fC+7z0sxhO(H)`m=wSl?0mv0%W# z3DJ6(140bsK|~SodLuB)kvo+bkix2LE=C)aC6W=zy_J2 z-B`=uU<(s!1j!m4U+3OgQ^dq2eCV*^BFJIIh8c#hsW^B!5n=R#wpc+A?iVLBz8W$C zLN{?je2Wt;SfYX?;)N7$xfLp~_~1VhVv6pOh{(kX1;Am>-@yUs2ADqt<~1m=qo3uU z2Ma^6e30+z0~vw!KY)TBhJqHAi#>MJ66_p6Ll7K`y1aosJu9Y|MZ z4r_lG=y4msr+Ugv6Wsowz*~MiyE&(^eJk7s%>w(arV)1$J`vP~L^IMH)T!%#SPN0B zK-=uGaS?X+($1%cz2Hq1gNYmz+D;aebfIWF>o!`k?LOarVxlQQFz>4|ziioZ87W{@ zrr0=Ty^y~;G$Az8s356-h@RXcd%Nq{bTyzDT`{~gR|P8wei{7L7T&U5=M@D`yHIpP zwwv#=C8}Hg5)$MslO^fCqRqF4HqZJVVPc0+BCCe>VS12 zt`!j8*u1^Ic6HgHx8=(Wb_(B@T67c#9IL)+ZuOg=rPgoRsedlcMZ*10#wZ*C)H1w# zN3+HIee|_E)rdRmds}f>ysO1%%1y|7yL|Q>`JA}zigbO1I6Yj3Ky5Psiclkd3DC3d z{*i>>@Be<|R&x8*w-}kERr1a0H+P@*7Di~ypS1xk|I2SKVM`D53($~K@OyO8!sqmL z=B9q9~ zkHdb5VFBt@9u%9LF0cJ{uHc4=_*z2=b#ZG!Ke}HWM03abf`*qpVCn1VIj_N;ZuwoB zoFy>#a5MW__U6rLk>#zVq<{HnB_AU%osDJlfKf^i2M>@){>2WISCxr6AzcU`;aB5uca1g)a_pCa`TKwZ0myauXJ>eB7R zF-B&i@B7$(g%dj^ic>J1d(E`NP~Q3yVZEb#*30nOCF;^-F)DoYOL1^Y8SH@y4q~++ zZS=3z;%j$%2Nr<9uNVS;pA1bMb~Ebk!^8`KCC`lGb_?Y0wV`_mQ07=%JUyH*!yijZ4jp53bgkeK(EIPC72xkfsOmAPQRs zziXjMWA_v0_?CB)fB^44dg|#NJa#RCTrP_yaM-kBVp_%Kj+}hPa|RG{HQPD)5vY`)b}GWj4!>%SK_QkaeB(Nzz_HBd?xY`(hmVO zEv_KYV$qxnJ6vVJjJ)0+Yu4O97~Ayt{qf|kIo62)b(%E7dd{B!_{vSE2}9>?m%JP+ zTLLwL*6-kTuSOon6=<%lNErD@$FsKz<>1_%m#ed#dFHnGR){FU4vsB5k=7=2qi~*@ z<6>@|SD)PR6}R41w`J^=c3KB9=RT81Puo>|q9yqKPC^@Dmi$G+>z{islEzKY_|=_V zr7JU(x#$MgZuSrP@_LJL=eIWOh13KZ+oN?oeuzWt4rlpNQim9;9?%*nyc-C~dKon5 z-c_Io+Aq$ru+lrJh}|a^@fbGX42)S}*kMbU2I3s(3!YPwwyUDFR=-MQ*|Ht{x#S}U zcT6oBQMJuq>f372z;4Wvd$5M3M$16Tez8??uM|gKLh9dIJO;>a#>r9`YR9u}bbYpS z|5zn={Z?A|xaS_!s?X{(>M(lFVCBuahpE#P0Pg7>ukKZI96k3wwR`Xc45rK&^6wAG zH{)A&a`7*-whU)|nhHIP8nn3LfX3c^8Vd2+Jo+!SbMG9j7&1dcl`y&$g9-PPAFieB zI6;V<_-GEZCJ^*RL?y(JOoowNqzgi@AlJYf4KRh^oanuHKFS1)(gitdX znlpuLs&v7cfe@q0h%p6njRYFaQ|XFqsSHCMZ64iUxk!4Gm);BeTC;dS2K1{f$3TCB zDS%>zu|C-ub`!br>bR%t)E0zmUvBUU-t-)5vkt{G2Mmz^?aO+zAQVe0* zLSltIgZvgj;;IaCF5Ex>V)EUG9BH=Ps6mMNG6nChInz;-!_J+9IIL^sk!QJZ?zuIT zYYuxxab9zzRtQkDBab=)Ib`Myp^^Md2wAm!Q$Vv0o>&_WuiI@$c3GbGtta<>A*bu_ zxOwPP2u?0hI`^$32hJ@7kEo@%2g!D=cBiVkNxLV{*&J*ZNIAWFUE7|nsfiulLsf>- zx{~hXESF18W1-|y>g4MOZ{bPrSXkb-w;wkfB_|ITV$uM0*kb4_X!Kq&R9H#{X%!3( z<=-7wzp(Z-m>tlcrujx>H}V#wr$Z?&Ge zcO#r<1*Wa4m!vDJ>uG7PwB!wz+D6pSR`SM0kff*LMBHZpd72UaQMWg6Ec@h#nZsif zinr?1NwCI2XsdD<=6mQ6_t||K5Aw+p;+KQsm&jX2qnr)aIPEJF&~>pfg|(zf=$3u6 zHLo%s8%T+9TjkMMIoHPSa}=KdI!(iKnqF90pRO`=@%SyT-SwL&vcFD) z+p+<;?F-&_YHmTaJaJvcjO&`&V|V#WdTVpHIzH3Nd(8Fg(rvfCmlAafLBlN;2UC>m z$b)P+i}CI2z6|uy_PW;2ftv<5-pNS3l+-;cm)}VgwB_Dbx!Yqpj_(Mfe!PY36Q0>5 zrSK}{DwB}z!H<=KLpz>_73)(fh1?(OT2tx$QH^>a!+uKT{Hk%Rg`4QN88#ert%GX# z7GQ(G`Y~#E&8ho+$_4kuFLfEYD{Wbyw_&Uj?#EAY%EKHUZhx8~a_gfDYvb+JJ#aR8 zNz6!~rSdKa-M*f8tc zaYq*aQRa$9lo`ms`gJovHYHxC&AmT`O|z_CKUwPf7DZXuk8V?cUhQ`MQ-e);^Qvr> zE=7M%Ut0{YZ}oWpMhMr!MziI7@$T;CYD7J8u>!kMQVUH}jbF{x)dp|aec?L*73#&J zhuPXL1-)dz;yu0bYvd$;_p^bk?6ZQ73_uPn8L#P&2`S__r)2HwxhsBg(?@57q-WU; zN@j#aQDRdGhmVu~M5NNEY#1HPcpBx6b9lJ#UfW+mYw$BowB?>;<79Niug{=o>B=4p z{|_7PDe9ta?$5qV>Cfa>x8NCju@r&k{mz>t4=4Fc)3o5;(V*MiTW05I*Tby&3X7!Kmo1AL^x>^^ik4>_JM zy(^Vij*l}oI}C7f_wV+aUB@M*c{~hU-m@TOhvy+U51*nN3-{_(3}K9gS6BJnv)l7q ze2G?L@m!qk`r-Yl0nOF1W$jgoN0@CVxkDJYaQij#7`%H*!7R#nY-!8;~=j< zrc!gZrCfRkx?0%QXBm3ilZtY!#*a33ZA{YqaSZdz$0T*_g(^~1vHvsd`h_0exomWn z!TMHTFzrCSU!aSrY8XGY(LIvhu7_}#|ofV)G_mKtc`*IW+n##Rv7AUFQ=MLa|~$7LVf_CczP5i)MK=kHe$O z{S7x^!I0a>9AvHzQXGgY^UiC?^8`IS)yc=dpjbeH7{4ajKa&d+hQxfnnz(xr5C!UZ z!p2rZAXRrB99D&AssE|2x&o;5(%s>>ulPY0^6S_t^8fJvb6BP-Y$1}m)@t{0zRLdR zPdsl`1nPC9`m%iXJoPSwF!w3+A?j#Z-dFKve6OFUYId(}Cj>K92kWaQ?fhKDTzRV*KAHxaj+PTOZo`A948iKZ#$3g3;GFQfXRkwe>DF z#o0EpxU8k9iWYbMFWrzGRyaOjHNW!dwS3x!RfR*UX8i}Y0_)= zOCOHuEAgL7vYlf$e^)nI;msWL2vD3;WEOTexI4wzt?fEa+frjS_8GQ0 zO?bRtX%O#rJUsQiG8A2!S3{sB2P$qQ@)rqy-S^khK&&&z7QernW~$uLbqi+h@Ejj+ z6b2p6x4k$XYzGZAaRl(%Qm&gl_uU8_Q*r{Ny9(R~TocB2nCJY(zLx? zaT(I|l(Zr4X`Sg_I6kGKywK03a8*X4v3FgBHGggQyg|EmdbFEPAgk{At5(gZfl_fDiXyo#uVFW|pw`)QpH}lNAwXxUj{`=ho&MlBBH6x11 z5GEED6A9>87tl=?Qtr41)(8EVrff8y^LIkv9CqIjaqLV}p34!dMFgdw_ zv5&<*LIMZcGG-r8b8vlvAkvT=w!hA+Z+Q>v)~Snr zeW?AqeHhQ6`D`m!Jke-HhS^@H?b5*|R4`uV(&&t+jrahgwmXVj(>jWTx9c4As-Gz4 z93C{J?I(v52U0ye%bv)NTQmWu&HZJ6viWtJj<=fbuwG_95P12L)^njW}3&4 zC77t?W{aM={gN95=_a>aOV=KixIKrrLq4m|{A%uMx5K*m47g9Q9DmPqICRUhF29Ob z8%r(ZG2ezM1RzmwZU4`no@6k0tFeIa2ZRK*1zs5$<{GeX?9R)jnEcvPB1{Q9mH_5L z*rQ+UFs}8pHr+w9W%6kCZM-E!KZeViA+()Bus(keu^Lmw)2~|w*>lvlWQU!wLZx~- zA@6}sNrj5|cN({LlLV{n+$aI#U~O(}D!fH86bb$sQTxNk3uNJZNz{$FIedLMzFoYi zP!t0?P5L+$4=zcU{0J7gI03C_?l}ub%XeD|_tKh4JuggemS&I)okLRO?vmUEuT3)7 z^mx}F@oVFv?k+nE&ngz7e}h}D>c-qc!-zN+((r?>?hQ3+Tv}$lVTEB)ZZ2dk4TBJ_ z3?d(N^-}h>urL-w5!}R=hk1xnpa!M~xZn(pZm&T?;kD<7wQ}$a?!C9H;@L8F2fBEe z#UpHJ3@h(@K*grx*LqED@V4S^Ra?xUS*F_Hz_Z}x2JdzIAuA)2}Lv!7VIapIU-5&lKzAv5XqIG?m>+G>f$ux0U>WtWjX z5_1}h;7m|&UM+HmrHg-BXx7AN=g6i9Tyayso~>1A+L(8B#uYB+hP{n#9$jGB=Dm?L zg3z_PdepiW+w=6rW$xKyFJITdyL2VwY9O{nheOi=9X|sv+_tK)qsA{PF#bZ9MLm1^@BqnKn8X`^0sK=(YE2)+C2v0n|GJltIG$os$#2YOY?*` zgHC^ul>=wJ4ay1o))j77F}t~CUcS3GV|q``#66=xp9~9q-Z*Sq3&q+F z^YX^Fxx2c?v1o1S=05#Byq=GoSukWs2z?e_aOFAUGQ|S?9)nW*e|MHVu^_;^y96Fw9L={J z8w0m>rZYYrTyb29%22`9G1 zxw|X|^da^*J@*1#8c`(uYd??k&|R%V?640R=Z76^{8hJs}>e|Ns(gB*qi!IMbTU&1nXnbSU`CFW$(NLJUpdaf|bEyB@iu`U?V{S|< z4C>)2sCrL%j8Ge>+$k+W3wh^k7KAs5Ixkz>bXa~`_H&7YvB36))P_yNb1}P(U&@ls zVm?zb;wJgsp8w2qB#xXhi0I62KY3`fyQ)m_&zoy?_QyoQ=;lQU3wsV;3unZQ*m<|h zGfD5?HeCVCRkv$1q8r+8^HTF?tC9b~M6@HV!!&Z7=$MiS9dqb~UuHMWd(n*8%ut6*&eFRYoDHV`~# z+B8MHel%iC)s8TSDv_&K=UaiyqU95BGLqM}2^VDk`H}>_u16aZ#Q2Tc(U5H2#sa0N zo${{4vB71v(JLclA86Z)o^a-+_YKIvd1206(>uLs1?s{7M~)~87L_s z%`!o%2wBX`1C~{PpgjJP7uS6_LOHnSPIy-?(EW3cTKIsj84fOV?aDk>6gZ18U|iRy z?x2;?fQ3A3wiiE&mT*ZIg3zej6b>sVWbG{$^ms7suS>k1C`T`#YsE|&zb3~ulh<$% zVl1x>Ig@v70aj@lc^!B2dykQXSFHH<&Ra10UGC41!jGjqFe|2XZai^hE(;wM7cOgb$i-X+ss zb-V1ohh5x71n8rdOt4W(oO-E0`*Pxk%Va$(J>CauJRCEHO7-ROMM8_S$tVNJ!uiG=sJ`TmEA`JHeq}=5MB8@e~7!&rR5S|j` z%Bw0S2932+EIQ#2VeN&nI*~%AgSDAtmS(BQ#Z?V2cF~8wjSq{yqBMy*s<6dMEv3G+E(x0k7m&1V85Y-?ENJW5tQAVa5 z%I77tMy1m;F9pyhntc?KpadjhhK5CTM~y*#DICP3KW8dGGF335V(9f_)LS@LR1Iv5 zH9E8U&E5GzA}b`3g|-swR2FH7sg$@X*0dK#Z|XdMvGT{{3$A&bd=5%gHGf$Lc<` zQJMrSlIZscNJ`T4vGvRrO)PMn>^I$LpzKdz_9XY$Fmbr#IL%J>KmLQM=W$<}zT(3kH;DvrsvkD;)%QcOx&wbTkA zW81pr#k$DDLA2YdyVQ47b@i8@_*FzeGcITUZ-z+ppU&3pjPO4zDd#1Z8#fJRewxVDErgQ>>kMUS-e zq5Z0ou1!ytcV+EK6!$y@E&@+@LqbP0?p!`6M33jH0RW}9WG35flNMg7Kd|=QA{uY94Gaws&H6t3`pKhVnE5|1{85MF zke5Dts~jRi)gl(yd(54p=*f3H7G@OElXE;(EfNU%i7Q~21FH7)FBHlfpZ=L3D zBecWDJI{nk*|RkEDNz$Ed_@ckC#aZx($(wKqGlH}|s!ZtxY_=jVDi4DDV z{aguXITIx-l8_fb>??=TnQ4Y`(oZQW8JNh)k-Y?f24Yjn0LI4~jG4Mh%SMmUQ@#O> zLUO%V4Wc7czg={Khc1s`-_y{3cs;NFr5&jZCfvn0LZ~Dwy0sADtD{;1c^1!_=H5rTx)!#PS>wh3ldr0~SJ zz*uK5?TI`gF|9id;KJ&m8Xg|V4Q#)ZKN5im5JULAWhpR(XluBRS9zsUl zKh9B)ii%=GCRBMTOL zz=pZ3lGdS#Mxfv`K5IJx+~*u29$u+CltVt&eL{0gy+W4kf0r7_-k3&2rGfzI_i%xXL#?@~iW#!)o2z#N0Wk>xt z?Lj|SEZ-x%R2uOTsDZ5FNFhs$PE~dfRA!ISddlb~B>x1fWM;z3q#qp9&xro~J6s}w zUPzNq*1oq@|Igi{Q**-}3?)OvM_cgl{v_}b=NwHiYsZjTEuZ^TV#3jXuM$wC6MHuD>@KR1x zDSnBu*wi#h*bj4y&8XDAWn9>%y>8x8D$`n1>~0co`NFAn5e`yF`$@*bTxGxWP)x}W zQ?e!hr{LS~W5lmb|Bv9^?-O>(DlsWOzv+Oi{jB^qlIQ~4BT!oAlm-)Z!wg1cb=8wd z+M*~=2c-=Tdim2K)3B4HO7y;E88!}VygkcKnY8zO6sYTa0gW60RW{T(#nJCm{XVw| z_lDWS@MhZ&K8QES@9XbBxw|7AgS&5AK_JMNHURb$vk6AplvHYJ=PHUJqR`$$iDET~v zrZcQ$h;KL1F zg9cv-jQGC&UiE){;QxL||Mkq>`jA|`v%5P4CGGM{3}3gh1fp+zXY@H865I$waE5E7$| z=tc}xk5}`*YxuwUzi)THSHwIbkF&un-X;nz{;q7=wTvsOso)t^f;kU; zokQ4Q`U;w&*<(U{=&vU8X4q}&^ER|`C3>jzKXuZghWXPro5WQ}tx$|+=~;g%@ws9U zn;*oyr;KTK%ZYN$DUh0OKhS@y_`j(^%wSnG{6EaSWo+e4*QOh0W@ct)W@ct)X6itP znUfCF4s+7sq{Gb2%-ms4CeQQEC!LYL(dZn_k5kf??d|1Nc7eStS6#Pvf6~V!T>-;L zUJyHR0@~Vz#g5}kD!A^Q&<6(Yv54|1t<;lEzJMXKcaS@mNi~%6jTbXm^Tx{}4RfjV z#MjYb41w0Ccvw4`CKGRvOLJ0_V16*)*W32%P|KfGX!jbb#h148?nI2URj>wTL$ZXQ z+LNR&KR~B9N@xV+H`IKKz$U3#=M>A?MOh-WPU28O4aRde#bULNR7l6gWabdw)EfIx zZ!BMuE+~)2lt0#3Tfxzs!%CP01vx_>SYZ%3(8eT~%_FriMDqQ$KX_}mwbp65Ts690 zXD|?&|2C;Ngg>AIT*jKgB^WH!Y{nLSpq~Kj7Iq;>E5nX{RzdGKMl^y1?IT)-cSq)y z>k&$ozNs^?sG1aml{rPmLuj2G>uv`@ofnQjg&Xk|+rGnL;S=uyTc?vooF!%nS_Hbp z*C>!B03&AWY--WSrQ0zT=(Ep*moiDaB011r;SzlkpIF*QXRVt}`XPHzn3aiKxQYp<%a)wm9dudfODOmN zt#VUs1%zDt8t7u+dC=I{S;Yq=BEiPj6F{l69$P;n>r1YtOx3LCS61HbhH{O;v{t7O zS)yDSCz8VmDn3c7?)*UZ7#s?{=$V%Z4>z8Tt z9O9R0q$c`!Yoa$APFL#yeAOrGMg|-Ru_x6Tx^y+ipQ#D=<8X}3)`&KA$B!mN;&g~J zoFD7mg07KiG#5==5%mh9`q3XwsR!1-B3;9#VsRy9h`_-YpP7U3ZR_tCLK_${im&Q`d4x!MSQxgyZik=2ke0yNqxf&f2{t`G5DV(m%}9nX zG17yU!2ECsYa&!UL*b8Y*@oi>dJCAxN{eQ_Psy@`ZZ`Rs3oeRK(+W zL+VP5sywanwtpZPx^Id4eJC^|Xb~b*_H$2 z@&3Zt$xz9G<_m472^JcOgRBHDtoVt|pi-g5ny%vSkB+gf+0h+7S}ZE@Jjh76tFPxW&kpM9#Be>yV4u_=UF(ukVkwSwHyl!E~m zs{p=Ov&jw+0=ybgEX4>pt>zh%?6L-F7=lM&PAPo>J7*$^)kt2TiRdAW=iF!Y+LHYZ zePM7EBu)s1w56qmuF&Oh94z}Y(LJ$GC$4NL9iIFQ4@RwgOBG~f0MtvL?<4MBd?KZ9 z7>V0u)5oCxhNu>;lCw&u@>^936-0VlLM!N+x3{Ccq@tmYh_gTH_{D9H@Z7jm?{lj) zBp02|H?8@IruZ8cQ#Phfmzb&P3~NzzYYTLixfT=tPNXW_V^OLiZyfg3cJ7?q(Or>= zGV*zb1BXM7lvt^H@60r~*pwl)y!08dv9f0KSWyj(%t*H)A}8Cn5*hX@h7H*H1$8t+ zW5A}^h#y1U55DNILfsZK>orSLOQ<-LJsT1`NDZaDhFl8ucdrjxaXSzB;-a=nj(%Xt zXd)|gNN+STC1-2c2p4hHMy$z7V9aEZQb_|wnqZ7N^0YtlMW>Yr^&A-d|9m}O-x@I!t}nw`$q|B` zePDzA)E&(H5!wb$=4l;ZFOyD|qNH6%9^YU7LuLl2vfQr!l@J-Eyj=c^QbvZ|ea69$ zyRlSoJXp0Bt8CO&;tq~88t49XG0z&Uz>@Pw^XtU%tGSs%@xhMacQlE&8VUegQ&Slp z;Iq9YGULdlklF%HyDp}wsQdWVd~k#JfQN=+$^M9m@iR#Kqv%X7BP>8{2iV36mvbLL zlv&6aH(r?XosqR8@Y$a&I-KpcO70iSz|85*ThD;-rb9lhiE6S}HfvPoA63)j6}VU& z>iG-@hs7j=K-ODFeO*AL9xF>G(%bFY(!VsR!!WGPfN;V(Cv{<-E=k#vP;9EkF?VJV zU7fn=ju=%X*TxcUI23?2qE*%igg&$(>Qo#)YS{tg>s4MJrVRD^P(exs6csY;LvWN| zQzr<}m*?X^X1OY(( zhgD={gD0%%Poxw}`C0)GfaoZWBTeK@Pu8?Ex2SNcg+;it2i#>d{JiwixoV3$jBZW1 zeFx>p{&b`P=$-rzq^VvG+ukAgii;VzDXi()8lp03PvdN&Ay)iHp~L-+U{`kqfy(!d&U-1Cas!G^ zA8}#&$C8akz&l^!#BAu?n?x@ z>gZ7dXN-a$Kth6=DWdwy?_uvUB#XK!r}yMP?_X)E82cF)bvdSAI_r#G|4MqW_8zK7 z{b0Y1h_*X|@J6$$lXK-fGLKUqA~B#H2|>P7XNt7L=nqFU=|{6yi9~pXZ%Y;PfaNR+ z4xi?`gZmxHt`b661O(IK?dr7YEy~PIE29d zskD2Cp0QH&e(WWx=x%&%$21WgxA^o;qr=emc+(XkOF8*Of1eW6ogjb@Yp=JXx;b$k ziyiB4B!^loGOCdTn{1Rm9-%5O5aq<1UN7bK%9mT!cM+4=981^t?3Vick~E5Ov?I); zDFEUTm=}>EMoa1r9Gyx}m5c)QbQx}UI(ziW&)ws{oKzY(K}>C1V{3zJjJ1a;us|QT ze63Z~WYorLku`-%t{Za2S3&t(bR`$)x7gNY<&?qOn({?(D-3zXf;ACT6MFk6)Xyoy zuNjN1nR(ivGt=`C_N!S@ii=2Pc?O*G(N99~q~TqwT2+-W^Q1TyZan6y{OAm-IIm1|Fj@d% zllh{0Q9~rr;|m8C94BXWZfMJ`DCaQ|mG6#SOzQjcR9Z*L;J)b?nJ! zKL7!k=HT8EmcY5EK8xxvxR&ZzoP8DOFyABao1(!hkL##&*Hikp4Y_40&-hu327m zIgjiD2tz8JPms-g9CtJ2o+Mt0D~z38>&B07J!+>{hvsncGrn7Ig>Jkm`&N?z~emXneI1 ze|CSpeE>aVlk!=>&wTcTjzHboiX2Q^%^CG%CMTFFfFJctT`FRQ)ND&WyZUe0H z!FCG6mhSl4i$~1*5EbLi22&}HIWp8%U{J3je}{^oG?>X|xHlsoO{Y7r4-;6?){_KI+94I@>X*Frmrz@_a32*>6J9J?`jgy^QT|Tl? zaYo$ou%{?r;;R1rh;2f9dnZ)kMWuCoS%kgB?us2vn^hTU0$;rs|LMR!{3ER-`gi35 z@*BKGnrnr3PIDgac_+>hXnE$mmfom}eA}bs*M7i)zzrHc>v?a11;4cIa^v$j-yP;( z#3JK~N{hB7ESt~Sq_a*?NT3tK$a11aRlO_K6zcM=?jRqfW7C50Ii{ofKg>;cYlpO& z6?gvkErKLcKlZ8T!qui|2_ove>viGM&KMbgA6iD_PTwHSUBx#oewUQ*0HFQEQJaVY zvqO0miwlwHM{5=qfhO=)TjL%GYlRs~oG~QSX&XRIKHwr&M8` zdwpCtT~3@MG%#$NGVrRd*xDr2dqhFs7$4d(^;ufU%zig?-u9A5%Ts+J?iq~{{_ zEt;QxLwiyCHiISE@@{T>)o-dFV(7P!PijtYD*ectgfYWrw7;2FwkZut3^Yrr=Bf9*tG zAnQyYOC(tPRk|D^3u;V0-YQ)Dts>3t<5zE&{__-%$_VL?LK!-72|v)n%kMryB$+H|z=h)maNmg}`5Mq1ZRP zS+<0(yNX5Hkjhaqr#(E0-@s}#k0p%`YIY_%gP>MDx&z8h2x=ffe`UX4brNwP?q- zMtOE~L`y|iLJ#SyP_-K& z@3;uPGD}f$N{;Ld{jkCi_FpEFY>7e_?cPh?_53$w?loIFtBgzmv(61Cb}Dufif0?c zR*puXJ5&R}@0f&P#2RvwNv`atu423|3`C3LV~cQHHn0{4xN}z90(^eP--!UfH@S|x zG=)*8Vvx8|%A;>i=3(pmTa)MJ*n-drAZ-A{%p@mMLOFFzjI8LTadZ_uI=+?0cA#FZ zGCjNUrArPNxFcIPLoY|=dPIz7uk|A8BE^QI5VczfbL|ChiH*MiBi}%$ACGb);>Kn1 z+oxB_R{6=qvYim*98k$-Mb&l|34i=v1?t2iKB7}}IsV?fE*9BI;M?w^7m*tHYIwJHxX z?^|l^oJKNOPfxscRJVyRH+${C24+gTJ1}&sup@EQa$tkS6lcwiat@Y@vEoXa+lVYL zY$U=CLx_bxB%wx}fMjs)d%m<~qEbTjUG#*#n8yO5rgU;3vgBMCDCgT*l8*&|?Bu~Q zU60RV-<-PS7pvy)-mCX+6*UTFV*idOwuP0`D;$j-qG#N>j)|wnmjGz4Wr=iEQOAH5 z_*zm_a$3Bv1@K0y$8>kt#ubRnSiI_?%}_g)k(}SN z_Bf|n-8A*lJ$NNidf7U$rSmm(K<+jkO^igm#>nPvmb@l1kl3S13LM0WpgflGL>w7p z8Bun^^klUf6XMk=fVE#ZL9tvatP&z7jY|`WlZp?bXK0CxE1{u75KNla`p`;@zIM#) zhPFN!Z*YR!*~*x4S}`s>u`?hhlgm+h`rt~n$pD>El*iPNeAVDP)Hm_bN%pw#U(6($ z^x5zY%?g&BWtmXF8Y`0FQE~W$%f3m4*cHe8qj5unMu%1P1oNw1aWsxlsR_Ic z(1dBbON&b1>=iwl1GlKCm-dy}s$EbznyLh<~{x0u+I)NsY8@pEK^ z-IQogCfNDr1<@MYac8Ylv}>l`m($Mn)jLQ4uZ!l(LalO;P1!qB%=+>2-rTNIyb5xE zh)pl2YOm3wJ|Jwm>ldVb<3k_{RU#T6OHiv)7syf?p?EUNaA3L9N0-RTYRF!n{SbWX z<25gbil@kY!R~D?swuAE6n8>fWAW`map!TTqY9_96;@&AFv5wpwR?;pEx(TL#Y)RN<_SLLUg zaADa;ioRx9oisvbNNuDUZgic_K~FkUXbI>hTa+L#(5EPou_!8S)x1DUHrc1cAa+94 z4a>76J98Vb{eZE;NH?t2D7kRlfU)2yYjbmib2bQ+6B7?7N^kJ9IL50NF!2&gFz1~3 zHk+!0)!t@ErJ3&-c5xh#K3A#8`L$PS_L8)*VT{GIV(3DDVZ;(Cwl^e+!<|qE4(CVKVg` z3;_bQXKkOY%Abub>0jRFGezQ|2j+Z~VHuAEb?yof@M=_2DuD)a8$414oYRC`}kNOMVMVR|ujm$ek;V zrDp6j=F_{kjIFlnnBCJ2j)Z`W$n4(2Efn2F*BRBpxM|k**-bSlEj&U(JbGk>Tk)4}5FTaWJu!lJt(1Nojy)8SFUAOSku17_fEXlR^$Sz^9lnYX(1Y~WsHgEz zTW-pDN726si~H<G7e=Yf+~7Tr#?n+opv|-GrbyI~IfzL9SAb zO0(kUN13#H+IjHcjCQznz2s>WyE%b;+2CxB)F4*NGnZ`87*2jz} zF~mjNReF|ZmGKk{r%on1u^J`qG}0>km0aWFtn>5-Uo9=>Boqk^JwiS_%O)bhQ_uJsO8FGmvKBq5*cPs-Z^q0x!nvJ=xS*D9{Tot66^(inLbPeOG_*ED+G)B8Izx%_)nz1=o(h# zu-XEpP$Z0q3Cb=#rK3hq*sS$8?PGRZJXw+y{TUC-oKsIRpE-)0?jEVYzj9p32f6@X zK)!{eaq zPp{!trQ%6v4eBEST+`?AYn``W=^=^8R6DVoEaD3E(+)p+M{X(SE<(4WnAXLs9G z_nx!OW_(ay$BWyuDXZ*S|1xY(>qLx#05#sVsvM|~a$R5Jw`YcESoyT?p$+I$4O=Xg zn=bYDF%+$pkRIJv?AcZeZ)cl8?u2>=&Z<8U`OvQkIuUC2@ARR#^PJ}ZSuRlOk;|ORh#F%)|7-c;41gdCZ**=H-)pk|@_Lms%8x#OqR~N7 zBe_0>ABub6*uYK#&-d!1_x4A%mSlye-1hHw@Q?E=8)W{&ls`rDt}ZBNMqMk1Hdr;b zmz|JGo?J3`j||@o;5JzX785c|>l^*LO3-Uc!|pkWsoT2N_C8|)XPgRmbyB)ZmFixcB3oYge?tl12i~Fqx+(Eh8 zR*P?jx7Z0{AF+IQ{1@BU_uGA)UL9*+{F9L(vT6Z%)h1VJLsbg=>4iOUsD!PrV+O;^<*7RNQ z2Q=r4&Uq}F&Np9;-E=WmxU~vA`<1JYHu*ENVhNIm#TZ_Rh4JAf3V_NX-b{(T9!!!t z(8aoDwTMF6=AowVCat{q=bKy~AgrJJ}y0Jo)!ik%9iO9~(VMECa-?5#> zi@goMB~z`!cEfz!+!*v?*?DY+46&`^;v+(D;>wC9!<5GmqyXi^3L`Vl{ex02xVm6d+=ZMJDJuOnTqzesU|go4N&M`dm*Lq`Sx9?*5*`%YACyV^FQRU%3R__B{7*l0pQc~UVWwGVPe%HbJOm<#)?^VtT{a$l&N)C`pr7GeH~Hx8Q# zhp~O(j*s2cZ7n~c#$BdKHx7I9n2DjZ#4Ng zf3OMadN4DtwL~XNuxI!OJ+iFFO3fx{ndxO(9Wz1fs>H>T>QG2O^v+ZH8zSXYZguO- zHCEm4x9VzVwyi5StXNY{JIc2Sk&E_iV_b1y&Ajnh2QVShBNfB=%ao@Sr0>rgEBS|f z7l^I&sGInkLy;$FYKI{Xa0)BSJ`mz;ma;LsJ>{(V+%0RoJbwBR`zPTFZCh)i%3eD;L&%cZpdP&M1O2 ztwNFb{M%plExOw^gTW7519&U?F$RrHdjOu+C5cbL<2kR-&dY*nNP`^Z{8uF?4{O+} z`N-&BGZ$^f#c+J|aNfigl8ZXsUMOY* zQ1cb$YIo@T3kbO-+4M<%{@40_0s0EqGdy%lrPJR6L3|X$1H6LDhRaKcXySU$)~^Tj zfKy*Vgr6_US;JLrCBTilpz+YX+92rps**HyZP%w4?Gf${_;WrqnTkaK|4tH<=K(W! zNV)oai_`p?XwD89hODAA346Jok??y_Dw|((i!V(r@Gal7u7xWEHR6Yue@>$PbC=8~ z1XADKntJrI?%VsLSqN&Ym%h-_`X zW#0p)+OeZn2d30<9?nlet%VAgfO?5p?69IXf%rc$mQ z0Fw$0#6FiT2J~e(Rr@tMX&USRsx=!WxtWBr4Rl}A^ODp{q zqORY{hs*vKTuHE5o9e$(vl~87eyD z1=qC1ByromM}zrbd|qt=7L`UK?QKWBkR^XVYxX_!rOHx~=q)xJ@0no55V88mPz+L` z*%Lth zg#Mol>Hp@Cf4G;g>9y})yA}kqP#|5%-|%=KX>kRy8WE$P|9cUjf2i}WZr*n0|0=&+ z>S`yiw<7yb*D5)Wd+W#m*unu`7KEKmk*M*>QC-uzNYK&|(m%liixLBVv^ysdiQ90o z8k9D(7^G{81X!`XitNv<=Mmi6xhRI3b+$t9S)<8WCH_r8@5tI&p6(7A-zi-e>^fYh zmp$P*lun%&301*orJv!FtDE_XC9*vto!4 zA^g<1pg!-5UsR{;Bsi1%H`OBcRywP&EJKQDsWdzTZKAbS=7g1mvIlo`sq-ZFDk^X% zt#TE2qFfDZl4_gAD9*6+oxbl*lSYzt!c#~64`3V$KE_Cste96h6=4L^HX;nUeNRd8 z*vmMrZpIZl?xK}wZIK2*F5Q~ny&Lid_L-AMS+G$Q4CHhGCu#Bc2f`M+Y2OM0o!5qLe%pSyymjzhY5jC_HwcYVx?3U~`>|!c{?~8OSJPCLCy!^Zc$FCIxX-22A?P1Sjx@wL=G1mGVu{25$6Jv0G@tfp8qmp zbNy7GuJKfw>emaa3T!<*Tsyx+%tdV?gc>@$K!|wF>p+y3it?+9CTdQNN9`S(U7g9- z%`mOKHL%T?2wE^QLEod#jNVzQPS8cD+)pE8le115U2mZPIy;Jdi8I**6NH_b8>Lhk z8O3MxVhR%P6Lw9*cl;@soHX9;=2UVsERB$74lUOe-+S?%K!^oa=RrE@=rn>b#Rid# zVLK4cs}m^MLqmcnH-=GYMgu&*joRx5#V^ce)P_%v3nB?c>7@{b2|fHIC+}bK1R&x) zVWrc9v08TTD5BvB?r*vVVC6suD4v$!Ufm*z;T$zmgt9B$lErhaq(MX@xU9{tLb9 zexF)j*cwm7T3mEORH-P;mtjRSjy6s9AXhSK?}9LzoHT zBg=B?ts@OKo9TF}pNvG9B$E;1i&~fB0!pskM(F@VKP;gHQcQ&vO+KbvHz&U9k}L8g z7h*H-!l(g2)1=+7dTDeP;lVCo0!G{`7W=}*=m;y?plmEB17}CG(&KM+$0esJ^Ohs; zb@mG72$)ZDrLqq$wQe^v3?i78Ena6)xu9tXrqDSF1Czla54^6;vnf^v9~65IjS^8@ ziI~M^4N1*G`*7YSa&`-kDLOURKHrAkD>HnGGa+{g@g!6n9)cH=AbeHzu)N2yb(_KN zD!J13e9yf9G@Zd}No5}bB(358Y;=Gx*#Y5eN#N|=AcKMUR0>!p9OtM19oZiPpvIDd zt#FkZa?zN!H?vAnPb?c_8o&di0V)pcC5*>EzB3*pibUg*V(ZeHWXu|I2-k$JaOitw zhxklj-ti@Nx2`+S{CO0DPE0Vz^~LwF-H`OgFrc*}8DvNaNZG3RyMe@(CCO-Nx$q>| z*uUizBpiwWON;Jh2oY?`)#}ijcVpf3S%9NXFh4R-5h;cm z*_!Fs&unj265)ER2zjmC+c#YD@^mDKRbkN|1lW(!Dn=7;fzva8*ZE%U`{zybwBpIf zv!SFk@*7mr(KR)BUf4q5HDNqAX4!NYItNmOlz_gX%r?=xID#3ZVDu9bE`;K4>lfG) zLhhHQ4)eDIESKdyG3Cn;&8n6R_ROqce;noZxf51w;CCShP?*`Mr59QTxKc-whBKbM{ zy;yW+e#38XvtRP0#jqRjkYDLNa|B2A^RBCl(C^|-CXYDp;b%gK6engFV7sYA&nr<~ zKdU*-8{}uV_Tz?&cB}Z6Ff%zWfW=ua?2Nwz*Ty7l)7Iu+o^F3S7w1x%$hU~Zc@#a> zVfsIZDGac6H!9r6PJDz%E=4Um`&3ZJR zNy0B5O8SO2M@YYSRh@glb*k{lvG~NVXSSMtd?}anbFd0-GVWo%3@Tk?K7*rM;fw@6 zcN=m&fgCT0m;L&l@fG$X5B$x#?eXBgaeYVZASomHY7k9v824CdIB6-v?9u9}@^sPW z&zT3N75+3qE|=xBNuJ4{V~Gpw{%)N^a1HPH26Qz`zPl&@Vp6Hn=w&3{#fXLGp zwKvb)&E*wKa`L6snoPc~V{%Q?q$+okw<%;l}_bgbzv#YS7`wle!hVN{f3xL z*C&o8$Yn@t7u?MQSdjXq{QJpv^>;i*l2>Kc;TmB!}P2C0kmGDWQF*7sk48jjIrW8gQ> zNZ%Ctb@j)iW{MCG(e6-v0srfHExVSBqs2}BQ5rvXQ(S#XYz|-B4~wB|Qx3J~GKiNp z%LT6O8zTZXOovV5bAn|i}fo@Eo zyg%F^B0@-8Eqo!&2_X6Nr-H&tR)WJ1-TckBVt7Pcx7WC*PO(PfKoIgpR)qGi5vwX) z3c!qMxcKS+7#JABq&!9{A{3(GSCK8O3MR_Tth7yKK2YUa{f3v%~X?pJcSgc91^ zK|tk&erWtQT(S3qeTU516mYeu_&im6TvkTAWDpai6Tzl%Fh-?0VuamIjy|KsU$Iz# z*RdH(&?sVwz7R!=$YfS^WI!gSxIxInaCFvR14-|<(Nz2Ov-yoHdT6Se;yHnIPiQ17 z+$6tM=yze|yM@H>OmVN_+uTzmE(Ch3#9n2u!KTT2fAfw0e8h|^FbF;icQ7at^rSE6 z#C7#-tZukq%bJ96{Y`!#wuD+PZ;b1_lXkMXj*HH46cXxciG!>E zJF>;)`!7wV|4#oB_B-@7b#!q1M`QL|_3%>X-1R&5{o3mOX@2BzWg(}mxIQ=7E`52& zUcKpoQyQ;G5D_A_K-2@0V0Ku0%^;+*kQI}2AaKuO8QEiExbkrcvap_)r+P(SHYXQF z+dXgdMu46elkrRcg^I^KiptBfT7HofLFe%ZIbPe{igqIvRKO4Dk1cRv<-+Ayd3 zeqo`|Vd?*&*5IS0*z71|#X}I~)lE<+mdUGqZ$l|++9DNJsgS(qE{ZCc42cJXfCt5t z0)yVAPDt27ke+wwHCsTsU50$McfTQ#vyu0R;*u;8C}(i*bqkkSQKV9r?U#{F9YyIj zaKTW23l1UhRx6x#Q4xt410a zFae>@l?=m1WgU3dmA1qTMWk_;;mEtn)>YchI_r95TPRI@G&bc}U<$&yDxzm&B5Sc& z`*M8vagN#g!=C!Y)0vQ}-bS$T$DRSS-J7cVz1~yyU~-H#giKvtq&g#jPYRvAGaF__ zO0~r__>o3j$obc>{&t6qGNj0JDa}R{r&1RNA(X&-0lhx+B6tMeEiUk>w6e@9Nldpj z;yJW?J^!$|mo!Z-yKjafq6pPbCVir@ROBhD_;cb`IF&B=?N%Su?)~{^eF|pg(ICD~ zxNGCN&$jMLjjZ6#he)@rV*(T{UjI_4fFOrZue3XX^K<$2mK326*p!ibrzF0{F)d^0ov^?oJomv55v$2>+3F5jKX za}BGJ&dXW&u=p0UlqGIh+O}|_uA9Tm6NeV*52hjz5*V8(1D0w|Di#Zph%j*F2@19E zxkHD)(;TFyu9Hlp+K&90Px+e7(Y6+yPuKdwv<5_X zp9_AhzB&C+>ag#tEyI@(;eVh>sVy<|qWbyK~@3M-3jp58m z$ZcH7pYOSjf?SyuUN_n&y>LBRsK-gNe4BX78*>ZG@3*w#5N@8w$*9IT^9!2(&)j2Q ziAh)pJ@9JRaumT^(2Mx;_KSobXYgmUcwy(T8|8?T;2eF~;rMcbG)^>LoTUp?InNzC-jN9(FX>gfAkdh=V2E80Kas-H zjJ_fhrIVS0=h_)yMgT|-QfD$8M##4;WJeIKhmEA_Hs?T5IDV%iozuz{A}-WM?@0-W zb-EnI1GvJX0?2BJ*=*v(*P`-?O0A!?Iy+~5Pie$oARKixius%|%?D_Il(Yid*v6Mb0G!-S>0%S|<>{2T;e=An!Bm4K4*{8oWW&_96s9rg+2p19jjuJnx+jNQxcR&U#wq^_sS6PKcs5#el zSgoZKl4t@=tW(Du$q6Sd-8N_h^>01dJ2W}B(Jn0>Cp2@~+*%ob52dVZp%p^2io>e7 zbPcg;ZVA##67)XsFQ$8lh;Hz&8OtP#>|Afz-*ia{l_U`A@H|e!H?AuX(afU{*e<%> zDrg{`(JnRaYh78IIEW}-R-?*NAQIZ8+3J%h3)CzHha7!@`8&b@6A(CJJo>^D*>TVa zQjj*k=DeCd!eYxE$f!ywh|eEkIdxP0bpwNQD(QcC?{0rhMXZ?Ohd}P?nLLB;RFF6Y zdBLHeJFv%MjqnbFFZ4^1m_QU)%ruPEgw-mBxM03_AL6)y8u7Eqb7(+&&4=!*rD?1J ze%BY4J?jB}AtdCl|q?ahDYYX`3?z z^S5@G=rv$%d&22_+)a_AIxvl{zxr1$x1H>k9lk=#XvyUvx4DShUEW@-k17|Qprx24 z0;iuMond_*3;2BCzOCXLc-Hc6Mn~UyUiKdTeQoxf9RuQX#Zce|iksiN^ zGt-JiLIkq+IF`Prki@mjU`{GbUGV8lL$4MgY!Tr3aB49lNpoA$f z-tP96wLozUWCoQ2DNhQR-i3{q6CZ0sMGaB5Biy`&b{3B6LO6DdZguCY7MfqL=6ak- zU(2!-rc3YZ-_|tR(jeBd1A;OO*VnG5;2`Yw$`7bqEsSt{6yJ4R-%%}_Srrexa#riX zb985H2Pdlf+s03o=eoe<*u)6=VZVU&yFK{vkio_cr)bD~yI_csGrfOHyu)=9d+T$z z{jJ9HZCyOp%oBrglnAySm1@ST5*=(=ul9|@?gvT5x141*9x@*n4lZcGJHqSFV#sXc zQv1Q+z@Zutq>u___<02xr{seXhgSKamIWWQFjk?#7XWy*rWd2>61IUs2u~6X=)5TC zA)DJJ)SFq?O~f|g^2ZEmz6!L=XN}Bt{S(>(hryL4YnoYaK0M%NsNj*%0gk$|^2%xP zS+*>zBWnS=eBWP?vA{;~{psTdK9Db5swIJ-mwK*$996SZk8dRm4`ILpbX}3n7P>l@ zIZ7*(!)++UgB%h3^Yx}HT?v7nFNJKB~ z(S~;-zE8n%S?d)W^0j002oX$}bux4N2{YU^d582(Zr_7*h1g^c$z4~0v{LG}zbntO z&I%W4!-rQ7Z4J7d055f_lQaN9WRU+I7+5gIwpGEGU&;G$?fK+6bNCnHw!lFL?)OIB zpbWK;(8mKmRI48(K@KTFr1u2qDKa8f{FU3xKzrlsEwK0K&z>8ceuV6wk}1ml6qlU@ zL!BtiimlmfK;umPgx*1@n~Et;1NJ^v0jod?9`V)a(l1#Z{@1#g!Ho8X$!E@=NgBiPQouk<|&+J&Hhj$B| zKEUD@A&YHnyi;#;gkL0|q?+A^t}wLewda(cjJkaGUl;-J{|big6O5*teFvu#jQG;8e-l)Xm+++?A2}Tc7hg{b#|-!S?SKi?|pUH!CL-vnVsS zgor4MFssCWuO}KugK%{1EZw{pD?m)!EMI>f! zO2op%!bZgOttZOG!^%RWBu^wNu7-e-6AA=G1oW?7WA??Sb~4^_#?i|c_n*NuSSS#w zK%(B9Jq2lU>vo$G-!Th@HM^^02fIHq0W}#})Ri?!YUIil45?z$XoK)OVf2Z}ySwAu zmJEHQ*ivMH8zlUsw=Wr?%)n#`3d*N{DYu?FYhQMP5kW{uNMtMKPhD>I#ABG{D7ZbZ zHi*GK7AZ(b#(SH80DtfPPRFSr8Q)@@5fM_dXd~YWqu)uVQ0Uv{JI$ehvmpPI64R&> zBLB7eEfysAuMvP8#_V4s5_)AK)PJq4BmXz9Wa+^a)zz^~BMMtD$G=Uv(f;wPZ8OD9 zk(^D{V5S|#TyiOk^1XxU|4xSg7tj6wPp-_$xsONg@N7xv*lgcirkcpWYEsB;r<#6H zf7djr!yCwV&BT$02>n~uBp*#nB@4dI6;TSxN;>14TqPV~W4|`z#l;ScU$bPtO%=pY zKy=jyr#(DcRn*^In2fN*?S^lzhDk_n|5Fd#$Um-MjM((wgTn#mmE4xO})?oXCFb@h&*i)gz2J2vu`$3#tQ z_W^yeDa3zkn7bMNxK&SmfSB*mwFVP>IT|D|@A4u+cYKm9=TAcnV^+K)Z9?P-_kUXA zaPt+OW-iLeW8D3S$c~MA{VpCOI{1ExhzDcbOY8b!7TK-?o-I*CL>1fr^ggaWD4PsD ziVCu7pbQ02Z@a}?zZ37}-M=AK zuPZw7o_;Gr?wFmz^54F^Rc?XpA@t$@objV0X}I{$<&GpFd6iUXd0vV2t;87D3^Ie| zGQx0V%B*F1Pc2LL4R2mu5hcX);=APVqb8CA{_Rnc9J&x)&83%r0rp%ixFbLY4QZC= zna+)YuNJKJ%3@}#|Ms$x#K|;aMxKPr#k<_^;s$akq5i6?@7+}G0zpnpF8Gh9TR-K$ zS6&m_j*fRC%1lmiYgjV2q`sG3=qrVreP=xv1Ox8Ln{{&Dj>=lK}db-(V{{kk5{XJrb-gMb_(1~`vhB=Gro-nai7 z%V(>O*q5q}GfKPYDxakAkbUf&!VJXz^#?D|kSNK?`Mt3HcIa2w85Lc;G{h={EQJ$^Nh&Fhu0m{?{|24AoD)Hz zwh{lW!+jPa6YE|ZvqU!0xDD$JrQ7znW$)%f(dGA!(aEp?_HJMhr~ps8_=EqAGJnRs zMQFl>5y(k z{}wb<;W0zA6pQPdvckUCCN4Df*1{U)cT=oOO`k{fXz0EmfHw8Ip25z7)o#}`D(avD zcIu51pb_DCthQ95|G)pIH!e3+^4PtRHN03CqMaKtIPwr!gWcd*FePt4_$eXP3}62HzP!P* z!dTQZ+oGamFL+1?M2cPQ`we2{kk9M_-jNU(jLW@Qz z8P9L*9usBoVxK05ZLhzWlp^CJ=Sj28#eVVfiEgraVEvc2uc3Q$BM4#F@INz_|4K=~ zDcFEa2fg|XS;6;8`%OI62*rf)-k{Is;&Xv?>b)Zz#0|Z|`zpLPqUZj9cM1gC^RqXs z*!tC#(C0B4m;Du~+vDt{tJ=wbi6{h~4D+2p*6aEhi4w5DN zUXQK)F$x|iag$6Gb9DWZ!Rehb7UURxX)pMK^kZ5xIq{H{Xclp-p@DulqYbc zn7^^@a&z&t`z>s$GR3t}wQcqhgg!nw@84#htojc&Ey5ms-t8i0mY@1zB<6^&M%+Yk z7ZBfRB@LnpKz|7(3yp{nqW_2LzG|xqnV$W7T79`D%GWdN9-AyitQ=R|#yojS#aa~e zs)u4YTML*u2M7$^E?~-Kf(w@(;jl|( zumC$@URnuN1+b4+-``p5{`(Q#F>pn0gK}+zyOp-vEX2t;swzbwQhd`~%`icbzy5NNBY!O+y#k@N@AoVS)5TQh02H?`{8NA zAia3GJ|M^BO~y)O$U^WQlZ=#e`l$NJYQX~F&pj0SeYt>ct+PmXljYGp>f2q(X}*qw zl+-{_BDgpn0?#TD`Ztq_I%Bj+r8rL8Pl2eMKEIVm}Hyft^^SSl=Ew*Uw>vCE& zX`~fOgEd0xx?$h-p3)(88=D9?Tm~qF;diI&a*n|lgFbpNd$4sIlL|v`65LKr?LxhI zN^?5iqq%!KuxY{0ur~|#P3r=HyZAlj|6QOnW_nX|fhqOQ)`eN5<`uR69)B<{r1d{? z=w=gON!2DEP6z&SQ+!H8Aet9kS_FK!2Q>~K_B_bDZ%9-Z>W`bth(D}iw*psHe*PC- z2O4-tK&)D`?yX5Vh)r(4*8bP#FfBXtg8;bVTcrRL>Nb%5!g{Dm*^8!{%2;iHk+2x? z?gJvF2^)txF2=%9+;fjccYXEQHAj-94Y^|@N)-RQKa)iVeRsrFZzKXHthk&#~StZ`L^wH?5S}x(SP1_U@Xp8USo}2~V@SKxWO( zaAhW-d2OL zL2PMUw)*vA%)A^5B00jCCjjje9TqqHHO5FM^Ivu`@TSn9$6|+AA-r9QIOpQ1@t?n~ z9cd9+a;s#tgr5N%vPh70rfzp%iCB?@!zc=E%%r7%gPu-C`#-}-4|NAlBdQl|8{-= zJQCsJk@phRo*>i)c>lAfWp&-{0Ut#3oZxtn*HgZm1H#W^awEjG2U5 z1fJ%uNeF3lzCF;Fe(R9V!RUE00}yU5{CD@fEjH)qZV;8bg9f05LQcewFXk0k!zxpR z`aFWbASM2V<}Bhs{CJU|`7H{`wLhaH%3F_RRzHI=4d#i%1NutqNfm9!e18k|h6T@D?)Br4?6rM#ygb<*+=kt#e^sPsX zUx~b<`ZJx;VRiy1LL@=-@Gdmk%37l(!~$U9m;XlbjX=xiw*)_OKl9=Bnez=LTrOL*|I=3VJi0jQgo9cv!p zqDrCnYmrWMCpwc;zO}kzBNWJ}(DmDZ!Mma#U5C2WzE=UOb@Perv^M2SyrcA(@e2@m zE+2_%y&1V!d>8^(JNSoIm6i*%Mu6OS_Wyw$#WqB(OY(g5f0oH=H<-$=po5tU<|Gd9|K$Di*cM!$n|SzJmYUl#%vjd%H|o zD(~Pm_{}jLq8ws5U9|)rStUNG+XVpIU_cg<$Q}ErzSop`M;Yivw< zMTfZ)q@xcQYW{!!?=6+-t}=kPeX<_PAwG8!hG!5MeoyGX$p|$>H!kZLe6^waGi)5h z*s23xAS zlD94K;QBs|e?#guD=HdIxii)-=`v|tn-_tF*|z~`B$*ZiUtH?pxNuGtkZk?iPa&HV zfISZZ;?zOAmvVmAm&vBTj*vMVH`zx0`$pGE^NYVh4X~+F#868+?VyRRvDCA8S!Q+u7*=Px} zM?Clc?kWZHjc(L1(?BdEg3ND;z)0L2WJ7NP^8k@Q%iRhYUQ;X=5?D+1#~xWL`6W+0 z+(fraB!&@eL5zmCE+KpIG+S)p))LEo>Pd_olQB<6)a#6unss(T&N2$741gWWNd8;f zC7tlm-ExhNZ0S+ar*!eCVG|R=qUPfjlzQB6)js5!ByEL-yJqMW18;Y8_?Kh~y(&8d zoY=hIT`~(e@g`9n<|9w<{krhTh%Ba-8eXvOJmx|aGoRgu351ZeQrv(r^^5;48FU}( zq}kMMRs@xnZwM?sr&jIU4PoLz{a;2F*HkX)Xh}-(D&$M zMuV((Xrv;mUIOp)M&PKIkS@-t&dJQ>na3)5HwDBO_}Ln$Ezu^>8kM6#NO98adwsXP zyM0XK*@lNm1|XVlP==nRE;D<+kd}D7M+Vu;)Ns{X(s#T4!`r>s^jA+qfx}qMxYr0V zSBoR*EUc)`ZG`KpFhYICP1JPp1^@&3H{bS#N$q9%XlwRs!tdyfF(h7YTRCi)*ht`c zr2-sIKcCB`vUI&gyaM}``8i5%8q|pC{L`2V4%-nMQN`h*5kv6?E4lV^^R1ta5@xPw=*}Q zr&srSBK^)VPvTbDD75{16_k~8B+}(>*i)kvs$5A~phor73HfdHf>g-4zx;CBL&kII^zFTmA#DdI8C?QU{0|$mJqH5?QGpflK&n$p z+8VD*KqAltzp)NNhdOp|B%A#fr%2oc?LF1&JJ{nxq;TBD)RsaMgZwM>D`0+OGB}Ve%j?Sa$a%XezTOJsl}1!?*5sN884krZSA>hSu(`CTRM(jHBTuu zdtQ;kqY(j>xEUEC6p6L}IRt_#0M+Jih`)X;#A^NN6;AXxYQ5Q2v1t=^GZa6)-WKyC zM$W^NskQxkBM*~7riTRjYBRs%&bpBk6({fISwajE!hr3%KSluWvmpOWJoQo8#`=^I z9zw$;wVDy*j){8quIxDPFsw$RNV;J3+ig1J9oUE<(j>HmXw#%GM~>ZV!Km*w5F>%? zLH!eW5sf;xxj-MWLAQl$a`Dzw#a+qARH5gq3gyx2r)6cwZ`}i0TL-2e;EjUIB6^V3 z%WO(4)D0dzH){ER-rBCIvHGj{f zm+My7b=mkx9Asc{T01hI_<$_YTGj+eAy0~he0c{a94b`2$m*@BW{hiIg5Qh7n*UUm z%vy8~SDoRErv6s+G_6+9roW+LDFlzBwq!T*jv2$D{v=+u&e;8Kq1@UUv*zV_WU7`j zV`$)-CqOMPZb#Qzm7-nxRu5n^Qs9!POdJTm;OB0A+YeO?mh8&gno^~Ft^GrDW-sS+ z!pY&*p7X#?w0lWu=@ZW~z@Uv32StO%w&>A^X%RgtH{yEr&4e`xOrP47`b)U-tV|`X zk(#)h^2h3{-V^?3qyFZQ==z@ukG1%wRz1cyJ;YxDop{&~xofFgT}jnw=@+za&Zb{* zBc8wr2)~E=#5J^!jF)hp<41WQH!zT$&Nq+yovZ%BFXC zvR+a;KRWhm!RQS_E#=uI%PrqBA@E$_QqxWnaF|z}u3|F>m?~i0u{HB-TVVSfq?f+S zE4f_PY{{v;aqCz1bjAvCC-sQ88{RRjeb!f7oCDR2=SI2wRYVqq_Cwtc-p;tc6LXzN7q=0_6Wcd({1r&b#w4g-p0+K*62*Ux{$O!( zyfV9H_v>X(Bn8)83wI260?(T=v`SPW1x@jqf)pS9D88&ol9VRjMbNfE5Pe)WX`L@s z4$3kwHft-(Q~BtFTp}dlX%7t7W$He_`eW>9{r?R8efbvvZ3^%C>Ds!3%~Gn#kj1FF)*1eh90ZO zhYM+gm6%vR1#{j! zv#B+vj;UC~5;|Pj-?%){IJ1Eu=b}}4J$u?n_JIk#fl{4t-9pus{9KgAc{Ry8--No| z_oz$m{t*KWl7L(oxyZ5=-5p!aJ;0=FtL5pS%g3gG>G!`<&qQ?o-TzEs@Ys?3^r8p> zPK75uV)_jByF9sOPF@xTNNM3;E6TX~D(y7uW?o;VlaZjX+BK?yt*g;-dNxtz zMYMUyn%>sLqRp$Wk2;6@2rZO5cUQwJ926DH%=a1@h&0Sb(h)B0h47ElLfmL`KU*WU z2a`YsdS9lIM?U$m+os%iPibarZ26|`OGiiWuB_k~=zRhe)Xyt?;9FEaoCH3>>{LEz z`Q^KLbj0{yvUg`20!^5;pV>Crt_uKcS!kgBWyok?M!%aSsv+|H;+;eYJpWRaa*9#Z ztK4b(@fn?3sj%Y)je0OEL7P$I4=Ir=kB{PECo|>f0yFX)qdv~kw}T!UH9%j*0=WMC zSdP7j@7?L&1Ib6l_HXdG@PIaV2fEQvU}ZE}i^a4@HDL4aX)c>E^_#wXHX(h!1k zA0+v1c?XvtVqXyy-YA?){NG6y&I@f9TCp`kt26viH+$fiI&SEOWS&!dk=J90i~bb? zzx;yV(H(1FO{?XP38g!^9in&x_Ti#KSbMm;6&G!+`st{@lNMiGffceq0|TuT0dc=f z0MrY4{0Clc9PX3|ySBO=^ytep9H1ImGPeIJi#PK{1&B2hcIjG{RPZ}y22-5W%=>;1|0;g{BO4E<*h2*D zdU_|#ws`ebPF9jGKy@`M|ln}I#2(v7r=cTqFO|l z;RR$>bL)ASWY=FKwDfU+KS&h8)7N(_)yPLyx3Q&ra0?C^nW$5%YwC92Vo0;feBn#rULL!9_8*CmE& zS7Eji!p=SYGlBk+ajB5ZZkG~4Y&1}9;OffSPtA9!?7}0Jx$lk39Z$Q?Q}F?rJP)5= zZ2726HVa=Gmz}Blig>in!4y3Gf#H~RdlfwTM6QslK{ zczg|5z$t}C2jVd+YMqFh=Sia4I_)mu)Ch= zA_}6a-WLywMLFd$fAia#PSNTC8*Csh4pob+hN`Q9GhTqGGSwah~$>6ivr16l>4cZ z=sXDB&Ud-Pr*D0?2&qXi0y|+9^I|1amx~tT%k$f#xo}OvCX})AF9cOEMm&YkSL_uf z#XV)Nj<^Tp0IN4=;~QYV)pfhHy}f*d2McL9-E+j|9kN*EFsUv4j*4fgy^JL+|E*MBrZl6zI*n(Ul-7k`E03fvjqIU12|=zUo#$U)2lAaR!wx)SR~wC9H|hft z!J4n4Li;8g?}*_iYf3AHxyHj&c9D02L0bxsU$obkG4G#vG!YUGnU|ykI|#EqQ{>eb zfL>sM{7)-T`tuIMeDud~Wfmfka5U(pT<}40$SSd3u>HcV6s*VBjz?^bXe0>D-2}?k z9k6;G(YX;yUQJWcsMar{Ko9WV%__}(y^GZ)FWq31i{Tgnk4g?kHCm6wfL3$XGPXD(wAkIrrNl<<>nZ-M zF`Vg#=Y!8;?I&E@k%y-RLdS0p1B_CRoKl0@%7M4ud|Fk8L^IuPOUE~7;7y$ddcB$p z$Es~6X+LP!x52sMz7(*t?CBILr}=|w)xBcOo9dLQAKac0s?wiQe-*t)9@=(;E*p^K z6&8qw3q}G~)W%K)G0}WNH5lDplKNA%?|!PraPz22yWHJ%g~Z0?a?k$f%b}$sE5F#E z#`7kJwfmV>Ei0f0Dn_e$oFr#w$37?AwC-(mC!>~>44YmZ-`tX!QxFMLcA$C%%jb&o z)wTl?`9pt|=|pKXvn{g$!<)o%D0Jg1eQxzapSZPy@J9$A&ZW~hp(uAzVdt{YUB^Cm zt|7|M&;EK_$9e8uxVe@>`+?;C*i5GQDt_uv9unD^#4v)UmBb4=NRo>zi;sP#*&T0{ zT!a?TGac57a{NB*)=JB~^d58$s9r$3_LF?#pVr`SABQaPa7E^-K7J1HjO~)BUH@}| zg|X)sgMWDet7#Tv**S3Osga*GGit<)hO}Lp*~2;)MbdD}&yD#GJRV6hFE0c;U^@lU zGfU6`@wDrEk!7b$0$+>JiB7S5&VU_OAw?lo&`&IG1Qt4t_EmKYb zL5L96zn(by4Yz$g65#cE7Yxoohq;Iv7o>o0?abUZyNRMQeQJKKrBL611pjU=qrAoT zTL6|xBPvVy+G>W>ZWbuKfU?wnuEmHm+F79b%$PLD@nL$`Z05BZe8V^&<-O|(ZHGPQjP=7gpMK)c)`0g9;TZjXTH;ln>BS5C1%Y9p_L9qs6=&*vHdl_-Yqc;hVCeb~g<>%}zv& z@==UT^BK%%PQ490BBHjo_RM7R8rQCL4Qxu|YOCf|H?;2?p+aFv+`3_3iY}EYX>GHu z0*PW3Q>t}FtAHEAE~5hEo>ro71SnP;gO=Q}t}&c3>ZiBm-p-UVAtN5~(+7!g?0I292awB?oc3CQ@D-mwdFvc< z8gwodWg2@~F^8t_1<$5dwu?Vn)LEMXi)h3A{BwdseJ9OJ)iWFErTyNpsQ#pp5vG^Q{3Lz@HHKW7HGyNgzk593eIBb;9B_~k zxK`Bx!JY{edQ$YPsR)!wmYtyQq98tl1@2uRoNLyFUWlPLoID-OiA;B~AjcdliWDNj zjk?{A@lI`w>{*2CA~Fi{2PzcPUG`_p&h`!@IWgT-&CZT#>Z9u%ea1yGAI0O6NA*lj z?p=?v@UDMF2FO`*4FwR+3YBeptX4KadO}S~Qt-XX8;7d2!JG;u^^*pFIh!arE*ek# z-HiYHmAvowlNIk44sL_bYSc@hTW5^Z!F_Sl>{gQXWU4z~5-yH)53~n?99n~%1a-vO z!jXgC1uyLE07W0oK`BS+7d4m?YfIq)NG|QYOz%9r31pJWs!GHwPRGVh-O68kR%W57 zL-y{aZ@Owja%0fgUvRodiAi<4S!3Q_bP%4=lsBuH7Ge znLARH)~{_KFGTq}6g}gfSJsPpVkvxB^TohwjMaA_wl9GbW_Fg9WW5$DMDe6fc69W( zroGy%qL#@!;sn@$X$g9>3+6lW;yMr`wYA+V_2k!UZ$HSO(6jiX>{crDD)aMrz*=sN z*F3&&d9aH8#id3-Y5o|%#aZTyBAW${3PwKi_QpTM_6Yhm2>49O-12I)wTXxg9mP!z ze)-Wj&2=t?^o{{dOWwG}X?sxb%aWfqv$l>d{h8wuGC@M9W~Xhs|Ofdj=W1@DyDmf19&9Mmi)TaQI{?ke?v*&q`3&YpJ2&?)@}n}je?|EcD%6eA0ewX z5+bA~2BmdE1zaC=$9RMddf9X!ojj3qfDRmITf?5pqU_jh$?wgdEPkd?gKr}UoS5hz&X7*GtPdjxZEv;yTv%j zc58>LVoL?3RZ%|{ZHCcPmVK7}9?snTe>Xk|jTD{s!S6VNH*ElS-dyG2hPqjL+)Z}> zSuD=$EO@U5){Mnl&1k1;3<}4^B>4%_J3qrDn%4bkAVw%4zVk+y#+WKYFs>li5!&JC#^<~Y&9MnO-m}y4uL2m@H~?C#t~D2;sXiL-awClB zk)-D%EGU^(!Y9 zHAu!=OJ$ZEfx1K#{OiF_`HlV;+hYQPk9lH{N>Bm=W%Y7ImW~!Z!K{-6m%qe;v+JXS#7u4!XkRyK>2c_ zTOjhtu}%Bw!Dh1p$B1tSG7d>AxAw6BbcM&L*EbdjQk>;YzWpp}2}tAv1OrhE-@EEh z#JnS;pWrjeqiY$U9lK5=cb)^(_3{fv;sd|oT$Eyt^$S5=vh|*RSu(GQ7VF~78_xE0 z8k9(&&Xh~c7(e}0P`N8QDwzB^>6BWY5Vn9ZI8Sp&m7k|{3Ft(euA&@&d@etHjzmEII^MedastR-dYrmeeTTLtT!H?b0 zzl+9{q4?~@>B=P}p1j|wR>l9t5>=Dl*y+Y|vQroFg%_1mb-N=6<0ok=$3+jKDBrkW zuS=1QxyI46KueC>?lzA#b^Zl5;uWYVll}Hh(UrjS%=mZk;H*JvoUplmVOz;hL2<>y zxD^`z*X$h{>`rdS&JCJfX-l0ibj~#`AM$X}c(x3p^d7p0xDV`bhr4w2=yW4c z`;&@Xh=&jN@m!Qt1-aKKKm8x&6}B8JX77YBfyflgjQkR8>tRXud=-l6UNgT<1!_5m zr`>~d{Kgg&Cet5R*~Y~S9R>~>kNP91#eA2Jk3V(m zV|nZQuSed*Km}ij#=jh={pB;e=@P|<$v$9&6uc3#+w?WQ3M%u`Ae-d3uo73Lsr}w|@Wsts0R{ zRQ^^s3=qbO8XzLEIV;%2{}zo1p`3C5=wIfeowK6V2|758d4vnEUkPn>w++g8e|$+E)kJ}{NM*`#S#&p+IJK-@uOt>yV{WMMUm zs3-bOOs@WfQfn|jaE*RRDnv=SfAT_ewbJ0!KeD7 zahDij{Lwh1b={*r4?gVHkxToF-O?!h@=y`Q3gx{_^0f+n8ZHsI-G`KSpSGGL@byL@$F;aa`4f!y9&q9$OzF?rKY=P@mmC?H zG>8F%0xg0D3>a^(qme(d28F66_UT#lc4E7&(E>}M6a!x}uiKG3B=hDKh=KM^>;rGj zczr$A&KBwA*lg+-FdzsLFw&rADiNY;QB~&KQdR*DxZt+6%=XOciZw89tB5MfHSvr? zAzCRpvPpX+m2&Uz^-(0bmD!dr_nec+x*b-wgU++RoGRHmKIgK? z$}2)QAF4h1<6iYXxJv0KPwU9KgN}C8Y#r9_y4+31%CbYyJRE?v4w%}g4U_@hC7=+L z4}WYmu}SpZyBp;sbPQcdM_X&GD;OYmx6tSSMM!m^#>uK&w-~6$3^J?Jc_%C-mEAj7 z^%<p3FYEEpB_9QJK=Rg0J| zp0_}mZ#cK22DFGMvQgD%@-$0J&G@Gerh2y678f18IW#3XTV-pzf7NTadcO+LvJ$y& zLjx@n^}gL#IZCxDWG|a-2CJ|7DMdmg%kR^Cc{%D0Fyd2m?wqCBh&Odwc*Q$Add#wt zlh@LvamR}>*_{KIL~OroQfAax_YV%Pn$AGjw97Gm*PV;JtF}hNM*c>5N)9cSObOeg z#$%wnV#bWu=wzaRNMS5#!t+ zwh%&f?@yp0T6^Q7sJ$S+#@==-a?JELMUXh#?tNXC;~R{XdG9duouG-qin(q$37pV) z!l1>8)!v!?TOt;qbZbWPJQ}gLCka}<8Elxf3 zBy6D12Ni-P^deO*x6O)qDqKNpy_4+?LD_7?xQE^palG_feriFQ()Rm$cYj0ay zSR7HyvMj2A%aQJl0}&?rqfwLr{Jxr%-O79AC93zB`C{?uz+X|SbLzT68_*Tn4v!Dd z+?#(X1X|1~EauK73N4za#22i*Qa}v+peujK2o54-xI2tW0Ob|mm(brB>C!9kz82S* z8JU^EGl86s*6>+}+jhF!8c0$3-O%5!+(&+Yq{mC|VCnI{J}vHD=g2u3*ctG_aH&1w z6z_kSRU`TIhElYJnf&dAHZ#Oy#EodtLuayxLqv$j3kohvPp0#1dW2MEgSDAmbTsTC z4sk`30j`_WsdgzncbzLIiTAlsXM_%GCpeiFDYN)YmFu!7C%3M4aio*M&hA<{D5X(t z&K7!Zap*BfNh0sVG$5L$WI0w0|;mLw-n<+xiM0)x=kL~|HE*6nfoYl|%fqv!~bCJuK(VS0Q zS&5<^HpCzC;Tf%h-25|D9w|*n58PbI^vyebVH>jR^{u%ApS^VN6bSf#?lBIUS=-6< z$}9x+@jSXM&N%wKh`FrH$O<*qBQcauTbb|otvyZD5xl&+t#(q%SbIB?9qtMZ~N@77zN*rp{4VyDymKJ^VVPHM!7wab4U4b_xX^Dd-k`? z$C-vzxCiJleDe*mqsZeW{~$gGqQ1XYXI{a4HiWLJPVJlZSanMw`&uD~WdFB)*jv$q zDokjNzcofD5@ANIZE5_}?~JE_L-8pKhpA5hE7i%9hpy~57+tZ)e$_l#3D@0SHCjg4 zL_lkqZ$SC)9|>cZ9<3@!mZD5%%cfYg(-3-(bb*chBrG*qyRd&9s&pYB++n|QX2#ecB& z`6e#EdRX`#1D+ptR4;J!;rl|T^gFEwA(?!ca;cFGHeZ-s%Iyk-iDt^sLBm_bcd}Yq z$lkv>QMVs*Mphf;Veyq(08#3mRsqkV07GBix=)df^4Kc)fZWQ+YhS%$=~e5#Es$OkY;< z3GqEc5MyN6XIxyq7>(8D(|@xMbZt-NfVnA;rlfrf%$?kekyo@4!Kv7s^E#<; z!Hm-j4`H8NXSc&5S_^~(BXfmfDMaBiI*Klbo!}Clcyp=rBNXlm7wkpkFi9$#&SQ+_$E5mHuH`rv> z`dL&_Nb{_-_|eEaT&>2}iYQB=3IT&1QDbO8u=v7c;$_t9MYh9Dm#}3Gv%RfB72D#R zeLu9u;{Y~R*tw6$oC!>{*7?TkXh13Skp5)_8{_G15A=A1`Nw~HhZu*wBBxiGo@m|n z#O|#K8yg8k=1v(rjJxsq;$kj6%8{y5C=V9yti=afE=@cwn{OGo1|h={VPFB=w{B$T zaX}#Ucf0M(|F0LIKGs_+qoxIaW$X9}hSm_by>eyb+LdjfR1mtPETosRchXM$nHV*B zCVd87?|v@pgb+jVe(745itf3XOzlXjyyIjwX}UHEmci{FumxEd9IPl+|iInc-L%qQu&2;{o@> z$9S2XWZq3`^VG;(fx0^&K(R5aqL1r^j_u03`-Bz&>*z09h;B4*qDQStd8Nm93tD~= zp+`*%;Fi(hLI`g8bn;~K=o)d{)ccHNgOO_h%K-uephV~W7hz!4C#R-N7IVj4{4)$2 zG#xxph?OWq9#hteYvZ*qbnhdZ(KkL3?hGf~nd^Q0@7uEM53&}u$%xO^*D?C|p0V+J ze&%ugVp~P^C6GR*{2RCY%DtpAUv09dw z-?yZbzdgiMV&V@-03J^G6U;Y0F$)s>ePu2rv?d_0$VYE1tLx*WVE*r}r6QkrgIrYj zbzI|&wm#h>W?36(bxV$V7$0uP$lo@XXm2G7H8+cy=h$v8JDz#kB?pc}7uo-?_!IX& z`b}lZ>4m(2$u3b%Yw>{>YtRBZN!AA_He_G1(8$vQ5UC>xHY?Y`5C0e?kMFEpA_E0^ z&|5KTRaq&}G_VlF2uq1_S!HwFa%Ma3f%jx_lewXpBZs=~%$w0#-w1U5rO-w9n`_4~}liz|0>>)jAOWN-7v{ypyyE4Ij$6v4^cCS5=`{Tp|r@q>eWYJLIQt z)isEKB{j`lw|2g#i-(>eR$4M?tqF!%{4c;T6TIQ&wutbNQlF@)xMq*Vd-dVeS1@U3 z*I>pvE&XOH)>H&ZGZ~$!eMXat{;F!n09={l)wb{!^WDOxC-E`&SAWibL~=|oaki&^gSSK9y_lLtU$f&{6W}DE!A6DF`r~k)uJLQSX!;w5ojr8Op9stY zaL&^;{TlP<-6UwzfU8Pcn#QfSby_Gkqdx5>GsRnxo{mLe!?IO?;ZM0LI@SELWmekQ z_mMhy-}tM`$6y+~jG!g(mWr*GUF4W9(P1e4*87ml-Sb^f^X67TH@ww+g%I557h8D< zY%Ye!p35D_F;OP9+-~>EVnHIvgdf)mJJr(Neo~MF-0QOz!Ro!ULTji#Cj@hU3;A7z zL4-ML^U2$1*kvq0qx|XhFQ#f3gvAMd-^XV4vx*r#6Hw(b3Z;jJCK5AQ!>h%d{goW) zKHM9(2_sL4%6W8tPft?e4V~8{q+UpmlFM3RV~er8rO$}&zOtorhoCy=BTvhKcznQ+ z(;l+;lStn~ftvu@FMzGgMI7e~NLMjw-lIcbdC4&Fk?}7s0b+tPsKCT$J0?aAc~b9i zRAO9H*pnn$FCt19*JSIeqXP&1Nu;AJkB8vt{NuBa?E-E;(;!;E2YsFim4SIRcQe!T z*&2FSo|+YZQu1i3ujCmaPY3gkCd~V@4A27)r*9FMMDd9J*~`@1$IC7~D=*Hpi;bu1 zS{^s9?D2h2<{urB-tx5;POkCK8A$D}?(#zDnl@}c2rIGMMurQe8#k6mz`lk3s9)ym zR%u{hU88#x)*--ygzCy=4sETA?4_k&~ikXX=e^`a)A8#40_{n_Yl zZ3*PLH2s#s&lpw)JV_`w)JG-oJ5Pb#hRNEJFWDzUgn_A5tsA>9<{8z+?%n;MlL%V1 z^p`Cs&D7c7uDKxjaZ4pfy2YO!!S8VN8xm5A?*zK|`7Ko?rmZB~b(^0)?$0E7SZBUrv$|+RYq&tu=LSz$MC)^2!8Fe z{Pt(#pwYD*WTEPt%}4?&6O2<}Y}dJzDcJv95t*{{{9_2HjJzPE~9{JaPK*j6+OBaE->CK^TljglplAky&Q~m1@O^t zl1u*w`vPO4Uqpce95HVL2Kixn88mN$kM4-+ah+EzI#B42h!^|=PUq_IpR5{j6DA?U zFhhGvmlw|$iXaO?SM`Qh(<*O3$!>mL9Y1Zvc)qgdtza%8e@jk;&w`M_KX#Wg0Uz&F zDF6770WL!V96Yj;A#wcPpKICF3R}k`K{>&}UO2nzesl3^scR{LT^HD&&A*iHz5u!4 zq#2z*QlSywb+UP%<|Au)o`qLuTS>#=n>kRnqzXhybCJIcRA{4Srv%++iwasEmL-j5 zt(zXywSi&4_*&mQL+BwBj9i4e1C@h(u0iN{}q#q)p95Z9+L!gZ-%txr_h23M>_ z>oENMKnp7NlSg+_c05zQ4!X0To^~_9xmElJc(-*(`%;GXZbrR#k@P)4GHR0WTlgJP`S<7_xA7iJ)5$0AI~VJ??~SY|Cu1zMpEqjGQ_pXj%Ihs6EuyxS;xUsWtBsFU1O$%cyc9Xz4G zto1%mrlZWS@+S##;-j6}m+RGOBDm|Ldap!0VlW?KKl`PF+cd@wIpW**pJ19@ylxN~gx@2p95>L+WFFx;q&j&!$3Uz(9- zRT%x^w>w|`8^6}09+C2=AWM@$!Yvm`&K%}fe@EQPZo>~1L-l0T{Q&C1>c+J_x``~f&1(^b7ro&=9)R4W#9;wF}b?>$FX>gL7f_Z zO>H^6l|*l^dpZTIX}WKz^D~IQ;36wl?|P&=y2235hqSL)ScQVM)Z{YUo=J_J`%gt0 z1XPm!r6l*uU&vA|fWs3^4ABGbub|<^1;8MBfe;JYkU>5m!s29hNw z*Hr)GK<|DKPIGXvEZ7Mr>yp8U>8}113_V-m#itdD%1bHoAKqWCd9A=|`|~dG`L(Fl z-S&My?E}Y7t(y7=rQ^2%vKjl|DK*O7^a8Mt`Mu{925nQVV3f4Vj^j{4bOKVqDC(F_8`V=zLK*w_VEZnPWHzRY`0ssLe?>E%@h|bh;e6M25 z2`Na9kHA@RHl=hU@BqwPwfMsU0Hw)m*1UT1=SGb3V`(}+MHE9ei!ist76PlTy%Ls&6Z#eG6SYt&W@}*DCT{3ygbqH)4ZL+xq(Jdh-O@DNlsADsi#ZP=oJbF|BY^ z7fJ=#Wc>Hv1sm>?YanUv0>}d(4p@KbKL9xp0S<2=@xKp52t|>d%?JV=mAXfB-gasU z0<`dH#&0vKu2q2?E@{xuv>@J7iG`J7WfOh?OOK&|1Jz?oxtO%#wqtk-d6LvJeBQ+0 zAJ)NGmVtpO^p5^`)n`poPawhnznDObY4NOiR3oIT*~y91WdA@!(dShvuLUt};Ip~X zfoLX&-QjVGy;P3k=aU`#gr%wQ{yW%0JT4tHcr$?p0q3AMdJoRs_kWuje|D%F@6P`c z*c(lo|7?gePjslEqNugd)3SmSIVB6xdg`q&gKLQ`oP8*eIj~e13%3d{pv*>+h4)k2 zknVsZk8$a8e$)uLD5`**aZHgCo3v@0%RP0;6#x`vob;bBl)<}qS@&WoD6$?o1NNP6 zA>+81pqO3`p#VFWMc;}FD6_;&5?8XplvEgHJGGZ93m5F&+^x~y5wo#$0)3lV2r;pb z`;bbe5L$&*3~aNh?2~Z>%0n?#Ga)pBdRO`Ro`iu+glsYudPK#X%$}>hF_uS5*+OM* zfMoe@e2qyRefua&n>12`?9=GQVZ0 z0~9=9aIfZNxh7D4Wg}PCEkes5h30as^u;OvHeCg;H-4JLLavNc456c-4vfYJ?K?SR zT9Nt_TCR%QYWE+6vcC+e{BN=U0m&nXY7lEuMZ|B+Nqp}>jS1hw&nCGc&v5;I_ zzCCrTgOHWp3rPZ{*7Jq!er|>0r2{)_NEkHju+?bMSj6H>@jqA0$Nq;?+&#)8k)G2P z^MRvSFe>TV$k$Tk>Pi8|C7tpE0c$TtCa}t{llrRue4Udu5^`yNvB7tq&z7$zBdlO@ zWtLv@Z9vmFrxDyhw3B502CMkr-=l=2>%Tub1M}=Z1Aas-;mJT;5(@55Gs_Ivd{B^` zC1&5|dhd)PQ&rQAqXUli0EfWf6=Jh^XP0LodwzTk>}z6{DOVIf_ID@Bd&9sRFoE{=hOG)M^rMij3<7dA~P2ZX%4|(mB(xbJImHj0z07RJPNogfJetl3C;KX$H7F zxEJ0BJMtD5SO=9pxm&TgBv!!96H1qrjna zus&m-CYBu%GdwT(vT^nqBJNHbmx(?XD&-abA}wFT2q@sZf@NMe?o3@$M;jm?Xs2rE z5f-!F3r}~l4mC=#KAe>rXO1q#xGA_n^ITn>vgK7c>ub)4SEZ&pAkoQVFaxh~g1f4c z%ZV>cC(1fUyeDEq|IU9iZh)P^)j)#y#Eh)Dr+s?vCY&QY#Wnor`Vnu>I!lSu9i%WV%<>S~VQKBP{Wk%;m*ML1B zI=Bf)9YZlGwKI_rf!XS3KAQy|%yDE0&ZRBqaeQ_R`Wnb9G%W=~s`Uu0QL;A9j@3|n>7VZECXD<$$t!&$c24$#Pn-i z!#8ddio@bmByTfpxz;NgcI}#WruZwI_z0|$HiJ@sS0cvc41a%Db3taG2H$Xym|EwX z4QU#(PA8SpWWQpKlFHGi5$e(YNP(Z4|VvjU(W z^MEUpPR~#RW||SO;3cpkc_b(bRG8$btsn?36|d4YUU7dT==tNQ9&cDY>-KL&Iy58B zbnp0kn%}$SgND5(x3Fij82#*h&XGN1D#Dk&{JX`^yG+QtG<(G|w(^Z8Vj;`XINMA{ z5hp4UN7KM+kF%09C;0xI$}`cKS`mwP?FHot*5>Wt$}>YCTb|$uE$Bfd{-(q=xZQ zeZfxz-gu58NdtFWZUaavS zKsA^=F*&Iai@q2fT;pEKvJgm32-k-VLJEo(>$XJm>0A=K?&SJt)tpPtLYAY_#|B7 zp%^G<2xGH^f?4|7_IrjGiT=`=WMOy()R2ZEqv@3kP#yqix9XaPX^@RYezAYoxa z5r0$*+yhlSXI~}Lvm5Td!&7VvF?8I{f%6D?bF6yd;p3%lrda@pP}WRDSk28l`Z$rNOp z+o+Sj1%8|HD&UsQ3(UtR#-NPI_PUl|XAyjO2pD2&Xzdx9O~D5Rs`OxnZNNr>b{w4Tf<9OA9PkBoL3R-s4x9pA6(kQ3wGJp!BunF~=N|3dzu1$_n{iY&<( z14qqG$Me=n61e7qLeJ~_s)AP9V9ms?b`7USpi=&}GN?vpvax5*3!+RrH z0vMjgtFZPs)i3|*IscZzM#(nLqJ}*FN(>=-Fl-Q+J&osQ6`3dZui**T8)mB)%FAZI zmt2Z?ffm7z(d#XRF979f`eza-?oK*l$5qqr%t0Q@qlZv_)G6-lBeLw%$KyEWuN|E~ zZ`g84ojAEbi|7%n1e^Bs1f2K_v8NmP$WbZU-rd?`nSKp&v0U5V&E?)f0HYw7197pW_AK*mD@{`l&q1J03K z%0Y#k1NRGR1^fT2o42eYcmY@z9vLmL@Xw_-mP|VSgP$bKgLtuj#^PiPcx^z*%q=-3 zTA++j(Dvol+Kyyln8Rf3%rk|ESGW8)W86l4Bq9k|jRR*@;YntVY5lzrWxc%9l8?X( ze{_iSon4?r);SYn*0LJ&gf@S~Jh793Q8bvOzj*^mDF_Q*iZg=hkx4`Spk+wQrK{U- zjlC>Y>=XLW92;nw;DTpnVmyKt_x~2Vww%%XCfu^@69fvU3>!9m*%0Z$wp|up!SAAG zNT$vtTKNDr@(FcYyV}{6l?m@8od3+av!EQ%PoCCuGUN5qdTBn$v44zD1|3dZc6xvC z_UH4dKG_S@tXf&ak~S;9D|hsN*AiQ&?Po6tZnnT7!o1?5J^Tt&ht#=EK4g^Inx#i# zCa1TWPT+?hFR_YGMTR7vE(i^OXvE~20XMmh{nNM19f57f#uTO8%t`;+b55t!6Zz-W9 z$L1JEtK#F#z?qk3nZ5d(@;HJ?3^>DpP6BK6E3Q6rPpsk>^%jjlwN^qGmO!&6x-sXS zRCB%NN_H|)q9KF;m=}Psl654tCQZU!2L`PT8&+!r42P<)nZ|hqb^?%yJ#0H=dG4<}bT&1c35m}`84h_%PQc^8;Iom+a7Tv$!6%iEsqco?M zd<08zZH^g(9^?CV5ELqR+bQO|?lZqkHL+8_@!SDT;R*{{ac5N(cCpjH^Y`BpWsbmH zzX@=53+Mfl_j38mLKdlmfQ5cw1PT$jTD9C8#8*Fk09tqJi52j96&IIC%EyIBpiU?+ z_|_X#G_hAZPRE5Sr|Wxio0fe5&r|I7`jIfn6(^i&kl>(K`x4?ovvdaXM4hW4BbAvHg5A zYZDQSQzj}|6H+GncuId>W5IYJ z#{P7NrH}V*gJG{tz){&H^H)|Me%$Je&r+G;=iyq=`%Bwv*tTs}`6UwU$WJ;Q=w0cV z*adFAQ88Q7QyAw}lCD0mL1ph$KjU|qyzMagh?Dy-TCesQ zSbr>3MB>Lk36U*oIOevXof1G3RzAUq=J8#xzRj&?|Gv2*r0ZqNq?My+F7V)l0;_bB zUG9}TMaS_OGM!s;raHdl3e7}An$E^v(kx4B) z=MyWp!jKl99g)>&SIR7&@~Qn`!L6~Uf8fXiz5Ikjs$0P_9VcE055;evx93v%AI~d& za?QL&_q8Yhj-cj=BXB~mmsu|-l^}xzL1RKU7XwiZBT`yltT79tpGe2P!_6Dhx?Sqq zN=sChjybx_B8~MkZ9(gxEl2v(q(I@RmLM$SSMDE74lr(jznof)3YA*x-kT9{ixP~` zy~^c?tMDO&a-NP5|9N42(*ml#{zrVcg!WBlqHZ7(C z0rQC4rxP#E18r?D_y4p2ByJ_pGelT}t!)BTGVa&C&zZ!u>n9M}(MCn+Guf;+YNYAP z57J6)Dgw5SxT1oS&D@<>A6p-hFi;KpNWoTT8?a7g6AJu@po`pm>*bkT|IY^n*Hp`2 znlVOY4C(TOhspt_tH5VPpBNH#j&(S^AP?US)qN{o?TDD6keiSK;4wCk^1~T()cVI< zyRAH2Ba97In&>iV2J&%_eyf9KJ_c){@FWiC%iulCTA^5Et~}GPAyinz8(8vaIMLS9 zckL;$p`Ywol364d-8l17&rx8mypKe3@@rMPww%CYVeMf@@|T z>!dJx;Hec|KK7UPJ_qOp(QR~GfD4EQq$Q)oz>awE7K)a;{m4-`w29 zlvRh%f`41TFd6BrSH`tLZHSr2$^*OV{Qge2v>mF7`wk;VQ4g(ac+<6AW~$#Pv2ed| zsSq1iru4@_--W_Qq6|s`t>{P@SSCnfpQXriTlG74eCT(l;Uy@M65eR(mc^V3xlT*x z{zZ|wIj0#hYKCcOT+#Sbd8D}qu?f4)o{zkP;T;fJsg-<*#WB z!}#2K_n!UuP0)CjEYd{b&4xj4N6f#A*nc|C0KjNO8b_%(N-V-|qew-neMK!>cH6#B z!K}A5QG1u)22v%ozV8DB;{Z%HdXG+>!PxEGa(g(ZZCWM|NZULQD5W(8W4OhOU(nyV z{vnkl-EJ^?3AYMxSHiV&zT%QNXL};88b2m^R+ezf;O5(R7vQe332qLwx^*UlG~3dV z{YHd;?>v9>RQKD&y!K%j{$}7FRZmP`WFH?W!>o{?bjo@%Y@0T?0@vR6Ye2se{WpDF zK>*mT_7kE+b8my5dG#F3#Iy&-y9{NTCx54psn?caTMswsmArbXuNpT+vCfIHfevXCm^f|0$T6^VC^uVqItsa@T-u8 z{PR!2j++yVUmKhQV3e&(kl#C8QYD$)SM~|L1af^r1%(;}OiD)y8iE$t=g-!=<{;hRSg$A6NFXnz`8O@vlisn_>_Q(fw22>RMJmA7X~<&xShSHdgU5>svvD3R(@$T-(-WJn`lwb1kkk5=M5h8{}N)^xuuJ`xL|r|3WEva1kqTm?SXUnRBt9xX)J#u=+v zJ7>GH^^WlK*D?FJ(Gy&}gzMeOnIuam5-S+UL@8R55C}4WfTlR4K+iz%c)g5e^!y1^ zEet;e)pM*waZwcIODf;rqsD=EmTI`oI6bX2!waJwy+cG;#S&+4u)A3!ag=T*2i6Qz z>~o6X>M@{=Ktn*$HpUvJ0yBmwpz!# zc3an|c>%(gQ72dcm!|42!f)*!sQ+o6KQBgQ|Gkg*Rmr`gHRt22TBO*S&IXPhdS|L? z7T*XlVVqi)!=e5B^LLP)`<;36SNkZmJ_W__rfyb1*#mwt?R*MpQ8D9ZMp3`1^_TeU zMXuF<5DlZ~Q{N6CKC{NQB^9rY48+douRKjHWo5fps31R#o5r(PJkR?EyGvn}^8-k# zxuQ+qYGUrV2&Gzkc@YPG5d+PIFm?*y=2UE8DcqAvr+6=PzKxD&9>>0}F6px7j0val zqK3DzmfiP!g%OUhyVd6(kqF^#07^ziY3<1uOM7#KZxdKo<>Yz-)j-x6qsJqAIg0nB&SjP@3?0(+{=^o1ZwJqmLJJl&W(Un*jmNN_D&K?OaONhpNayhUKDOuINgNS637iV3%QlcOIfCT(Srx4~w&pnmq(-_*a~mx~EiKlVF=#b$xsz(@pQ7nZ#t z)K=O(GeX4h1CTojM9Hll>a$u%cxgYG&1f?95ulGCS`denVKmTYeo zgdb%E-?wKST{%YFeBJ)W5*9dl_ChnoUnW?;z3AQR8sUdgain`^oCYy;L@?)&;DKJ zVV_n?-Y=L!r(-IoQpY8`7*x4P*8aGVGt|A2WzaLS@^hyTOm;c~YS_NOb}X+tq+q1g z^5J&b_v>7J6OVgKfhV`jh*jJf9_rG2@$%6MbnG|Ibgs?}>whT?V{|Xvqa5XWgY_x? zpsE$8r7r$6XjyW~yLz;teee6_{oJFKp?WFHP~?-ec>y+NAe9TR$av=FG ze&Q*s!t@L6g>=5m|HAt8K6R*u?3IzsKqb)!LaeXHV5#|R6S=Gs(Y^6s<$}{%ieXF( ziCH&*-uAkMpGT~vQlv0y3UUbVm~13Mn(cmT+9p__VG@}s>z=AA( z))_R0dEk(}GK)@Rjo01XJU%6e1bxp|xpCs(7CIKB&M5hBXFln{f%ULcz7uj;dM0Yy zg7rx`;#nJYD6!MR7g70Gs%HRhFXK$u)@rOOumrt%(KnRU#`A$HA5HHGE%bB}b^;xz?G$J~XMc&dbfn1(q|>;#SPZ7`awGuFE!;iI;U9ePs#^qIZK zlz=58JP$kvyxo|ZS}j=g=p$@$CuFXe>-=5yc7xm%G4NJ)U+GwtW z#poojf2%Z6@bFYoAd$7fPIR=9l*t4@W?GT&HI(pBnX9RyJHe_}suItriYE~woiYKb z>x+)$5lz>u@z_7x&_1z1J~(8NKM0tzs!>JMr^KE$*7$D`v^3rUB{n)SgYG@m_WaBazbEITpgKaNDu#1;FG z%0n{GfNUtTmUpXAEI&KwM;#ts4DmGyvrziFrMzEpjsLV$U3Uy1wSX2xJI2BF_^YGZ zJtJwpzQ(7xHfNV7iMmkzvbgoB^-bE35Vj*;6uic$a;Gul#3lGHY-b@Z*;SKUipZ3- zVWl%cnLhk^P%1h%kSzqlV#Wgk0LhO_7%k`nw4;b)`XWDY(tVqP-cjKAHfop7>+gwW z*)gYz-|*V~{;Pc%EANowi*>iXwvnb?B;Sns1yrDb<8H7q;%NZfJC0b#K~T2AcC#hu z-Tm%nOCmcby)dayb7Plx$}Fn3_OA~B>>=$Vaq2oESt~ugx2Il({TWB~+q_WmOYQX) z>JW+Z&>NN$bYc4H2s|fLRdG``Z|U{oMg8HYLkU-P-EnO*`l-seKynocqEyd_qk%x6 zA;LoPPv5DzZa|1TRohv}kJxMkIBJ2{z@zU8SNuDlp+{S$RYO`&k|k|s9Sx})y$_m$K3ia5t7Y#U>Smvao2IzQ-}S!lrZ>69uoEIY_{JJc(qBsepf3#r8htk5h5@l^ zWwJi6*m;k#+=UCvJj4by>r^@`n~NZOmulRlL`XUmb-z zxj1Nl%r03fp`6N5yNOTm*acRgYSN!$0iIwA!1otab z6MAboWe7j*u*D^`I~KGYG`h_QOP9YX!|Y1v`lI5^ z_g?bh6heDE+R*#GL9|#{5j1=dHeZe*o5eD)wyw0;cb3t#*IccACjXo>W=~%V=E~S* z%OjHBq?G&_BVXt*;V(WaHG}2e9HrU6>FxVkgL{|SIS#AkE1dZ@*hE7ox*960^{`Z! zYYCQ->LdS-bCtKt;9sxydYKc5WpAHc<{^{7yA7|uZ496fREM?xD~uO17g6^a^j6B* zN2YgZ77vHxb4pnCI3m}|Z3HpHZ8p=<9K%VJ_GpjWW19}`W(6l0HQ;zWuBJN zmm29JWHRJx61mOsA;;{a08BC{Z5eo@C&r**S{}WU+_WC~SS6gO>wn0q8 zV9Q^&5p+wpkG`+RN&tWxP9(_&n}LLsj`q4^BExsva|T&vA*P0N{KqD)F&>0|F6-Dj z|C9Gm*R8RAJpD9`ZlA5ZQ4U|iy<2!!LwuHUxv)nB`!ma~pel<&O_YBQM?m7>w7bK< z(s)0Kry3 zv9{(Y4*6k(qKJbIcBIwo6o=s?i%%&oj6;6*>np<`Kh(eZ*#sp;EUQ1jCk=6M&7eI! zWrMZPG|Kj_(Hmep157^keMSYX5%(itd8+)ErgSp8q<-1xwY)^uqb{jSqD8yHa^nyT zUQqeUEhkEL%(NSYeMOu{%u_gU#AW~18Q?A591GI*pcY@y9JJ;zc>jSm9kkb6E|%+M z(4kOIT3@E&o+!u=OV_wGK_RM!P- zyJVOD{KFWb5=K%l{paG2D|mWzgT}+lU}kQ32~P;4pw#L6s}xF%wEdX%5DFdm(OSUA zYku#}$jiNy>d?@ko|v&{va}yJj7gqQ%;Irgc;=|_zW}{VFDmg((@NCaL*GwDEF*Bt z)Aa?3=mf~Fe+>X2eZtu(-+nQaY-_<-v-PCUPPkkYJQicE_~vG<^HbjqEo25ipFjV) zi8dQ&vCTDT?`Wwkv2ST>atZh zklkwwD%1S<$1YR9mM>})%;xB(jA@MUpM3A~B9|nA3omF=M4{NiEn=N+QUtLB*>Ejo z4SNFH5vB9fUgTEGYW=yyN<*gEA*72(wMd2=+M{Hy=}{W`5Ly+YnnMX{+*0ZnAG*is zS6(P+F2sP}S&^!KrKBS@N=S=^@E>D`Ag3nyvq9Y#c$+gzIozukGHMG*un^z`h?RlQ zJtz#)>O(%#%>6Ub6Wsl9^NHKzEZ>PDm@RR6R3x)IAo84h@h%_L!sQk=)*bK={~R}N z=4SK?oCry9ibTYyW|| zT>6GJ-WO{u0yR5(5_-J2@I}N&dVG_XhD| zcCGz=?23A|kig?|pAnJmnN`X}9=R-bD&a(HJ(HxkBvAW>AxQqRHGu1zAl9Irm-Vp) z6w^O5)nLpj_JY>637nwVao~01px9*jb=&2*x`-uusMMkDiVz7vNhHhpD$glI5a1(h z2erM$Zf9w`>Q1kZlOnvQ_IR-6mHoo%^;i}@$rxo;WdsftPy0Xf_`|F82fm{y+snul z8>Uy16e(EIdR-fVzFf2B)rolURTCTq@mupcpTauAuYydmhu0h0uF!u%b%3H!Df0wr z)%2gqlWxjbT3hhj$AH^1o#=^gDJ3DszH;dt43}u09CbA5OVPH80FaD7%zJId`-`cE z=AF7>)X?N~<}sGJFD31-nb5w`3Pt)XBQnV*_M}f=YO3ANwV+}nM z=QXoceybh4b?&aE?a|1p8pxqaxoOXUzLQO_VaIirBg!XF7qUSJ!o12P-aZ^j#RMv- z&J7XPY=}E4jZ|&v)r7R-RgVT z2nyYj5(LD`h-gY+V%9kUU7U={u^lU9lP~*`ITon9Y2NY3c5{WNUC|y-dEYl;STt5% zGM%^Ct#1UnVShjwZ`V6{P&=BR1Df4R1*l9i1cF-il{2gf7q&CoqCWOdVemrh{JZ92 z>i>TSCQ)l9fR8ccr~AS;1e(-@n4p3wE&Gezsx?a9EBt8h2D!$I;oJ5CSc7Ob45}6> zH7L+z?+hkzjSw3I&9OPO{ zD1}Qwy73dnZ%0lZWmdMEUrgr015M({tmtTEe56yXK^fOes`}nSG*AOGSi+6uVu#)r zV3I(f2ae0wo!y5Br;mplKSC&YEina#mgR1$5(>SucJ6t2gd^p zPp|qH3x>agzFvgB2|KY2m2K#NB6~zy z5!qaOn>gY1kVunJXZQI4uOiF9Zm}~lsczDHrtaJ8ma{&4N|duLT{@QNs92wMq9Mj% zSe;bT4u8cZ4799O4s_idQQqzhsW-!m)V|1eA!CfGefj$S5@_tm$(gY;!Ai*dVxLo8 z+fq>hi298V#{>TUTYO}Ef3oc|u)kmnO3kI!sCMSF(eD#FF%i6a-DkHoM4{!K2f07K zV}Mav?Es;@hywwBmkdzRzIV$M<+VYB=jgoQ%Ma?B>F*f6>wa?(rZ}?l>HL05Pp31_ zq%fkl(>c_399rVfEoN9dB+_y@WgsWmY%11l)sMN@RZ3!T_g3|0f!m<=Hp=+MpTr%e zIUfN{agfdNrt(6%GhXhwRX7#dRg$&|Q%u|np9AKUl4}K5AUoiBV1M_XK+1qPPKa+X z=iK9x%KO~EnlIDVG?7naLKV@j!+Q^a)ORjU@m%$CB9Cx zW6}Qy+S6CWAKTpV8054%<{OaV`K^Cly^}Nj4mDr6pB|`jV!wI!X2_i|HxTNkXrq;e zE7M-o-TR;}-@o@7Dfw$q5LOEHPwy6&-`w46mfT5{?jN|(e!RvdUQk;{hdCbBB(Yi# zfyC`GaZa~w0WqfT6Og%=t|2KZGFCgRlHZq)E?wO`!l&QGJBwp9TKoP?9hX_`NU@n9 zlfUnb3Dn?ZX1l9}wY&`GX) z_M5*k8rt(sh7QYVq$j4TdyGoAbxfGZ<67s!2bEbhcTzmr)N*0){39Qt)Q3$N%Y$7w8o=D!UrOynBmY~u&4FA|UqfVNC<~z8 zLA-=e!>=1DScMTz-8=}VDw1RChgY4$OlQ|LD_*s!%CQHAw+WCrR|a7Hp=ZdF+~ z{f+@vUW>3VfbieCh2g`XquOF8v-|{Q4w}y}=q++dH)u8AfeVyf$RLbwr1sn2pJUU@h9h5i3V8Il8E` zMr7m>F9zdu!$}rX;jnVWK8v!dtu*w3A8-16KMu7qEghKEQ%Clc^R4+t)%d*A^@)L? zL2LqkQdV3BJH&3GuXf9z{n0w@j34uol&=zu3UB(`Ja1WNDYs`?Nd|<-e9yOH3`mFt z7YQ=v9uohqZ=XWegER@nj84s897djzh8hrxiFBW`Jw*Ys1R=tA&-FxeuJE^5)yoLj zKo7$UBM=pX?=VKx6 zz<6YM4hwS=MX}yKtBAqi=YHANfC&Bk!}ZCzf7cx|f9L#wjv(|nqi>b8f5>{o4R~`| zub$oA?Y+-)M+0uLzZJ>v!J}8g1NW6hPDDGHKk7c8%#WeNcRw%MJVbDGhI$x^U%A9% zZRvBdCUijf^{qrnLgFu7`tp9{sQ&Wz`zqM@K#QPDFJ@>TpuD4y<~2BjDF;%TN*u;D zR>zHFWp;DC3|V)%$kjbuus5aiu=c|2<8(@~7Q-uw^BDgRiPvptVJjhUGM$R@>8x@q zE`P&Bn-V5KUBN|6-%L0~e&I#A9t~u~w=8 z`T4*MW6emYlNjRNc#Rz`l=M7m+0AvlNy323nn1wnC*RkI{OJ9}l1`^wRQcuSxp`(Q zXpbPQmmQFxkJdptnSZ;yhtW&oio%`}GsCI|!u|-|Zh44t5%Y4XHZcKFVONFaS8P}= zlYCm#TG?;Yu+(}L7e4x~qU_=J1ONVu(P_!%nPQI=Fto?;7v)kOyB<(S2By#hoxZ05 zPrY==PrM#_Le_j~Y$Oen;4%Z5&DGIi9p);Dme()ht4ATp-SX|wkDVKPbKJGPJQ#j# zqh03JCA>C7z#n@QjqYTVPD~W6G5;<7JPTJC0wj@7Dmi6Klh+0vf-;$}Bb?sTgJTcN zgp(evlCn`(IIkE#v#e_@eBNnOQ$W%5K}UNk#D6<6UFJ(O39{yVx5RR%;lh`sA?3re z`jrD1ZqUeb1GEW$_*GTLqWI(#4AKC{r1<0a^GYVnJ|PjZ*Qu?L+@HBks#@$^;au%|X6J5h}}434o{-NR`l|-_ss%`%vf7+<)e{{ra9@(q}r) zKr?;flQug*vD`8+Q}0zO4mU%{%0L#GbdTbV<(a!={{8Ls@_qy`1E$|k(~VqRDD`so zxwlWAr4d@k<6AGMz0KTJP5ZDCP|;pdc|SHDDn551J|`gYcK!#P)2NwY4BqrUjYW%& zk6?A3ZckS3nK>_s71Nctl!S&&#OuxHtt6zU68jyew+_}Ae%(h^*)gu(5{})m;rip^ zFf4i2$eEnNCb}FqHQ9gc!S@Wrqc-7az3ZN>9e!)=-!l=;iS;r*Pq{%&Vkld7tOQS@g(#z8ZttyT|59_ja zso-Cg@G^nKqCvdUStJ-0ZyEYwf-aB|3Z+W46C|OqjkFe=yfX03&_p;U^SEHD#*9%| z?2vm_9azkx^ZB>bUmxH-!+ne5HUl0TC3$-@d>0E5l;M}9RDw=3<4i1-eifQ)OPN~~ zTfesV;ZX}|qN;E#!*kIxYTHxBMJ{4j6M+!1-y(@jF^1I6oFRx zkmrQ0^LOxt7qmR>m&uNQO9rd6=oY>s?ELv}{Cj5CX#2HWZa%EV^GIAY{9gSmbG0mq zF_zpACSdN!L$tIv^W`VXs!pCanevQ2=E4uD-rY(Xru6_!JVRh2RJ+&xr*x14U9E%xDjp>gHY@i{-A10)dzVrZfaR4&T;{-D%w3l$im&Re@tZx zXF#qDhW&lnt+kya|0|148`QRXeGG)~vQ2`&N)~I0+-LOMcdjPi7G|NIh9uRldK;+H zx~zlLqLh-8yuT>@BqL}jk^y@Ve$hVvIhxhoe^Sco20r;Uf&Kv1M1Snz12j4ZJ-!F2c5nd*JDywiLtjqz7 zhC1QA@l;Cdgxqr@jjLs7LKwHmxxeFPR5jd-!ZNXLj?zTh4gaeTJG! z7R51WWh)Cm-d6_}`@{gBH@gf7%Gy7Qe=<*g57?7=BHB2JabD(hSOf(pB<>w~^0hAX zA{$3m3^^FRI38czWYFK1M2-0QLih*%?cvl)*Jd7)TF|^=4bFVMIWK%O6PUz`Z-%9u zz}Snr;1H+)ZX86PLtYDn+xg1I=e`jWzV9k1Ckp+pCq6H%tupxMhok%R>Vd$58-tHD zvyBUOq-P`xF~4gq5>@| zip_KP?o15BayBQ1Q6RaQiK^udG zX@ld=GS;=Hr*PDSCISmIUOlEN>PkZT>X}DjV_$RNN5Y*|Q+br?spZ#3c+ta%VeAor zfwewcwupkqoo|3EIaNcjYyX(n&GeSXdncn&2sstnbTK{RPpnDm^xK4At8=EnREC zU1gpBPa>^tCptNC^UAkkojBhP;6y=s$iNMELz1B~xDNRs=sd+dEK}lCU|-@yIbQQN zi7m5OD%!#Drp0^#QhTPg-+GL0wV(l(-CiZ!cTgSp*lF7=s=Ga~1b4cQZZ+t|W1dWs zSns(Wiu*SkO`V_~ik4%~PA{BD!k^cqyFwC~*lVXsDUZ3586i;MxS|EQvQ9hO7vBfQ z`aUfp^2xYK*1!>sf?j1Q}ny!i8DW0}hBQ#zkO+rtsoz zw4n3P??=%0p5UN_Y_g!WS4jwh=>_;=GvS`4C5Ji30rHyDqAal)WrJ{`@93KT=Ca{= za`0fsR}5hbvUcOGnX5q!R>zzumblMaOjVI?yyg@`pAjidHPwC@UqEb9Q_apy;1aEl z`JZQFrpZEIO-3jPVC+#GNT^%*ES1C9yed{@@i`u~0}P&As50iB2X7ARRuy+qSBSM8 z55Tf6>Vn5vxyxp4&2sfIbOQhlFny3b<=?2p&vekM%3YN*L#|b z*ZydHqnwdPf7{yEG>y7HXd*>7MLSC8IFi`umb=Z-jA|4?8D^;P><_N(_PGEvnu;%` z_^CIz^P~v3hTy3`$@FMPVDd>IAHLB^3 zzj$?>Oz(02Xu>C$SSGP`OA30?8q&x$cAc=X*?kYR2P38hqMY!Y5%Q_rGj4z~!^`Ap8f-!=T|znrnul)T@rM>Qb$dHp2V?W-pWPWyKYMsD z^7Q$u4^$`bB>L!C96cYT%nSo*m?pVhj`|qpU``np{Ix zgrO&{{9mB4^WW+!!3%k5Ts3(BTyucu*=D5!0MT;~F7s$lq{8V(k5x_^3t$E9eqjVq z>DY06HV=|v*}$XvNxWwdILPwted#OUeGKhQ-a1=K@H>|Hnk9pP|Hso?heg$W@588w zD4=vBsdNlEqz^41An4H2>5w8_3J5Zk5<`a|ATjh164D?YGBikobV$d$$ItuyUDy0O z=bXLwihHef@3lxQQ`DTz>ET-i^$r{5clu86({A)hiGGoD2a{Z4a_fgS_KdZ56_XJ` zSxoqOSdfKm%DI_s_WJ1_@tDsMPIdS80+%(_Y^mDCcA&mqig{R}&KAIXYon6ZTMn05 zMz3DR_0ixk7A>=YRXCSY~Cc2Z4N?;@es>w6P-(vLmhMk3pBvhhx%yT`ZM1ElMHaSpA*T)Y-(G!j4b z-A9ERSQ`WrEqx=im?wHds&PMFv?ij&`}X@(rrZ6r2{K!CU`};=F4YFh zw+^cA|K0XyTtC|BVp00{Ggbh%~z%3)7Z4O`0ZjDhrL5}y8BTpLtk>NA&r=6B=L=Wbga;^r1pV`IBLft9Je5CSYV9y846)Umf{}AUJhx1rM0s(% z?+399_32BJU<%@!**y*W7w?DIA#Gt5%)7Xb9Yw!A=h4g?4i3C~DmG=BqzVU6j`Uao zgxHwqubMyO(*45wC+nm@zg2^M48AzHU|h-^rnn($k2fEpF@$jo2W;~hC9f9eieIJl zCgouEpTS%}|7+_-8F+?0t>fuNc~Y!ws8*YeT{o3ow@oAIkz%soJ_WxsFXGFeM~-3O z)3Bhc^k$qETXyh9hVh--mo|KQvq|j>);%FLe}?ecyS_LkMb%6 z_s69IEFHPak=mTw>~|TQGBW7oOB~kGykmxAf(?wFK>qzu>*u0vyA4p*dx52@SYL-2 zMCbbaP@8cTJy9Prs&|7BZ|=c!&D&2l$a3wP>Hb@q3f1=MXi8|24kgu1N*B(WG{voXvMPMi{THi2_7|b(Ik|NO~MUtteL`LWgkeM`TrzUoc=)`~{dGFR1eH zv|5MrXz`@&ThoTR`~YaO5$5Vfjw`Dtg!Ops z4NRIGo8bc%=+0{DxS1-R8Z$Anf6iDTv98=w4M5eE~=0Yg(nJ!3m8 ztGd(kFju5<%<$Rk)aM3mBsBDQJD(ZSG|vP?aer2*DTh(lJ%2VuNA-#WvQ4Us{8l!y zmBL_4E9j=4+Ti~)cvqk3+b4+o1FEZw-NQMe8-oEtFE1>=o~(paarKif;!fbZ7?D@S z61VxXtDm+>GTsYhvX{i}F%j^8tHz-#8zJAn6v-%4G(m%!A2FPEjr zlxrL`+<%R`_x=&BLA5k%DhB~YMP`If1ngcm`6RU%_YuU=(cykx+XT?#B5@pV<2Dzq zarY2|gF4`FSvqiK$CJLUGjpL{;Cz9(kgcF-OIdAyyj&~c z_0Cv#6%Q#cK{N=5Fh)|8L{e10ekwL!+ZzTBeyW>Fr6mIqcs)L~sPX+qYZ-tV1pjvZ zb3{ZntAzf>)uJhw*n?FZ- za>IHOC|RdrUs!1ci+r(!VY4`l0Iv4i%bKDe~PO>QrE*}@ON+Us( z=RdjuGFk%UWVEux?)X@(w`O6Hs9MzNdSL1-km*fA5n^o z2?yxcw4e>3$NK@sA1e3}cxz~+Q|0buSw-dbPvUe3@-+3=b@gn`E-qb_u5LP?Zm@I* zqlJDY*V%Q`&G31&b;*NeS&<>#L0X2Hm9+{&Lle|`BimX*@k2u`E_=tLFV2BHleouG z%zR6yeEn~i$a$O#wJzitugXe1ivxT2Z9^vS6L;K<#?Z-4nUkZ+>ACSc$!=x_lvQ^I zx#Imt091ltfBi8&-A6eRlFy&N7^;hQQ_s=~K8(t*n+RuI7%VzX1 zcGg@t@B^6u?h+;c@Wvsc?W=?8TVfIhg@{@4%1}a{H2asT^0AIe7h4aB>|=XMQXF1@ zVX#7Of1^39EHg8o4(}Kb^nEB}C>aae!zHy?qpo-;^dN}L%w(ZgGVrwPE*qvV?9$I< zPwWW{VQ2r#=;(79%a*MLe-GOKef2-FrMai5gva{a;=`4yW-9g6w|4i<$!L2b1Occ+A zLCTQ*1ucNmMIKsn)b_%FJj0GWKs@54Q>I>zHr`0HL}icqY{*UJ4`V}94;48@Y6qD5TaN2C1HB~GPyO;(lPmzlqruum zBxx%34Mf#{krdNGL(U2_g|7%KqFf!GdQH#ya!ysY39RAimfuS-C4#n~x$a*&XfRdm zj(l0kWA${i^eU^A8k+3f+@#oE{=TwPtb>q;huzrvfp|`0-HuU_gX?@`Xy7A;fLX_$ zhXM|$oHm;!hEr*aUdt!Hgjy7x%0Aw`G3Zequ}Asjfh=+G0X8CVf0vl3G4=k|;2rNj zZR2prhX-+(XF++^y8aM?OSVBw7Qe(3%z|!44QYH*ZDU(l@zCcI_R7bBRJxSK)d+xo z=k8NHq0w)ICB0Czi16|HUZY>G&Dn8cgk~U6#}p|P?vTsAqp=X^kfP1)%NFvQ|1=^r zHZc3xjH@f^AtLg+!TD)r$Fm;~j&pvM$<9t;W}(B${Bk&zy^$bj`*&iJfl5zS+Mp-i zO;4k93x9yCIp1sk(9|4tsN<)ILO+k5^hi%LCA7nuXanecmNqyQC>=!+KX%|($G7?_ z+|)`$+K%j535bk38!R7OMO}qL*$FP(DtM#JM3Ty=;g_aOH%4^iow<7vcCcOn3Nz(G zD;r|alywwA#nm4E=)#t8j@M8S9@ei_AMUK#5T3$LcPd`qI}pDW$U&CSehM|97{SEo zsdZFl-HWbf;L3FfW1m?O&SEub_4;^!L|!Vj)wU>&GRfwsPk^lEXUnsHdffeyi7c4G za-q$3=9pGJo3=WWr;qLSxM}ItlcxOWK)dklqdBS?gh5-jv}46qG{TO5bST_x(w+Kd z@&gxh;#6u$=9*Kec~9F%)@npllCcSOyHMo9vi9Der+ac%wL{czgz~Z^68_P17%Di>ig&FFtqly1ACykZX!K%AU&QoXn5&3OZFHQX;bifYI1h z7#W82TP|hw>ij(WZ%((1B{hZ3zJEbSkLL@ms3bdRkS54WJJ273O2+rVUwO9L%d_oF zuqyUCvmE(4xBX45!o+jvx0H>KAG+e2^CY ztoffT@pBGRQu76s^WU5HN$BnK!F_52db;GFZjKL$Xme~=^?vtNG2oF!8KM_-7P*W+ zr@5=;DygHIqlfO^14FPZ2-DoX-v1KcmOp^!7~@|@{2v$K8!Bh#RyHWpLn^IwQuDK` zqq5EV*hzx*Y8s9x1|JqL#8q4&#;w-p+m@LJ#X^R6sy7Pa{Qlg^eB}C!IJhthpdVr! z_U>PteSVZ1T=t?#FWU%1bkMOnor7m5_ChP|WoA#xe|1j`m^e`Yx45xYxh0V3LatP1 zV_M>7QfDn=Ms_<-(xU5P%!+SIxOjiCxt34kX0{7s?$q@6nlwW{2^-jHzu;z~2=%Kf zyG}0r+1}zN4EA?vrJ74 zC~nIV1Ai7+O3iX@VlC8YIC`<_pP?k)u!0+xawB|m&mnY``R-Pj>_^n|2+mwsIUajA zj)ebveslW+alYx=@Iv~n`2w@LE54AUDSFTYqtqckQug$y-3r!oKkMUziU^P(nO3JH zaRd;m^b(i^Tr=iicjXT(6|c9eS`Vc0zRp%=TM+(?F(lWVxj(%iZTV#D+^gKQjK9TR zD2c)%3~kxSg*;R1-42I14?sF#J%KJi2Mts$9=itj;Ky9?sC(6o%$t#`6oTYfpfXlX z=%QQDw>vP}p0dbS0&8Ac!4qYC0@{d1^vJv448&Gb^;>ynsN3+c$S5(egD^d6R-Fc|NLu2S++tAqNF9sk8skRrJHi75jvPW=U#X5Wn|tl zrgyoG3n&N-3u9VZK$_-wF>#}jcQXqN^s09FNlATJ|1{9b_fA663`cu<$;vvf$mw|1 zR$Ay_K_Z=er@_5kn1&gx;41-CYGl2Lzq4t5uRkP$Wp>m3RJh01-T9gn7+-9jR8|kl zit-}veA}?z0Y=n4dZj&hkahPlqY0m&Bn5rTiGw>o#RdW7O;1a8I87uwK*!V3 zT*2IrdkRF z0??~CDhrgh9%|K_NZH^3JW8p$XGf9&m`5gjb}Uj4MptZSt^%6|E2rd$&%&+Lrn{Ch zFzWh?|FKeO=M(jT0U~PPV6$1_B|CnC)}%qu4KE`zNoedph;2Hq|LW3~cc4 z+}$xWhxN8{zqh4PG~9}1^9yg5_$9;8gH_Q`lY3OGt!Zz+O(O4=xoJuDA7Mgz=G#{txLafMcP1J`ceeB!i zTK_)K%DCu9oGN5ExeQZjkp2F%M|ech%+oUc#o#5rBrm-=V=6;662<*cM_Jpdt;%hPc+3!V4+lVcOv0Wy2I9wTv|F)`wxP9bpTf0BCc(yQ#%Pi3b%kQl}>6_UAn zVESGau9`y)SI-d%Q4WfaETMfzmYpBazma>RqvqbkS+zApFGB>0=6wa{jGOE#SP~`c zg-1YQV;?lD@6CXrlZwrG`j4X!KqOZG!`cM`o3A3rF~QO05p?RU##0(bfWt?8=u1f{ z043P{jENOhg!=2`AAR|blk1@3JR0JL7@~z*P8QdYjY2FwP9cjSZ{I6$ik3XCy=23f zyRhpuVv;3iCyl4cfeiD7V4Vt5E}z`VO+soyxE}hjVzp0_)S{}21y3Vlv`LRML`z|7 zwY@(}3(<%nL_bC&vmDloT-=MB?+ON0tj>KnE$gaoGQQP+ghS33geQU7{{eC!t7mR9 z{jT>{osB_?jrid|1E}n&CouDE{X7knTQTT2_B*CioVcqIzvR>jxedmGrWL- z^tV+{r9@Sqd9Oh@8YvA2?l95Z!vG={2}E!%3)rsX_wuNAbuD7t`N03lm1T!>gF~(U znADIk8CAP_V%m2OrTnm*OD4oOer9t6r;to%7L@Ij3c(^5E_{(6$6y0h{aqKwL2ce) z;zPTTkDS>icY_5gEIA~Lhq%JN--+2 z!vk~KXRnTA)KK|x3j&C>6J$RO3c*MvOIK}$uXQOC*t@=M$sO@#9|EJvITg1G=jQm- z{BeC#ttwSXI?IcQab=Dea1!R|d0E=p#M7gcl|XSSpa(a0xowQ-8{4(#HMK zcd8p?6{CECH+GLsS~=cO;HBENlt0tt5oi(T`5rpw2tn$pITC(Avu(^KGPM0pQ@DgY z=U(QjznaS^M^dGPu!qVgb7WBfs~zaNJMe@|2`f0+N|g4}~49sCH2fVvm_g9SMsQOkgbdpYz`H&nh+?4j${Q|iiQ^aZC8 zg~Ny!&zk;5JhcMPR9G3_*;U~riA{SiT?c-6>w*SxL{=9p#1FQ~=8f6cb?cMW-&ahJ z&0WXr=mM=MRKRKl)e4w~bzt@LL8yE>zgl|!hRVt~4@Q!&0~1qXXSh1wmbpqHbLFBD zQ49G>Kx~D~ugJnA+lD)IQ#iWw1fsrucO*bN4KbV^wVe?{@IKuNFyqaDQGj-qjS&`q zcxS7D)apcH1)yKul6Nd6Btey zBLZ)ycnx5gYNQ?fRYV}Qmr=3>19`UXHsuVi=e-j%7=%9ZL@}?m(dh*+v&8+_dKCU@ z?o`#qNNebYEp(~2AS=;T%jncAE()S1go5(NX4?F~M~T`pivtREGz&sa0wSskd48{9 z*_<%9B7EwSM>GiJLl7+8G-sUVbhpQ4zF{M`nZ_fcG8dEFQODsJ^73u31Y}YT3PE0> zZTgR2k7&)m>40ZOB-J~%Wb5U^=D!SJQa}xezZNYuT6N(GwIo)=+C$S7Th{)o6ex0^ma+=1a89Lp>WzJsT>vY_d56?T{ww)!HKH(N?Z4+J6w zn-(PQU($i?oy{`?O3cAqeGM=@7mdud`?#XFNtg4@xrIghwS#P9h3vrM?c35N2qjLu zRcCWyX!!YOr_N~#7Wlg3^No!v$gkw)XE1xMub|HI3JijNQ&CWplDn+{-V*4{f?Xo? za|>umNWTwe03?91^Z9UXi-(en4ybl&A(tJ=uul%cnB=a>c!Ki9!1O*OFQt5n{)r3} zV%_**&vx|N(a~kRw&X|^)lr%dw`B`!uu)l=Sh09d{}l^IDu-IbI->pwc$W>95fZG7 zf1uJ(wLDR<@Pv_mSDNu~`lfa6vVbYdPa!T1b7td$M;iumghiIkl$*1is#?VyKoTqc zWl`@i)TD3~KlHQn0Dg2XqvE!o{xKf^M|_OVs~IJ0`E+G$UD(irMUEKPEa9K3vbJHs zQcpBPLob{{LpRa9NhTNlIzOTigL>|Q7(jr8*{b~N=k_uSb&kk^<05u z**7H`KS0DfK0Mobm%X4R_vm@zgT>>^FApTBAi(03>i;v)Eo^JRw%uuE)*SoGdMz^* zL*14rT`rJbt*Z07&y2oq(86R!UzqvYeu?U9bHC3RGP^m9WV&b^gpsZ&&dS^k8p4*ku)IBOW7c-|=NqQB(UF4Y~?cj{nV>$NKn~-5=!r`smtdm7JeeYg(aMA(w>a~fIF!TDeDI(gm^#Oh8XGZ z8^O}_Zp>I#dhEoyw|7ERhnm`CD-X928cxkME4iJ0F^1WL@e*^vhyDHY~1=LhoVW2$mFE6X;u5 z;OQsudo}2Wrtav69rl+$TB1I6BlzwoRCXp(w1@TFUWNyz@e9$4&45MfKd}Lk zXxG{+WSgh*@!>F%nJ8?X|0DWRkGg{WKZ73wckZ;iRkA>Rw<+6MLx%4hlsiF!2%`}lQv^%S3Dlkof>cT)CgYw7bet|@8`3fOKd z(XWnVj4jjO_-%Dk>|#@}C~w?FZt%c_@!`HlXefEdCqA{Uk}p)0vFanlibF{U zmd;h@=J?(Z+xHZj9Ev0Kq*mzvz3&M{yQS<8HI0a=ZkL0^iprYHAKD0958nrqn2AZJ z#5I+o<)rT`0tip)o;UIUm9Z_6X%o9AX3GxD>6yYdIVv7A0^(@PuQmArW+u7wtVos! z?O2@k&kwxsPpInVE0Ux>_rnrZMv@BE_ju%T`dXAEA&+O-%*UWyjgKqL1oBTpN@z0U zS+wp&7J^)aBrANPGWW&uT!nh^cWim_CQwDQ&X4sXo@TvlYo~wbKh55w9BXzVfr@5q z+BzTV3pX;rzmex_FB#PRXP0BkuSYRy{W|A_E9%rjYd2IQbYS=`^RW-HV!dlyn2RvA zb78SceP8|24*bMx6uDAIiRXZFlk1sO`E%`pZ|jjE(qeok11o})04SRum3dVf8=m@B;)o^I>{ zx2U_Jvz=g7#W3{y$RWIEfX?#^1-*c4CJrf6*Y=`@tnKyA=O5QzQTedX20dU7wfoc? zkA50u5Cs?htD=zrVF1&Pu$Tt8xoo?Y``*Unvi6Ev!X&1hNxr==9@UkIFm^x!*51}6 zSp9P8J@@KYTZGKfMb==dBpGDjE~AA$DlJ>W%Noc%K&!kWrK(12|I%s$S|NY{J6k(a zW$FLqJEkg@peg;y4V+KeThG}s6PBna4@ghDy>A~{g)4jx^13j%Qmf~0W(sg zk0Ql>Xx;PqNr_R6(d!wZ!<>PnLunZBBEbwyLLqROwNw7{OM=_d{4x667ul%rCe}b; z8LZ#=p}hFjPr(JSQ1Sd^L2LDdH0AA{=;*o85HlDe~Q`2EQ@dqh9U7Mf7o6|hM zHJp@V1Orvn%)T93)gbf;51j)yvjXB+v3Z#zYiP=U_Pm;+ME?uv|B;^D-w_{PR5ZV{ z5oOcldf6>^e}bn1R=#LJb;sZ!z(b-QI0dijo|7*9>n9Yq0Vgp7%s2wEMz?L{;c5j} zgm%3l`2|?ZmPRNx0;jf9Z(t_a(g(>fARG^Nvzo$7ej~g_2r35`JX38`LfwP5X25*h zhP&!^V4U2`+0&7m9Exp~%cY@kWx~K`rvY`n6+J~cXymOYDOD;ctaWHv$8In0BV6f# zo;%V%1Znq-V7&FPO~GD-psQt_^@rr6_x%sv`Pg-LDmDY|lE;4P5Trtz6?F>ui@c7- ze}D;gg((hIwPA{V9kk%)nIuxh)S_J{=X(5De9<_EJ+ zfbJgHc9IlW4fMY30pZes=i;Z*5~`~Pp{8_TgzhN8=(8#EQn`@!f0=gLU8W#{$F2l6Kt*DuVizotPMEp(Jsif?_WRsKPBxVIrWz zp3QU^o)~?q&N8a*-?(}{Y@Qc2O#7b*kmqU(B?JkuUq$4^Xw+0A(YKg?lp|@Kt$%Sm zmOp4u!n}40I!HaCzkj-dr_&zAn&?aTPTs<^#eg*PC8GKu)uZm!)$|5vVJ9WZFZzIz zy7yvMemd*y%a3hMuYMoJ<_cK5*dOm<%4*fnjxr43p?M7dLO(vMYCBhXv+lg=(0+1S zvmZAl6=9*I6n=~}$ zWs{6!)VG(2bCs4Kn_GKVvkyaOw&fUiHlQmTNv9RR42%I-Gm}bBR0ToQJqwNqaSsBc zLUNm*W{ZYo@SGEgs8iv8MfX;zC!@8`6W>rP0?HAN?%hi;5<3W*j$dxdLMoS?os9Hq@=N{cLx_53F z)7>AKxhXc7d~Opg#MlM_!U3p%1NADMPvPC%nB*Fc4ub=Iqzn9U+;>;$R*nVmiw1&7b=zb~Jk&+X?t$UsFDMrQ*O}+=vw!K%$Xszuh+mP&rG-JUl4{z- zYbYieY!J1f(I}=(k;J;c@d>M~4Qe^s9Np0dfmIW9eA@8&_UPf0isJBaQHCU{NT_wP=2iIzomj&_8!@l)89|HlnJO^$z1Ijz8MOFJuye;ni~$!zM%Gi zhKwbL^gl4ZOgk01KJ zY9q=pUptD_KRKvAeTyRZ74Po*p)^&4WmnQSps77FiL32&W}^2oq!2Q{5f&gF4y^ zz+_1ndN(x(rp?*@9^;$3dNH688nFKMX$&rJ1zXFbQfOX#?S~5Vx2oGYrQEOQ2>O%p z#0Jp!!8I!ZG5tG0CXNq$V^)D(VoHqwC#xsKVBzToT>|r_OCprsPPu0XrLWGvK%J_m zADjciyWP_>KRm7AS7uh21%p@ek0&Lb|2JLri;k3(_y0YT zRdZAX1TYt{9|I;4ol@xK19OWUBOmkhgHC|G4pLpnQ7CPuO-kmc-gA<=+kLnSj6JLr z<)eKNG{_Cpx`Dk{EZhFH1^|b$zWb(8E(phWIj|?+9{hW9n%a0@cA(@wo*~?ZvEYV0 z@Jomj#u>gHkGjos0TWq0VQ}lBk;*dV<6fuyYu<_EDzjJ2L-Pl}4}_O5eJL7|SfR$= zzS4sz2c>7AxDdRKTJ~`ZJ#6!H`>9|n*H*8=75 zVjTrX!T}u${>aXHDcUWC!2@a3DOAO?WNZ;7wOS$kC~6TsVNcMK>kO06f}>7Z)Wzds z1;HC#Su+v=EmIqQYCW<$()=#tJ|0NEmiWZ-wS(~1qxe;J2Ah5EmxfY!#AO81%8xJb zz?nimiw=ugS4E9UfD^-D-Kc%@gO^=#OjFoi!qqg3`~y=1`LgAQK>ck@mGz{ zUVz(a+wBmsNq39Z5s*gl<*=8$r%ab?BQjR_|1Ad$u0N=-`gz=8 z;V($NyTx$V`-*MgbQK6>e5Q?AB)tMjMjj`aGq>kiUlv&Omp438yWhxyh~45b^H4{P zRQV%Bxen+3?2pHYK%X~RO27y@Viy^>ewMkK@pQ0)i6`=oOK-sDmP@vSM;4K15(iTm zk{0=T8+*-3os`xt9BUJ(u#)k<7f<>}%`Mph)*Mge!1ND9mfu9cos%7k+dd9G6)^N? zJVqr>Ra6+rl`x<<*u0-0PPG52X)QJ*lE8*5Z3F%$NjItFM#((x_LbaYK@U78^6Rf; zAA4om+ZD`1oEt75em#@VDty!*BmL1rrbqB!Rc95OtTc+*aOiQh z`WX#kmd1PytVl!8VJ|=WnG`>KB?7g8O%`I$DBiwT$ zueE#5vlxXdO+eTG94@2z!hdWl=J=eBy{ie9)@t=C_>(Oj-y*e(1<@T2FQ8`Dda2N&xCMXu1CZ|kv6bvGwseTb`ZKEEovqAR*b}}8857%$ zxbX7C@huVo)d$~k02!)#p3{?m;5A?376z7awL2zn!+ViXMwFLrvOMwAnr3+fh==?E zjn2=`0pw6?i1*hy@m+`Q3>`hisxywy>ji0D8XU$}Qr-1|C{C%gl$1wErrihM{?s5U zn75Uq9SCi=AU244og692C-#U<;=t8XXG5*;vxrcVg%h|=p2YTYc#;Qv@INXkjV=6V z(elLi6`$-OBiR9WYe-GlfiBwQnO~~aMZw7Y92?M;8{kfDuS|T9SJC)yj@e48DTUquvz9{mH9L|7k_tO{EJ?#1&dK-}iZ1}+A z#4i9_m{DS~nsIdOW!H*3@iQDxL$n9S@&|SAdVs!Agj7BCfPy z&qmM)>!9=>PiS2#iZv^TssICu z7xje9DSDa@9}OC1Gk1gI4OkMtt{C~!?fTk9p3FV<_#id!Pcq|!(2d!+yLh%$P`2+S zB2FF>7v*D%4B!SNC=*hbbCKa{IuZgc1Svve+Q`SU1InxIa*CU4_2VkNh;mpppFc(C zG&l+;fTvXkE1VTQp9}yFyQVG$M*}3uoB5Xglw4M*jKS}*hKE3L?+h1UDFOoElW&dy zBb7mNNUxwbRb_LpEc-`w0j8b!&6J;epi>3?zW5hfjd53*Z2McA@@b0JMxuhc@Gz>I8r2smGP2)XU8_!}s<##6GJZ zltB|39tOm-NliHR^GpD#6T`fL+B`i3QQGz5nH%1|J`4CbXYg^lNPs%P#eoS^XZyi} zAxzuB%l4@9O)o*9%E8JsXIy(^in7DPiEQ)9XiK>0*?8QiwP}M8n_z`#5Mc-}16qMG zi-hk^f&`wTlWPQOoP=@-_ z>zXbWl9z0a%Ca|<%L160E6OW-YT5NC9T_+kT9&S0?#^_`MHdJ^g=vQ*Ne}D4A;wj} za@&Sk6ed8D0p*w=1{94rYS}S)_b7Jm_bA&udj1nQYzLTb zYnT>^WaQj^TPLjgnYz^#){YkWpzI{~v~uO-)7oI}38*at`vb1gbGcZ9Li@ijPXhsk zN5p*IrOfsE?k7X#^7bMs6NjnvsnSIjJ-FSa)Pxu0zkKox&UO$%Pl20gc3QjW)Mm=y z7tUp5z}sqbk`Er8`&RS(tmiOT4vSF755q`3B$dV_*QvD7H7;Cz!R-RLn}PLW%lrE8?{|h*5uQ+1>8WIDgS!d59XCaT%NJIDu2^M~|4=8L-G!AEaC~d4ktf!8 zgb)VZ#DT1DhXX-NP-69$qThe}s-n8(^+axn!gcWoHfQRaXeAXFD+T0_TUN&5LzTKSAuvJBLQg&h(t0e{~)~rvHRy-JKJPy^RF+s z+k>F){a>}(fVu;00R-IVC8DL`CFbjCWAOSLKZ9YGSq_~O(LTp++I>)*Zpnh5ydZ$^62!6Kj@(nrED?D^9qDN& zW&Hh?IYI2Ra?78tmLYa{204G1Hqy1FYzW7cSd*b0AdUsX$GM-+Z7)4(pba)`(zNM% zZTnVx z&P-cDUiOPi5hW6jS$kBaN}GvE*2Wh7bADMWZPMNpC&tlpZ|kOyWe31j3^NfBz|XGzJ>eKQZMJO#Qwsfs z>G{-o&`rli@53|^!OmQdc(q?N}AS33CQ4|;=0d)^njs3>5msaprm z{H~662lZj+`em>WlKl5>#WgwnX2>}?=2$R}dH(2b{)18qTr=rujTayX2ked`jH3Ea zGDzlwNiUIAX_bPnYdj6JwM}^``L?R4x3fXBlOHc#6LC11ZoC{Z?IwLio-lq7`%>O@t z2r;NA>D>j!7WG9S#Kw2<02oGNn)@n#$no6o?CI?Zs(Z?)(`vT)2H|D1^pP$1A+IP( zxR2~OzCjN4sd$k-FnniP3YK7RcU6!i=YK9y1#*UJoi;4#%NW~tfcF9qi>4-~$q^8$ z7BaS^$*nMLmUUUkf?7;M9?-7g@Cy_1Cp_BG>+#&4!xq5#KqkSA8}J|2zpt!b$~>VX z^z@hNFi;y2jx89k8oWugU3AWv^)Wz=)ZdW2a)wW=4Uj&nLO`v~Jx}QL)a3XG=R|2_ zx8mx0ZZ_?2ms_gc!vK~A`&x1jZ5Fhap&HTLGP zxb=A|X4H`vBlnt>6A@SYD`rZZon?hZDEue798vqy`ZC}@S#qr+3DICn849QRfv90> zx9`RAo15S8Wi?tq!>Jbij^#R;3k8+XA=%NfHZMjMY6_Gygs%QB?d-6>lkPv5-B5Nz z@yjuNy3rI!+*L|CyZ-i2Oj6Q2XKX|XmS4OPFGUg?qBvkell>rdWLZgGY|?>ZtI9t4 z&F6=Dw+#E&FWr4S`MGf$>dL+d!E!2KIj-3Oj?Yp9|Dr}8*cC9X_j2@#+a15;`7^6B zeiAjF?H`~chtE~0D)MLurvysYugm4 zvTqnnkQy&e#`Fhgx>pwt8z|nS!Rcivsf51mnCebvppd?v*_!Gu{4;yhX7%Lvjl)N; z#FT!Zb$~ze`@H(PdJ6k{-g2*~fp@iXIkk9m&#O8{f$H3^VPa>)9>%*g@i=YJ*?zA! zjUiq?*P)8{X45oDm-8BZA-rL9W1W3!${RKEnY(AkxD56;9ep;}zuqG?rcsgqqAwSb zWlE3V9-u}&nWXCt9h%^0Hg+*|`@1NLl-epI61VPDTs7H^CSG%?O ziSWD&M~2j9iZ$Ywor4z28Fz6y6bE!sqdWUX85AG9`*LHlo+GVPV}j4kakgLR7fz{U zUC}EivIo>qSWM4oOI~@pq;bHyjz^~fF zA{K{Xkh1{0f{ni1Gdj9S+v-|wyx(P6AsZW=hGfSE2|sp9o=6bU-6@^X+P%}L$)W;# z^n|*Lvc0sP7Ds>zSCD7s?#|zAN8Rh~BL@aL!njd%@4aXaM>X#`>V}O}8I>0>6w;^; zWnJ-8GwFuZP)+dJYvlSe+t9>!|AOa7zo84+5_F8dsJ=%HnPw`7RB2IXUd5waR5#v@ z$}zPL3(F6FDF0ag6`-Clr1Nv=XmJQAw zXWpK-`5cEMj=HCD0oIc)ZDpDB8#*kUqXM7ASKUoYj1gKXvm0uvSvO3J@h$bfN#UlU zxEe;**YeV$uF9uI*T3tKW=DLLYmF^yUbCQ(n{ZGuiAJPf|FSO_dA+Vz$D6=*+)#Vt zoxVgDbRiLp1~0QGmBk;w^p6;Zd!j19p`xr+p(ypv#3h^&I%-IQNS-Qn%T{93|PQvJqh{ z>n>}PJJ5xt5)`^Sa>x!oI$V0a*F08K^>t)1#&(q)-x8d7{de>2&9;vVCR>|pJ5F;L zun@|Je(KY9CrX+0e)JtZOSe?!=&}RoDWpxZ)@Ygt9mMl?%Ad_G)gp*rK1=m)r#_}v zPCfknbL?d4Dj0HhN_I7USA`#-_PST`Ud6n|Q#hu4_?C%vWV0LWX;J>@1{45SX$9~{ z(RVF|ou569eQVU}?5-QiA9p!xaM>aLDi^#ZH9{>b8Wyi{bbc>;tncTGGUZyQP3O0? zqNhHKa~T~<_-Bf+{C#7_Cw0y^DGNdY9y7xJh_djE$U@PrF(q z()dYvW)!8Lzj!hc^%d-UGUV)4`o;@H`i)*KE0p7-u<$w4TN6QM_D@KO zIw=WuIK%MXi8FsPTX`Iw9sq<1`%v_pZutOT+MZuIQDnC^Iu&-Zn65lv9=X z))k4=vNYZ6{#Z?Xp<}-D4yFvA{ftuj`fq=f|MW)wd_(%mMVIY(^b1>0RT#YNy?ynX zxXPhJ9jedW&?}vr232|IomUc1n9Q8*n&qn=73^a}Mw~ac+P`B=2=UIyfNd9W#TD#T zpv~@w#bb3T0FBNOQ&JqL@J@Md3oRcX5%|<66n8rkk^bm17JcTVpPLdHlH3^ugk8FG zhY;sMoi@3I{@9t_4}Pi^ZH*NZu=G(h-@mN@pZlyHv$K&fHFYNDvGd0W)+ZdH(t7rYPee<@F%BiG+ zhWydzX3bx3n2y+qQ8_;QX+X>O8*0n6@$|bLN=B3PlDX&5EBlLo9jcNeE@!>yAyre1 z7vn?2f_g4*;1RP1!O%=KpOBERVse9d{}w^gB|t%yy-)qu`$x%-iHV^BclS7%mApP_ z_;Mu8RTA;a8|@Y0O?GY(sYg=-9{9AgPwE^|vzjk1^OWS>fLAHZQ9|zF-D>*sf;KzF zu7ClUUK1+b*tfFUDKWMz+TiXe@17>QO%BPmEMf7>5KcA_~j=y3Bxh9yH+v3aS}HOKKK}Dlu!>O7e4+Q{Sgv=bHwx zyrbBAg~V>cPYoNp_nQ;nF&jbe|2ZP-K=4R=iM$5}ykM)-_V*jGzBefiM zZ2S|R(at`iE198odgZ(O6954}i^F2qGj*+Ru4k1-+0A&0INZys=^K`>Hh@f@#-z_@ z9Zwd({S>hxkGrD;iGPni;~V&^RhVOqf2LI;Hp;QkL`}0A*Zz%1X+r!$L2PJOMjxeo z96KYblp&sXoo@Ag*1lluHK(1hWm?K<1x}OHj5_J1xO##Fm#6CRDKUAW>a4i9vD%H_ z`NZG|og%(>tc7PiXT?n`|*L;_SY}w;WG! zIxx~1=59zgj@CLQKmPgJqEh6HV9LA1{(j+Zjv3PdEneAsNNd*r$JAGVMcI6BuYw9l zONW4hbV(y2&5{yJH-aqP9fE)~N;eA9jdV*2NG_eOD4mjmz&FeLf8XE7g_jER%$zxM z&VBB4W_F%efD)ACmGs3FE!rbk@0$F=i5i<^(_lrK^E1s#YsGLh{w79yH3^f-A*(UfV9}yqD>-)~waV4>mi+rqv9w zuTNX&Z8r}sH8L$VoOz>2{y_dwgDY?K(ldsJa}Z^T-L_zonJhG zYdX?wx(03!1FY+hSBzBG2AxO5SEALX^%!#Pt927(mnjyBFBYrJ&ppkh z+;ZuX^Hne1Zhhx!-pa7g-%wY~(ML(8VcvBMx3oq}U|e&rcK%#=q;_RNirNH^;xzua z6gE94DjvXzGMe{m=h>8$=O*S-(|YV7Z1JXE_g?dP_-PUvvLC$M{96dzNSzk_wOa=! zdDcLk%XzYv;@Y4(Kwwg-lugFkRy8u47_k6x2S#Avfa|2QAp-1cT`y<2XLDXCjPbmF zY*tP0t?Pr!>0MD)JU)#QE%0EMnCAedw(e@U^`|<++clqG)+1ipZV$F??skY{eq1DoBjx_-VmS1wi6oLe;M-&?fv`GhKBMZSP5g5VIh!aalArn%XpF z16Y(&Rm5zpENT2$Z_mrv`08@*ra1a@p!U<;W}C_NHZnEr4mAzE66!VAX(2vI9X+V) zGjzTSKRX6Y5DXn5AQ*OA#;t$0)R-UM*xOwg3m;SX%SgV=xTViZnLD>6PV_Y=^l?NY zcT*Pqxp8#p)ktrsm_vP{MJknkD}>6lnPF^+vy5Iiohf`N=a2w$68$_hm7FXWkSUs4 zJ?qd90zRU78d01{y^kiuA??Sy7$K#Dee`9#m zK*3p&on2I2h6Z8oIEYGP#5TwFYU|=zLb)orbYtvyA*bZY(tB);^yflQ#@+|G+^AK! zcuw18U@KH`I&VjPXjE{@EsOZ9RsUHjz*%LFTD&}V&hGfL5=h%2B2%6#KT<7{q>~x` zRklo@o*@fXt039>gq5#TngFKp%T$iMA~9wxzpAQ_ls(mRZV(eUgOR6(99YzQu1O?c zvj8KX+uKrw<;{`l7Ry6SSil@);AQqNQ^oB0C$S{jkBo5kXoOTA@HNR*({|^QleC zv`uxj^{$-JcA}6?`u8Bgfov!?i#tgZ0$RJco@Un7?)VU>2hIdePilE^bg`E0EG;D|l zAg-ou!!DU{{$m5!Mwg{VfK{z4aE8p_YwTO!;dc5Z;x&50tF6OqRrKeiu)Hgi5Be5R z5MY!7Jvwz#DB;C;`s^0mo1X!)lZNcl_wQ2kKvM4Q*@S#gTCAv*c zV#xzV`DT};%WUlJ?-)hJ3T}p5X9s3wdxa0{;;c~Zlq~!LG%+9@1g>QK9CZWg1x<^2 zZaKF)Sm@r}f>g@3jXd?!B`QuL`wB>Oc`=zG`fE}AuMmjNSJo7@Jo#ILwYx$kDfGtaxFJogslPkYq>`# z`78n9aaLPbscvZ+1AIqn6y!-T82VF)C-%*#`Mk0M)k@EX;kw*b286B1R$myP=(iwv zH?zy%6)s3uTx#$vEq5y~Mxl8hDAzzL^Kqr1M_zl!-nuMBHXyhBP5^Q;NNEuez42$< zdUjIYf(eS}irfywhP>vh^}>)PQH2WA1P!RjF|h96`c4NVfJ{v^(0e0hgHmRU;>+_u z;xhJ*npQb;74ey7g3hZDpXG=Y%K`ADfz#xo05iYFU8OES9q5 zWxTufnjWWGNi^lcVC30+{XVk|{hR5Ebi;XUFtws*;5p>AlJGP5k5J*ZvH5+W&C|Xtu z+G*@Fe#tQA&NbQ_B>d%x0Lw!>i4mU)M0$EtCjFeVikl&;vPPms5wEgE5*gVo6ScE+ zOi1Na%PAHe6I7kN%Os4KEquvcMgKlacntT_DIHWd%KGhx&{K88lD&*irmuHTFPw+_ zqy6z9Q{*?ZVBz>cFWg&*-?`iOrqz5Z1w@a*YR&q2Sne3GLqS56Jy1!2Y{YzNOUZC# zdn*QQ<_)7+eEUNi#dBCx6J>5&tXePGq}z}g9z+i7GbO6I=$dOIlPmk+MAbm_%KrQ zOGpg*jhV~VQ=qDHMO-`xN&kv9# z#Vp4cexSIhV{_BG0XW=9SyK6{*$3hyWIXjR_;=}>1qo1q2Y$a5g>s$~3!{%pO#v%E z8tBvB%lz}h4uZAlu^5**XZw-3b+61gA!r|cX4t{Uxb*{BIf#zjKb`9)NQ;*#jo*(m z0%W*@KnhqjB<_>L?_@MxYX}4@6)G*EX+Xo5PBHVVRn(I~_7YT-Wv|6J!Z`+=QFeNW z0!i@15IuR;J5i*|YU7L)MR`X+4Db;-3}8kOr6ID%HaiAVsjd!<_W6ko3~NoP@%*T`H2PoU5Ss9V*g!pZrr+e_y`wAxQg6q?>aqNWz0D<2=SRS?1Zz}J?$s3|Wc_WIn_HP3k z&MNvjE3hPy;c@F^xdYXo;;}mh9-}7C2nzAwrHq;!P7{YMpX$vtxt&;6Th|_vzfP1x zOZ z=yLq@LF;Hi#qW+R@2SmkG={NAolWkdFf|9jP^2)xG>VI@O_ymPt2Z&@#C1j?XT|DL zR8bUCDvWZ|8HDGZtDj$goT`@sJ$EyZ`%DynyWdFnmzRjfN@Qh=_5cVV5)f zWT}Kr@ivee1?Lcrc~=zySxQn;zqhvAf+*wo$AaxZ%%Dk>PG>;>oXiL)bkh^CWN_4k zxM~6A;f$1=l!oXZG0)zCiUXVDsm3swM1_owiMlvxkY#K#BuQsaRMHDazkl!)!WxS* z(|i&Jkd#IP&C0~GQQ!!0WPuU-$Y4pR2wi#;nr4#QYMTs*nnYQ`je5;uLBJq;4204m zL0RnfAh70UHvIv0Jg7DF{1-^9f7&UnC2SGIw z97qYh?g^Od>&f3HP}jEav@iL5(GYP*wo$?aLFc(I?m|jJfshbKT9A57ak#!5gIdcA zvu~J1c`y11p$tR~HE~B;;6h)dp+}|U&?1n);NWO4Wxsc|KH78WEo_fgW7qnQ_W!kX z4viEo4P`V@>B65%sNp_v@;w^K50%)-`PBaK&QoKQfnw2#9J@d|ava}+*-?Gfid$a= z<=o6r2}O#~^19G3wtpY|yw{E(hgMjVjkj?sx(QPg%h1(#hXACf`9~x*bwJxc75%Q( zbjkK;hzfO(jtZ41CG(3~&Y-6VMUf`LJx5llLmMB>05~3baLD@qfAfxpUU0&I=WaNG{ z#iwjPke6%s9~b;l;|$7f-1vG!FeBi?Q$+t@0^=yw{Jr^!mu= zGeAo0H)+KrSRmbnsFVq=gpNSZp-~`D{N8%|3w8$7rVMxGW%)yo0a=JEtHf~_AMJml&_gYoJY(mv+;tz^V112YUbOX;%0K?l8 z;6HLxE3DHR43lJsw#OYw>J}q5@H=l&dEfZ!1E5ck4`tP2Sstu>ObtE#nuRF=jlwRx z{ck5N+<;7h(`@O(>=w4%?_GsuTd9JKDs1wWch zmM@b-vK}&`VpBdUlbN%!8Wb8@v9*5s`nU`>qUTly>l4}$1QoECWs^?Op(d>#msDA| zA(n4Y9?GSW4r0v?fKUFF=Rf5bO{r~QdL?ryi_tOhubiM5!jl{8?rFvPL_B_XAt}Tt zcuXk*Ao6NZy{rJ^Wh{l#>szLY_l}_$)k*1q1=HLN(g?zsQF9sT zpt{4+g@RN{@q=x(m9TNH!W|FrHr5RPJ0Pftd1&0z~-TU#<5Wa zEKy8F13Q!89qplW{r*``5( z>9--dvZT_`NTDot#b4aTX&5F;N-m$bH)hBZPk_AijSZeV&*boAh zrmfTa6j`0o^*r`Z!rN3e49P|BL8$m|>`WVM44m%Nsd$Q?KG&km-9u=Ct?Gw%-hYdk zTzQmX)usd;bT`z=g|Cg(ecyYXu_SsdlOELg5z}6P)t0w$7ne>B@lGbWP~i7MsMP=I z^$Xc?hDM(dsJK1soRArdRj0_!s-2@Mo7mGS5icm>APwOl4!O$6FD6q(uY7dl73IZa zWXMT2L^SVYNVO&jUYoYlppakYns>$G)U?b;eRz}4E87Kgfcrr=ies^!dFIYHatsCg z)^26rR0TQ&gQ2BRjfc?XEZq|jsaex=OSL$wnBr2ek+)BGXqn=1>!9=o(&ff1o@kQp$Sf}Zz*UM3gsOyZJ;tosEmqqxui+Z z3q>?^A_xQn0;w*i)6w zGh@4T-hFc*sr-*junNXDx5%nNYOTX&zL81$b-HHlqMqfhfz7LOp*1qGz~P9($QKxa zx898OUb^Ix-={;rOVEB!6QF&47;vQu-g^PgGlB2D2<}k9nDCWgw!xH#ZKo!RJkGzQb06X~g~aSNibc=sy;-lvh+VwzuapVU^Z`SH2mO z5GeoCXVAV1J+#xe&7?}_9X+!iYtkTtvW5l`gPY-4T^UBchpcq`{|(Yvhizx0l#3OH?kv$l5V{iAr`~=slLi#!WuPaurS|kHhGA%#XWb+~`hp9XC z6pB9v4)@+jQ_;aenWfrw0o6@1>$;E*vjPW`P_qsum9+I-3;*9Zcbn}zd7`+@x}H7w zU*9}4b;w)h6h^vQf{d`dk(mFQ3%)PH;Z)|yVVc?ZALAYB4xMg4Eyv<~{l5l5Hw}LK z$|ens>W%T1&Fl}8{ijMtbPdX-o*oA9>O4O`Q3HQyLl^nu9O(b8$O)LyuRj?gBO6UI z&CSoQ&Q|a?n{tY+&y9e{QU47wBSF>o&60;C@{TV5;~4V<^#qIl%S&nx4-c?zos@L{ z_2=&B}n{l~|A!@6*Vi=O{!3hnSuP>!ps7DkRpIt1s;#An_ zXSk^A61qS7R|SIlarAV9mfzM~a+q#Y0S(pINf}P(;*98BEH$(En*1l(tDbxuPKLp! z)ofjQim*hpt_Ldr*|npV?fm{g_0Q>w>;wyDei0<}zgdfkrt^!S(So1-PocgFb%_0H z+g{tGu~X2G(SMHAS@1F$XKzil3W>=X`|oNZ5wvj6P9NHTB|aNfvh(y3Gv^=dua2s- zV;%(N+FA0Sjht07eGv1WWmjYIsem36)~x9%D|q$=Z6MmPop zs2XZ(!en5RI;@in$YX+kJ;ax+1&7lT`1G2KpxHM zB-MzhKAMHEHNtBOwmV8gh{dzwsSusK;5HYNs zfNkT1ZbOG|)0{c0_Yi$V(^h%*O8+x+P-h*s&3mGxXMaVCieAhW_&m8?Y^UGUU{1~n zy-1L0Hdz`D&zv~{A9=&eVR{7aISgq3@#9AjJ+!g46UzKApUr0F^0xZvODhY}=hVp{TpLpj@Q90c z{-`1Ao@2yfY(067Tl%-9Y(UE@58j+K)BDm;*48|A52&u-IkOCrjI^2(Ro_pqVO##L z6nR_Epqm(P6t;Av`8i^XW_sd~BKg?@-rD0Y1uo%|v{GT`xZBk;$|Y*5rrC}`wRhf? z`C)#1fUr8mpfPMi->s|5zSt3@>hY79O|UA^UB46QF0u4$#Pc?wD-LheBL)W@3=9pO zoSgc1c5ndrEG#aXmURhToXMgiqiz=TbLCvMUTI-<#1oss_Q{!$W3xx5E@Em=4f2T} z&a5ZaaC^XoN0>%crtWX;rpxl;_?qabs+OzPkFA8L;j1F{!;3_@?nd-Cd3&lPe}DS6 zgu2|BNJgSWU+W;EMzt>zSg;)3%>Hj*m8=Uf#VI}i%k#+QW}gT%27VC!)nc7X`#i^>SVr~f-|Csw>8;SC&kBdda=Q)Wa$keeD6X50gj6cnQ$aV0Em?7Q@A7Y6+aAsG2U=eO6lOR+RS}wN$oqOZySR28o#v6n}WgK)-UFUyzXqeC|iihY=r6+_ow&-c+o2vyQWU zu5Ab#!72BiSQ3ud}E3zcsDLppDBaPZ{qNFnKe=|h;)?5Zr z)tYv)xWVDU$zlS>%h?~?_xnoyir1R>WVo_>qD%$C@nEBFh9(Oqai3s%wUggG? zzrFPi%P$nvlJ1BHT*<&-fWrhoxY4RnY25@|IW;-qa~wZ>W0m@()4K|P+cQvu%`4Dk z&}Zn8Vxcd!%Tqp)w=e93dE1#wv%jyIf60e&azSSvn=8%a21Q^+=4nueD~H+AqYyKz zdmpt^r{dAg|77EVqbKrclQRn3 zw%0*NX{1Jknhxm=fu>Z7KZx)`#vhC?MF!n5!rrMKr?%<8AMB+>Fk)lkgRKgWqg-VO zQPAjXT1K=T(|q2%laJ|xr6XDJOn6dli$d6OireGxfrlP`a7Czk1lwRkL&MMc`oS-u z+7URa_(nJBMU*Z5N*Qu}DiX+SheAQoRm)Vp z<43-n1CZ^8Dr(s+M*%sFIpebeX)Au|Ctn!ijfX~$|dJYl>=z^@!om*aEOGk-O8Klp_q){todI;Ea)sY?U{rkN>Q9+)jM5+RK<=-dC>IJqXkrj=puh0K%A$k##z zG!j8p-W5*Q8m!8J7@Q2MdhPh6c7bDPRXGoOrMhO2NX zn0>v2%t)QvZwt5{woO9t@`1q?mX=;jgG6oPGd+d_D*ZhB!K>EAVmx*^h2&T`FRa`- z!bobtKXX)&ntMl5Ke&0CB*Gx!aB=k|=}ZSPZzoA;EH?W#=xq>l=`%F{d-Hmm7ise+ zNhLoO09VN1hNnHv9sw{QOC-aq+~wT(shoA7I;U6x(+kjA6rJ!@qrxp=cT?Bkw5HK} z7cHQoZJ__#vP-xxRIFo;8^iQinD;B zMp@Bg`h6;PZWOu{;Af^$oin{ev^gu=rE<)^W)eGjoZNqblZS#-w? z_#Jyz$4vBfx=Sy(L?`2tfB(%=;$+VFzR|gnl3$PLOVyg;-QtS6&6#$RDX8Vy{1Rt( z*lBqYZC~{2DwrCza-jGD@`$smORPL1H^YO&wQLZ(2C9jG(fgwE8!!}H?mf{2DWC7F z(=l4?BbSy+tl>&pe#zQj_=qQUobUZl4J3bU3E?K=r;GIoRN#EUMXVJ*Y<#GGOmWhe z!rG$KijHL!5n9a&b(JjEsM^HrWCT?iRPbJ-hXzfh<>-LVFQS45gWY@tu`0e8KFVV5 znsPL5HspDf$L3-1IpT^o8!wCyE>EQ9 zXAY7-~?%-BG|Cde2L zFb|O0+S>Htdz1Uq#sSrOWrf8NZF_msakMwdeJAN7-YP@Ga-GYz&Z`}aG1owvnR^p~ zTL`Zg$hHghlYHWmjcP;lPYDpmR1R7UHgaKF+)5JV^ ztcb{==sm}3UIxTHER~`Yb`*$dDhWRi(=3o?kt|uuw*_~U5Q2IEH13@R`Qaa` zG90`4YCU$4*J5PjgL1%r2mr!Qcid_?y-XxSD~Lq%avl)=z^$@7M&qn>KYoh^%k(>p zjIj{D2Ct&Y93J#$q1(6F82VTqf^Og6Z7r#!gMhN@dks*SEVtzNwp3xTKwCMy+`LM8Xs8 zhv1W&#OM+9$31=#C;*g06nE8I zRbpl4HmsTNJ>Yf9i=*OO_h!V|l_x8=lMRX$QOl>WU5Bid;sJ$E%uXRx7CxLZ+U=go z2IrsEgjEPfMqbcda2Q`K^imzmFD^FA^C9!>G*s%Z- zy)9-Pfqr}Awwz=BXh586pb-aTi+4(=nnMsSG7n1E1o%7;Tru8M@Eb}v_$)-{R^e1d z|IFN|^Z78ROuu)=yvn(i^>SEB{>Mc1xzV-+f3b1vr3RD-`nVKA4Qx)%!DIZ#+*CMTb-`!1`pQlV3{N=L;t`gcq(P%-b z(z?<(;voyP_7%>zdS}7iEo*gu)LNQFRfXgx+}7o`pXNSS_f&J1gvskiI^!ZvkLFBj zdp9MRdrNoRfUSJ*nI;yK*-J4ACpyDvvXEOo8o4$GajToG3sC8XrgMp`5m0km$-X|) zYH6$2VNGO^I4cIFsbHRNq*YER$CfYgqt%1W5f{WyNe9NR=7QDekRo#yxsjSH^7-5h zDg8)|0qtz{ z207!d{GEMO!e>?a{(2|D`y4lzzKg2R(}4HR*afxiD|m%Ifl^TATazxH-Vwv5h6b<$ zf#1hHJv|N96&-nluh>rSb1%wrua_Amj4_Tc{Hb3H%ybf&`|uq(>C|B=~bb8 zNWJpI_)h|c?dav%SCv7IyXatVpj&^m4hLj)z&zjN=#15=+SP&APBfybY{OATr!~;X zOH-%&r=G`5!OvTQMfa+D8aShew3R6kE>p zY5fMDWya8{y6gAU^{$~R66?{UZ*T2W7%&|AP&vpDSMT?Xm6MaS91Q-Jh&nr`J{=!G zF4b=qDL2-8PB*gIu`lEnI&z=NDMx4iP)v{#+`4i~DpDkpzt8a9EW|m+|B-%09fE`Fy0HM9IodO2XUPpUy&5lb=FYZ zAZ~zZZMX`|KLjoL)8AY0{Fq4|*Jc&hE-GdLpax0=H`8?-Fs*94O%QiLR<4@f-S*NU ze{J}!x9vqN()aUhbZ_kiI^ty`mNp*j<&z+&kVl$h#QsJ|$8uYB}x1>Vt zKN&~n!|yPlW4zwGbg@Oun|t;NDNB51nu2|br;j!>4DsnM;vrT+R^bt{_+c)o2oP}P zIy#FLFMO=Dk}axdPm?@*)2n?CPc!XBo3^&H@(;qek$0nX7>v~;q1r?}vore%E-7s^ zs<;+z$_s8OZHyHDls0`^b9ze4@ipwN+^)T&c%-lSBdiDmL@MfwaJkHdZ- zx8Kx~tS!uDgb)N*L`1V0HYF>o_MjaVmYeOX!lBPn23u>e_q8q8T?z z=|Eg3A;K(koiIuvA!wen?0-SMMg@c6zOvXnU1F5LH;TkprEXK*ar8THEfg{m>=9WK zIgL(LnfD&>JGFDrZ@1b9S5CH{;&KofeQ-a+f4iUNfXNh1Eu$$vI}e`+f$N(TWtQ-L zN~6koxXsvbl}=fUp!Iw-mUl|mk!D;z9R+&w8>co6QkmRLPI_OCHJ3SgY-kXESPl}6 zppQE_dAXPJysf}){$r_~2gkMTJq8K<{pAEimI5O7Ko)ATB_Kj1XWdtw{8I?aYQ)gP z-d>(u^Byid*4}1X@Cn=fjSw80l1#q_qe5NsY4J)(Ob*+vwv`?K*rVjlSE8*-)`Vh0 z>HIBGOc81ks_?FPi~9SLOm=Apb)VoZIC~*|y2yjRcJfvDk*MGFpFS8?9^W;A%wP2g zy`Y!qw_X?8=_ds74t=eTqCZg6^IIO{#Zg8?{gAg&UIz6UW!U6V*S!&;W+zL=nZFq> zG*^%(fUHfD6vUi;BcIBFKl{jD$*$ub&Lmj&^jOo#V=XYBm>@ni>itHsjypRdUy&2yu-gQy-`8P$Lp;pW_C&@KTp6!wPI);0r zXJR0YvgQ`byGv&!65_pxtzL?FWK)Z`b<;fo& zaev*8I0NT@&jPgfX|rN<4*sag&8$7@zwftNckeV}Xj5K(MR8V~W<9fa-L!4YRp5lA zEMEeDo^tkT-tNScLVLFMVCRDJ@A{`zra*pTl{r0c9^PKj1DV>Xab6rJD#fFQeR#^; zJ_l#}`!yjL%*n%}Z)oV)Q}Xoj{U`e_@#9UFYD6jJQh3A+b~{$}=B!^=`CgnIvYVc7 z)FT~2_Fm%0U?WdtnUkE9=uSWpIJ`+T9y6L7?4eRkTkXgZ$y7axFbm2X0o!>pxgnfv zu{mM0w)|O>uES$)J0@H6zAbfjR`W@I7jzh%PJ%mDhe=}oc@K!^m)GcqcHWtI?~--c zU5YgncUGy?JgsdyE1@M^L*}O|K5<+X8&)z?#<-3Cat!s0;lRMKh)*q+ zYI!eJb~0(N$mrlUG!heFYoXNu{{$3jhb)CY&tjMHftzALGN=Y4w$Sze`tF_`yVLZ0 zm2G!RaI~Yzo=D;Q8ww*0+AmGb-PjK88fPy2^V6mQXK-e#v88))+l&}}V7En4*!Jk_ z+Rwag*VynljXv~|S>SyO8oiGZVSA6goNNAs+w%9qW^|A>hcL!wuZtrwGOprB#d;h~ z!I3KOYhsmx=cFq5h60T^=>lzhE}z6yb^VT(O^^SQ^2rsG4#z>vxKig^|Dli?QPoX` z4QRxwRE7agc5PMaHto9~redRJwR$6p-WJW&why(AetLghPt{6L7t^$irS%ogf_dyT z+1D(?U_H)_=qb1kudb)9*wXLd8}|$S^dv~Lc6Q7%%H+PIG?=(i*Ww!;`)f3 zdy945mx%074_D2$AH(Ny=y;V^u?Dw3_FJw$c%ZZT=Z!_@v>E^4pR3Df;{Ja>z$xq< z9DwKL!Szaa#G@vck1mJvt3ke0w(TB>5ugJ-cza^o@Q_8}ZcD@cp|-A9Ad<#=C0PkG ztbg1R-fSXI8ws3R4IJV;irQ=<$se zDqiPxgB>(Iv~bUlXZDM`KZZ_Iy;O^wbx$UGh+5Z=*r;T@k!X)e(s$6Li3<>-#0QFipl|@Q5T* zh?F#$jpY7Z9oT4h^6`<kme+ zLWOj<3EJJmq_VqY5&Ee4l8vF;QZeCC^U^%I@T%eOc9JIQS^4cK5|-oncPIXm7TeA@ z$XFm$6FumTqfaBPuXKj+Q)dGf8aI^|M({==j*Kz^@-a%;f(b4mOuls{fsuYAYI2 zWeW(}7efzdQ@7qft6&tm@S<`M`LIB6%m1%mYyuzVg`76piZ3G-%&h3a9S0uRPnbL) zl$Yl{6?@B#+MBl9-e0sx31@%glT&8r+db>m>k@t^6#~6#QC65QN};D~{40CHc^#pm zVY{qxy&?`zQnb}Q7}6z~GSi)J52~&B_H=;l*j>*zTKob?N-z9fD)^f}u{jRp+y36iWs5&(rh&p57OY zq4gyhHsUR_^S>CpGF*GZ@S|Z)=b;R@6IE=HKjLum%Wl0+H(73YPD=S!Z%5?*%+?kN ztiIrlbI5iKBf&s_R#431QeF#k+mcb0{Csl4yG_kpMCV_r!lsPfq@K;sp!n?Vt}urd zE0JTpj;}(=60aLOMX@{_akk}C>XChmx=(sG>gSIjCgm}ws1nw>U!sP;0#0Ff4BwhM zCbRr9Z<%-hD{cwv@m;@|#BnLzq;|0m%HzUNf$+@i*CpH7oa#L=j(~IPA}I%-lGK%sXkr@{`Yg2IM#u zQv}E3*^!mnR2)3FZywymeUh^=Tg}j!U0o-lF5z4go*Q}j+RuEcpOHw_OZP{Hc`7|q z8S+8c6TV=~;9_-Q>~*O-KOgID$4J1VpWdaGk^W5H|08Jog4jygSUUkE={^Cf^?fQd z6kRIp&R)7^i8 zKY4jI5)9Rdi@g84{qp`3Xr-a*pDo56Yp8b8OnH~+N4@;a$9DQZ%FVTsd;#Sjc)BTg zVv1w9CPnas8@XS{bMmN#={&T8Dr8e#kWIzTW5mL@f~xr{s}Faty69|n_^vlJGMhHz z!J{-4T69sWVhFqpKJQ-2UzS`Ef0@s{(ZN(+Gu7?%&9`l)`egRrkgrs6HvI)A#LxGW z6&8UKC!M>PuD4Ox^Ulf*r@VTzd-~*e=K`OuGWTJEeF|*y(16VqCnybr|Vr8J+ zsnwtLgbpmu46*7N43a7@-Sal__$Nhg&zb$eRS6>T`6+_=4is~f)-^~sScsow&#UPR z9=6!|BwZo`w@lLO;pm)ezUBIlzX|uws6R6&1bKSns4VWb4NRQa&2Q<>tRum}SvhIM zee<%s@~zzX%khc%i;lGB;3sKv-XT;ud+a7I4YO2ZZ zg2$mJEvnrUX*suYC-%KwMCHrg*(Klb`slQsi|JolxV$%7k6`dx-7e&=3^Q5ZB}_uAF_A=Au6r&m7ywdmy~IZMWc;E{q*-umR#S%yEx z5-1z=l2Qu$v28Zx+v!J`@o@ld>#cM$Se?LojOnj2_F0EbK91%ST>fOMXe+L`SfE(d z-w4JGh}Epi=B#Dz#OSL0n9wO(vk|_998ON>#zuYTZFWa-gSr%~f&&g3*O(Xg4ba+O z2NmGx<$fVKCF%FkHH=UG^|m~eIA_omj}pYxR{R=`MDY@!eH^} z;v-!z+xbj&iDa1adKIQz)3+?!?9HyXjA|Rfi5U8P{zQ4^gwSEZ4DWNz$AbiD#mO~% z6jMAS9%I_c|Ztqm6Q{ZB$9Di*Y*^%L}?+qA!o+qgChA>6iJgOh35mX!?3- zry&++vaY{cEW$kthIjbown~vxy4v*n};(F z$6F&(w4Z5(iXyaKE^0-!1b3|2(rpb#JPn%{U-c;DLCtXkc^WxWpns;<@W*_&g;v=#B_sL6DFYbQ4xQ(rX!!KB~d-NV> z>kqx(GS8NDat-UUyUW2>FJffdFE$Kbzi|5 z?yM0gCkM2mJgl0$&Q9m@u)WB^0dH==1U`Y z%X2tRyqhG=`u;Lj>w9%yKDZd0_=JuYINmLdNF6;Dwa`_cJ{EkP!oNSM7yEu=SSVpU zx0aLsf&uz;IIpe#Vyzs)s2H+sIyB`t{i+B|AVjLK+`De87fXt1b9 zngwUDGT8}ln(u~?a-i*ueF$e4_9O#EFNvF1K?=3Ld=`CNYWR*5#p&NTD%Lcrs}1^n zmRC)+wV#w%nm^#t|38|(Dy*%pX}c76EmFL=yIXO0io3hJJH;tb+={zfad#;eB)A0# zT8akw^Ss~npX6X4tg-u^8KaI{k=^tSU6>b9jFWIV#)c1NO!Z+0>l{d;v{l&2+1uh4G`14;q;( zKvQS(FFA9O7HO{%u2Pl!QD8R`@}K9KRt!P?gf2Tu_qQhLzb0K)y}s0Lf3HlEbH@F= zQY%99Yb)?8qjGZbvTM5#^*MuAvnvXl2jN83q}K-mt#1hg{PQduj6H-&Hw^xFu6D2O ziBY976N0VZh&`msbJt9>0vk;65E=wRLu$VYUIHxF9nO_2JE@sMk zZ#(Y0e1QtIl9+6D%f7}iqDKF%>l8)$lGBGpxz6S~@t2@BSns%BxMTuLT9i{n8C{Q; zIPJB%`g3g%X4>n^!_k{%ztMEmlKfQU<`Ev=zuRq_U3-Aj$=;C-TS)Q5O_i+x!YH+w zD#JNNUeeasy&{(rqa6&NlzY`AGIU@aOcx^0$Rq=57fev{{J|vvg8je_rf}(X{d?DX zUF2-&!nVXXXzJ%*9lG(!2Myd|^}f~@h$A8Gh)0kHEco)J{b1K8w({aGS)3s%&fJsa z#|**D`&|eYNMPs&#p{z4(&o)v4U|pY zg-VE-}YeqWI^XeT+N@8bVt z=IEt#wn*3P8^V%7;sS8xQW>+->D;)#7Ho%}7TL26R&WuyBq0ab%dO?ka`)A%Jqb2gZunhjpnam4{Ed&!lqSuM1V<6F@tm8Pw z@pdRgX;!<^V*<13Xg4R@Gd zCRMpdU2S1L0(M*-G^d=edR?f+x?510$ln8#-BFx))Cm@(N%6r<7$U*TSc2>YZe^!U z0u-|7;N?rP@ko&()SzH!#ok*40BZmM+!YB`-1jaFA^wrj8agMC+Ll)|488m+@Lll_ zPbI=WaF3IPOh^u45Y7Rn%^@WDiBDyirQFvuNR*jtjcQd82qJGQApF*_HRCaXQ^#lxHOm9h>?NN;(2z3gLE z0O^}60m}LHVTJ=a&gdI1**s0@-raCOsZN{N)JD= zCgrQUxy{3`RSi*f3a}ZvA9=}?8TJpxG>w6R{Lvf=5lIvp!E--8Z#P#XE`@@{35=19 zUR~raUtnjQ2bP7%T1S(yx?kV54=CI*M}g{)?mM5y$ZXOMC)Iq&)Y3^fR)O|s6N|L~ zxtWA-m6Ympw#r?)Dew0}3&Isfb(L?=Y0n_ljpDCfqzlv^UwYT-mvbhY?M4@O=P?Dm z`^o3wk4TQAq#PR8qFL_rml&jlkbX)2*vF_W{_ZbZTuPBA1Vwjr#`Pf->+=UJA$`9Z zOvuJLpll0j1_g#iNg7JYL0@K_kNO5d|OM6)^OYH(7AH$;L5mKi4yej|H7i;UB#;mHS-@aN2Zd-2~X z2zMpR$uO!c5FRFKDz&Uqj7Ua!u71c7+%I)-`8Zm8mk zdvx7>DdE9CkQ|fr`_63ngdaqxV%$Cu?05Ve+K=~7F0U8(o|*EB{Io;a6@5rxx%zhO zd(&fTR4ER!8qq4Mm+Xk1u z=pV!})^C!Fz^B`gPb!!iwcJe#^gUf3IR%t^&r;<4JA7_!##3fp>bySnF5iEvIk^5f zi9TL&0j5lSE%}Ft8#xb!-uEQ2nM1~@A<*P2TJr<-q~MJzLlks(?~QU`L|cPX&_I-i zzucq4I6|NJCaJ;;WP*N~ze8T&uF*ylesf=ST;jqbpc`Lh4tS{rV(}@5*^;;?Fnl2ngoGfXZj+XFrp^DR4*=LaaR-x;rwSmiwkEo1;>XwD0+CIhp9R~Y$-Nx zD^3)+t`A-~Bd87X6QxtuTwKoOf9@kb58N)tsSTo3c;%vjFjUBGM3%~b2R@p$0P)%K zyk}#wQ6ky>*XhcKIxgrOy>T3^*!+0)F~cVr6VFKNecpI31G|j8(RbdV{sd-S)kJ*p zC#IiTM2f%iQ85wDKjSOPNE@t32_zmQ|5tG(k>oR9w)Ajxm#pE#XEGo+J2%tzcMS4i z)tz9V%P69UZS;vBe?1Bhi*d|&ULOH^->D;(V*K7!;3LGllf?g>_fg_mhwRVVp!=%* z1r?y8U5F6=Ck2u!h>6@HQgw=BGPu$Cn0TCL?6KpSdwqUh`Q~RCecTvAUtcp`S~(wrkCx$~OP=?)HU$5_=Uc^A%YCu|5AyV_rZy zxU@rYjxi*#{lX4t7q=u}f%$e30iP^R{|nDKtMIV)?q?b79)>30*?qvMQypT$>-5+K zI_$rTeb0#^oX1aA_AhGd!Fg))>OYH8Rudo1^%>`%~tN(}zm)7EX9fSxbn_EpQq$-?|`)jD=qa z?HD8R^Zgcn_k4{2b0Tk#dqQI!tSJj&lO>#DMExcIAYoZa`77>Ex~G%~!hNaZaB z#k^I4d9cX>CbC;(2xAet8e^e=H~yuEzMvT%?|v7EoR^y#rW8efWMlaiqoE zH|3e!aj%^GrCVyjbDh-xy z@4z41p^Tq`5W76GFqANl^K(WVbuHyb4>Jfb`g%+%Mvfqgffz{%i& zc<$T8uJ5h#4;3d-*fW~QWWREj6bUPIAEU7|KBg`{asLjhjIO+vjH!(D70`OC9d(=q zW{GMgT*bH6(ZD?8Ju5w}mRl z|M*d<7OAhP)I_*1{|?a}{r#dfK7-EJM)6Po9??K|VIWi(I{ZZcD%S0BLB9J%{eOi94^7@9`Uq<+|bSe-|OC3sg3 z;baSoLCJ*o7O5p-gViJ&-ODbs9c}2+l0T2HIvF=REkqCUoV>a4kE_LxDf80**U_{G zkNm0F$*e4$jQA;<@n^>~jnt3#W;B>jE$dLAJ@(+wOvifTy`Q3)KwP~MeZ_ZR)|{v3 zf)r(xfbu*#9LeHd0cY_7{$CU4EZD<|5GUl~GOF%%k|S{40Gx=FUkuQ*qkyx&W{P_| z`L&pV%k=#+Fl`M(3v4m;?P@fws^<@CqIEt3K^T|mN~v8Hg3zpb!QYLa6)aysY;2Rn zVo?o=8pae*4frS0TKE1M2Bh5l@Gz%i+Rq@(aSrAy>-1d}2{5VEU_QtaYfcce;WEWi zjunGlL1*xNC1}Y<8M670U)V!2P77fuL#Q$7f!by1?M0gz!J~$&fUf#sLN5KcMecP% zHYYlWSC{N~boWUH+6_ZZZXw`oavJtiQe}AOU!klme(Qb&CL{F8sUOTi zU4~u%R=xVYcFY~veTPIDefUlG|5*ASM7zcyc=qDUcjH{3U@=oJm3--QeVp9A~6DRe$_5LS~u1-d+k%=ff>Dy+)C^zqi=IYBtB#8s8) z6Y6veGZnH)mt?rf5_ca%gE#Xcyj^N>LixEuEqE}@tM9{LZT$b|0_a;2ixqosnCFk8 zi;asRv(bCPs$cXpy7v7|+Y)Rx=&zd&;je$&!n|ID#C$8o47)W)6)N5T_Vz%zeElNX z<^<_!G&k~c|4~Q`A5rJh$RG-Iyq&Pb^N{h#o+E;HAl}wuhG#Nf^&4FFBJb*IMUA=o zrKNN)gb=I~x082}t6@RhInPWiaqd&o_U_9xI&0eG(02Sj1A0-=)OLG0X%}T=mCEUV zNJ1JC`me!OlpdN7mp;Hx7pmUhdW)64sEH&|LA$P#aM^0pt;y!i%CoEl^zw>-4t5oM z(^M;EVq|1j1IG=0!fP)Q1Gw<5-KGkS?^hgjyw9iB29DCdpMJ0Qa*ZI8`czxz)G&RD z&`j~BbP>|O9Ly;6J;My*b}F6zE%@A_<=oJgs-w|V`dBspldHYJH_wgIU5XWk%)sGnEX{LUL&*bs{f>f{ z!`d>I3~D}>7GgyW0UT62Q0HR>O?B^@oOZ6fkIS@OxcnWikTIC8TFeeNS!_%VU4xys zbw!-}&HZS$ z&`As!{hC;nILkIrwNkUiPQ{Aqlr`yh{6S)AH#kEB!VvL!sZBb?|C(ush_F&$ ztL?c$_v?EO%KL}{c!{hg4)Xl?=$5!nC>1%~d2H%IglPDRrwR%N8bA~$@ecf{=(G8p zryYa(x1}FDf=XBLS->p%Rx;{5%ZC6(1fc@w!Suc%ZtYBCzs#RTs0>R_t8*B)h0CS~ z9^*+ZNpkZ-)|zaTc`8nM&-#!X210~Id$|!!DB$FzliBw{#1&O*PW>RjT5PnuA}r9h z5uy<}@z*&k7p^hkOGd=#r47_3`ps=I>6j#VNHSJJIkW!_X?T>-wPDx@uWtCGJ?v6M zruT_R#2%2u9mA-#Rqb?WMoaR(f`gFnj}J{JB!zrxcu zjk?P2-GYVmHY&K0kH2u_-sl`tF>MQ;stAquIA!OXjjCgb68}dlOh8U_2Cf0mNs_kF zPlM4#gN3avBF$@uzR{c-4V?>`zfGsUI?4z0oD@qx?5g#xXxdV88LHEpjH;tV{Vlft zlGi>=J9Oa^erxAjev@fB3jCSy0Dx=aR>lrg;uq+UJr{VtQX-|+#`sGP|LOD6=K~Ns zdZOJ{Y;VTg&p&Jsg0~b;4mb>cP%>eIoqLOdI`Kh-bj)x0BkI#jR{1eeg;`>{Ee48a zZAK`Y946&T6G~M}<)vivh|?2yX-BZapbx_nBl^I`xIdNprp^h0#69f$*tSB$GC4i@E`T#{R}B(ygO9m%-0ZP#r@M9}HfBDnpky=uez=J+q_S&kmn`pbTo za}&hl+K;&qXxPZp6(3sdQEz$aFWJtD9edQbBz&WmEM>qb zL^+wWEy$qA3n#&b9>V_$PRsT3oFcB{(YE@A2Ep%`)BP{GR^FiRXR~Aqz(_`o2EfyL zeuKD^Rw4KEpeS5Z8QrjSd|8EwPWduL^XB0*6+cha02+Xgi~1njdkgP@swC#O%EqJX z_udle?z@MSWdb4H&KQo9Az*Q<4DkV*egMSC=%98~53*P13k;`g^%ZLWdq4{&SA_XD z=LY3rv0TI7$W?h2@(?htf^_D)U6Avq=UYq!-I3*A$+bQsUukw)V3P88F=v3D9 zbBbh(|1S!HR?f1vQ&xyngf?vRqxq8f{mJFn3z5o4O)^fa1Kco~z5+v-@bJMb0l0hI ztmMJ%S6r9ryrH;pyYl^v35*Cm3#~4J* z{GNMS_117hiDAF4^2_(w!~jbT2W{+mu^wbur8a)9^`ShiU;12wSH_`RRYWp^@$EO} zt}T9~kNE%kAU5oeM@ed!w`zw^V=ElwQWP_jcHX!Cvb{S$y_v8U-c?Mzv^{0=nsHWSk=_eI-EliETWdGxP3X&8^5V-`M(Z1 z`RjJT2k#G4FW#`eiLQ=agB-_9ZUquKI;&=tm~Fx-NW%U*3y;>NLo1b4Z|-lBkls=0 zxny2O-50Z`-j)}W_vzFfQFZpHrWvkrQgNgUv@F7Q^2p_T!^#P1W7l5@0md;U;%4hB z!*5#}uVj9@h=#B}7*k|#Jkd|}pCFT?&*?pA{m%ErLd?R^8Yp$|A@|#@zrCmxmjX9Q zKk%J8WB<@2%Km0#WMrXj#KkLS{&xHFgRG^!iK8aFdZsqvXw1ly#tmlo@^)}boDRtq zmrwr9l9Lra?1NNzD7n~`U$PVf=&N0#cqWauLus2OfH$?-!@@NzVgUYtQrF%lWw-GI zNK4o7dbvX7qBsNR0Gvt&a}a`1SrfOnMH=#O{WaT4%TFa6qlF%r9Qd*G!ebvAHgER_v|W1i!hd7yPi!{?=7O-Jm?-O=4E;ox9A&%r#WIB1e>f znUhzlZ2qEJGZMDO3K8NHcjq2n@yNPA;Z{7gK9J` z_N>@2KK2)LKS&`$(|o#fE){|b&~}D`*A@W%YDg$du`!PqGv6M4G#gtTD7+HJYTblO zf$+3@CbOKTi_<|i{9?&LqT%(9!&A4Wke+c~6G6(asT#bPuInVE;bj!#LR4lJ-o_o$5< zF2lhtaZRkWjBYYm5&X(nGReP^CWQ_^NwCv020mPB4{cZ_7Xg0MPF_gqtmu5?oxYZ6 zw5$^eXoRc5>7jKMgsA5gxSpYEM?f@R>W1{w0rYi~)hKpKn#4SY%(}j(#(H?l_-Acu zsDs?oeQ{)i*pFU9y)Xg$ zfIH2>DvZmp5OUFcN={_tef_4)=5G^5+0=(wo4kwgX$0=;VibD_o zxvU&B!+4)=>(gf8?NvH}GiN@x&?Ri$_2e+%>rX2}2DUH2Zn&T6!iRp)(`(4U7!_r%qdN(knK19pCSTJ-JRC_|6QY{ zGwK(P3N0XEV)R*ZjefYq4*naySv#6%EtrkEJ>kXMPJxL>7rCqP1l8A>Ev8}HaA+(F zJni^%tLT>oKUYjSM>QTj%_N-e0k3TtFtj-%Z+YZicZ9P?H_iv0vnR{+uW9jfS*Dz$ zBQ`6CK}0#1WpOEooW%tAvlZG9VKuXbC}EG_Z{sgF8*^s9JDFW}VJ%3-%-rC8KSN1WPZIas!|HB2L{ox14|O z-g}Jo9lLX0Zhggf>BFaXl^u_-uZoarAN5_XD4QHKBM$8|baUA6RI zQ@jgcAu8@+Tl$Ja-@28?k1ana|6R)Uj}WfkHx7>IC)3c3)KQAIpDNVGoc~!v)`Z54 zVrCx{-{vmbt0qo-Kx!t9`>=N;G%{*yW;4iGYaaSMi!@yteid2c#OUViJXm`{W}-s1 z?<6DEQ4!%oxK7GsDu`?}-hSlEW$3Z)(^()t^d5-#LNmpw*F_V9A1|)2=M;8~nH+nF4OfTrB!rRa$XgVAyDTcFq0r3iVCg$XSY6$fGo!I9 zpzs$%WG=-lu0?4zt~F!QQ{gA*|ExIlw+DKQCRifmPl>;HV;g1^bg`MSWCMiI-_kjH zA!y?*c0xvwMSV@;2o9CApL+<9sL-%b5(0Xnywd>^0ws75_-6@rT}a{7FVkp^dD#tfmQ zaLu;+G;E^+WxD>GJfL25sQLb?AQ8Eru11{UQ4pL@_BWGtdft&U`72 zY(tw$y>XPu2Fd!Y-~u=obM{ekfB+4_haPH4r5+8aY2qiA{ZTZi!r97>+Z)?cJ#prL zE11hEGlzkbO86KfJJn-=sv`( zvT2dR{$Y*4P6zSW=^b^FQ!RBMAaBcOf}S+stAj%XatLlH)?uGF6-n+-oKnyCG5V;) z3{;0qB8HIdIR0Go1Ot$SM!%*F-bRw|6v35AE?NU>B4j&%pCkZfT$IWY+>{v6z$Po9 zt7yEMaO}~l5qOv6KQ8gHq|4eBUR?8Z>lP<=RRL;0Y^Z9$`J7yfgmGP$=rYaKUx3Z| zwe=nKRNhE^hZ$ax975>-3K%IjWC;Jo(VaapnI`EX=WT@SVrANKbW)t5JF`E0m?>U8 zx&Ip^u*;Ix7lIA1+Y+)#6GptbLqNFSEQ8=PNYbd^_p?dAdwH5tbN|=(QQVxhc5Fa6 z;QPIR$!a8Rk+ZbUEjFT#Hp6w0ZO#WqILw7xEZ122T|rvP51W2i%y1IXW9HqptZE8% z+~w$cWq*q9bE-n;J1Jg2iqhrheKFnWNIKOgOsDzqz{jVh_gS9?hwaC|+2Fl%#&r#| zXuoN1UdoQzk{;k6*6|+s`u6x*6}#T0K4Y911QoL&z7)@FTH+Yux&irSG#uy9D_8MR zgC1Z(NFugMD(|>e*#Pwcmy2wLFd$Wy|!S6_PhX?fhcAtsip-mA_N; zbfca&Y<1EWIcE2Z&hsmV+pOd2>Q)|+z40Do63HTCFq&gc`vB1B{L*kIJ~dS!p|-Le zV(`)TV;Ux`y8X8xx5E&(}iea%{pGE~Gx(*pa=` zqEiJVz2swB-%wnAf+@ubUUcJhjyV$3Vee9avk>rpg_B4wFGj5~*tVQurUz1}E2HpA zL|5E4{gxjaQi7Xv$VF_tg)y;2 zdDX+JIZHQQvjU~9zY5`|AOCQE46d>EpMTU0S5Zxo%&)gIsZdX`B`3c0Gi8NG`r8l4 zuJmWgK8uv*SR-m%2N(kafU~C+D!4TC)QVz%fPtIj3@Oik^J~3n@1?AFt=J$u=T*t< zr$0a!xqD_45x`22!!BJBz8ZbX7-_tDwz7T8sRUuOuqs)R=wN~b@?ho4h_@sOguB+s zGT7{1%ydHr*O-g|QAY;pnn#<-8n;fr+Bf8;PdgaMhm6&}BTm9Rn&j)|eJWrB%V?5*1S~Cy>!06?wqKM zD-alAQNfN&l0|r!6Zb@Ub!&#?Log+SBolSSp?8xg!{vqU^s^u4>vb{n{gz!$h zd_msX;6QHDt0ypycUbG{g6&4j8@dX-t~4E0*g_yO_LWNVotKa9NW3P1qe{KE`ImjE}k?GEt`Slu8h3|+|)nFG*=48-L?JMHqEpZTcT0Psd4 z*_B7hfFOcmikbazTAH#JGlGw#M8d-3Fn;8F!YCpGLtkG7-V%WcIjs;sClILbM8sFkhxbpDia!L`^ z(^jwnu@FcH*Xxr1DAM=c&AQ$Ria|i1ob>Vr+F|M15&bf$;j)5;6I{nqzfuMA_89OnBri8G|;nE7;d|tQE-+e(p8RhOak%riWkk z(nV0xd5s+v|3Q;C?Jze=1lOVfxQy;_GPp#VR$> zp>Wlx@MbKO0j1I6sd8lHMX&hW;-4RR1bZyr85`o;Q}}IQ2WJCyCm#Olns)y{Y>bpS zxyBz)@zS=#Z=;riy}oBbI!QFrz!6q39)I?F`JMajRDba38GTTu+@!zY_OUaRuCa3esN(=$ffkvD$jYybRjQ8?Wy1N}6s zHmo`r&w$^K@XT(1@JeNPbt^jzKNf01@Y>7pY=ahy7-$Va5&-#@ob0~kCu~IMMrtQr zk#Trnf4fnk;#xgQo5$cJN8lJK?5oqDme9bo>q8zgt0@X>MO%O(3L{P|fim>6OxW^T z2p5Xwh9Vn&XsT=4M}KvP&L)xu;-7Ci>s2UP13Fa5-82_P+XXs|a!4L;5+JzZ)gV|p zmOM|#TxM6?RrZNwg|;Lg<{-@z7M9JaqD5~T#QhwqVe84QvYqLm*kr!WTQ78b_*ygt z2=g!`ymA-EKFSs5Czf(DW6g5&J;Sv23>C(gf31R&{nc|@Ev@V1kA)U79Yhr(sv9sG zLj27OB@X$L_Z7vV3|NJ-M&jv-a~;=)jocN;i9J@}g{W^R`5>mm5~w4Y{sON|AVt*D zX2#4+I?KDI6>eCUObHY_Hv$kf^|qT!^_Q{?!y5zNGMvEFB;w(fr>ipT@33_7qvy}!cb2){bJ`bS*Y8bD+IBIkBQa}9e&Gh|4AiPdE$4%0hEFiTmHuef z7+}sRunkS812FS}+2uQ8w$5li*FL7 z7f}TlPIw08^gz|WWcX>p-`64?oemS}!*f@UFHSag8?CeC1^#c*KD|G#N5@yDxX0eR zK4pYy+-^?iqrNwMv~+yf@d$>FJ1CT+HfCn9?V^CS$kLsjZNGEXXjSIRbOQHSb?Xi0 zk^yAMXZ<#Fl#Odx>+mvL;P9ba^&7XAr-|zC>i2EZ`Nm076RoBBfe1l=;Z!S#&=-g zT>qSP&rWlJB?Qq6jX__KsDPvI7f8?N6r3l8%eDTPNg%n)JRWhoY3%uejEIi6|4&Z` zZsEBnN6*KBLxR1jy~&ImsY(BR4>2f{B-LpOqdkD9%^|wIxA05O&DHFF-Us4CBP--@ zMJ_&ISzRo~u#ELoJHZ8icc#NK?~f$Z91`gj z@fFnjDJld|p-Hd%ykd|4BHwPfQs`AEIcpF_EWscR!b1J7A-_e9?QbWx&=#_yR@STl z#+w1ghvc8zGE!o#g%3$5BLMv#HAQT`W2cWbyLbTq*?KQ7plI}VohQ7cP*3nG(S!F_ z_qkApjnltD{}Kc0H0m!WZSuQ5R`i9U82+)m?OE^RDR=XW-`dWZzgFT=qx}9I5k}k& zOVLA;yp10hw={SUV&n|5=4Gy2>A7?=Qi$LeRw53Mrl zD&a2Q1tA3gzK1Zo7PcYGn2WoGsP^g>^|oq428i?Sf^?lDzcNK>pPjX6;6M1BP>U(` zxc_HL?aL~E4%xrfp5frIB~x&$uclL@g>MdwfpTlT{`U3_oGRgnT%Qfn;WT%`J6{u6 zDvrs(_R*{98{oH7!D-YYBF;IlNXsR0hkM6?2g| znRKlUy`LafLQF@n4UL=n@hhKCBPvqD?89j-w9(P^d2~S(!ve|C+6cewybEhA&^MbH zPXh+5N@)2HVr4VDG#>`|GVZjR{?&-6V+9jnu39n48D(pkc2^fC2W{`EN#^XGVbr}d zkLx!C5`dXY{t@K}PFDtgFtQJ|cgY7%}pG}== zx-eqOEEKoKUs9%4JNVkwb=uYKnS|n+LVsS)Vh=o+GLm17*WNt>tVJ>9k-q|ucAd)3 zcWg2^DRYk76E_(+sX|w>Z-SKQywR<_6Lsb}q`)ZY7~VBPltcQ>U1KQX`But+B1{XV z5CFro0NP8L%TO-yfqixJ40@LZs*^=twp2IrGcv-Gn`xac@BEf!M1w0&)6K%>{+vlH zL^QHCH8vPyv0wH*OBV8nId^={^r^s;L>8%fgZCJ+h_UOf7m~ZIW;e^eR;2UETGVGg z$Q5s{!ZrA(pUNq0%`ZR?lcJVhah*|BnF2Kqhz?#^XNI-q%`E?Th;&OAry-t#L7=o< zzA-(*E@LsLf&y!r!6GCy_na|F@a0xr@w#fw?f_`%_2y$Fd2D5rN$gqG2&4yMB~U+G zdO1v&3=13wc$^A=Yf|9Ol*Lh2{rM>fm`rAOTslG@HzR%hva^C%ct^erZpk`KxMVL&|)`@dqJr)3W6 zE-N3a2|EdE784L=1f!*XuWk0ceRYe@n82v*Lk!LtZoy}6_Dy~|->Xg=e$UOZN6 z=tp=tRoV(q+G%=EwVFXV+1=y!f_a8#`f2Aaup6W=Z%Q;|v)16E`M1~#%p@$5y;;jsWX;}j4nq#6g26S66aTCx29xd06a zZ@wEE137mEnwXsw4#%t6E$J`?9S+bHuKJ|_XxM{`BxKy5*p?2^Xya7)h^5~!AuWWG@0@v=2`C-eFiy(YDv zVlTG^4JQKCv=R?>P$%X2VyhYY2NItTIOCd-ksvFy`X`0DPF7{e(vB?2G$CK~ zX_SJ`(Crhg$u?!#s=d>P6<%&_=u%vT5G1Mw~S@`aXBt6m(&$xbo0DMj~PG zcQwkI;SP1ZQjP0VX|QI$Fo^@Co0L`r?L7Sy)BSnIChOjdNd(S`#XshCB()!l`H0f? zW4VOd-ZJ-IOY(f?+8x^u->UzlO0eM?+a?0#*=Dr7suFS26|fENKmG}`bDbwf8C=%4 zZndXyA)9do-azue?O^KNXSSx|y?%LNlzc0IB2{@qP_5rgec1lXVvR+PZm74%H# zHFb}1SQR2^La{W5$Mc9BUtgl#DejsgbN6a>;S|HHE%Q(tvg1920nSU!#9Q;bBnvA2@=6KuYpW2+p*QcctBE_zU2=Gd$%$Q?5VuPbQ(H&;%W4(jINhH4jVMQu8D9YexE zx+@BLn%9ovEXXCi?QTtO9N%5}4CHfI)0Zi*qw(l5__R9c;3u9aq- zLU1ZK^FajQdIz~cr*$h0t4trSB|$cUZoISma3&z@Jut{iX3vL@xkV1wP_@M1y?gV$ zPsD_LF038)fT4*cmaG=@Yzw!kul6p_Rs-}~URhENQr^~MX}4_V2Abf@crE*&;E-)U zJ45IResv7-ahgU~)s62N5ni7@`;M-}Y&jF#jRFV0sN8Jf+QKTKR zxmiK=5(#d+r*?b3^hq3v>_ustGBe6`LBvO!!mUiVJ220qqjOL)3r39W(xAzI-mtLn z65>!6H4`nLcv;6r69&p(N%Rh2cM3SUZ+8NNvhE|5O?qVlh~2L5QekPn+e_@`j5@T@ZGmN5O)4z08h!~_R@5(zo24W#S-_^VUirKM8H z6z6TH4lMe^BCpVC(!`m?&$HHOF4)X(LQPq(ET}IMfOtXMPe%nO6wqU7CERM}XjxjS zhLUf^G`J9V$Oflt3|P&$zhhCQPJ-sZNl^TyiGwMsJJ%T?nZdV3Y)Tus)F4X$aE-X2 zvan13ytK;Aaf9M3(Ljrw5M?{J<54IcqhsDyD8SjBzT8P#du6r*^T^6W9n;9-Dkv>E zCmGT2?aeUf-od45)I3n}#HJz`ZGsdq*U=Og$-S z@w#2koc4{t_>ePc@N^9Hw)1e%>mpdI_Il?(Z>)mO2{?Z@!AQH_8Zr}mTi^w)!8M@0WS%9r~3C$Y;bb@j9j zJ}KCC{6TEgJgoynL&5%hyA7#M$|OA&!3(BCr5?w9gksgvW>Hjs`=QXiESvhfOOwIl zhe_apCv0^m?fHf?DA&^0O}mU#>R+#k5m9{*>@TBrtF7w-(3>xrUNHUz@ge&3Mu~&$ zKJ5u>a9YUF>%>@Zss7>t59BV1cB&UB{1G%!9}~THaV3lNXPBo&@o&fXj0+up*WSZ# z(&cyd7rvQ?stVP@6=;j1l=LMD-}Lb0|7P-kk2g^@`N%hRtyOef8ntTb1kr)>?&+l>0rQ;-I)u}nX zHJ=L$8D=5$$ct|no%`x^{tbS$3xvfT#SDxm{Op|#*V?SCoYE(I&j_8fnn%U-6Zf~X zGk+4r6Y8Fn?IJPByTpZ^??@}@d;KRn7TaF0TBvrhPJgm9sayX0gfLl%UF_#v0*Zx$ zetCLJ30JC-K~_G733=)Q6-dB8!+st7%vq#}0#h8U^WB5-$?w(=s+13jTZeNTl>`g0 zn-GB!hL6#~*)W$cw;=z^^J$NFAt&ldFhu2_)sA$`GFu+iyz)Mo7F}-6)8~xYK=KY| z7ZV%iX;C+u-*3X$c4$!?c!+Xuts2ZdGpbC|dUys_!Sa_6{?Pg~c9#64s`Q}Gw^3VJ zuJ57P;R*_?lrK`_nQ}dz%tZ$Gt@A7D8oS};Y7oLRVhLJmVRQK%^?UG+5UlNvfsCY! zh^|f}Rpc52QrxN@a*+!6vHysF}}`L^FE>bLBWU0-oP@MY8oHs z2B77agCj&hS^;V-6Cz===Y2$3GsUH9+rWyVa>)@Ub0VX0>0yKC6CbKWG@jMruFkQ* zm`!0g*yJbqDj%;~?|=GBXt-O7=}A@-X-Yq`y>Ugsp+{UQ+@jY!a)dpg_WjdCPfpp- z$968EP0y8#tI%H|+N@|<5L!%L^h=3Xjh>4rj#;0*tie%Q-W6&F!^H3ez(pR>crQr2 zn7}^RJ)>T4Z^txhYbC`4WZ?{-v!TyO&VARrQ|uA~a7GV&-lhsm+tJXPKFO)L%lZGYEoP$r6o}A8MTd3~qdr$clElPOxuMSPud_}eDKTwEwTfh)`KM^=6nCl@U4|L{Jz^a zd@;A%$t&Azm|st3nQll_0v{VU%l{=P4YE?NU6$}->3F*}4p2=!ysG{m8R4U^TAYiX zjLucsKnL@Ifvh?>sP*M-FARdXs_*u_TO9#>)TdN!p8Z64<@)Q&Ln}=pwr^hP#JX-gu^%OI3H->!11Pjz^R;BG(_4z1TXZ9 z($RFLn#wK-0-<9z5P_??&RNnMp;MVD`&dr;osQb+Uqc)I+2;!`l_49VNRGK)4@4U= zCOElMGMz~5A^Ad~U^?B*m(li9N{Tc4V`4U!hcf?qISVL&CvDUK5Z$BWDM6m)oUiKX zVG~`gVRp!QrmauL<0cK$Q0TKJ+PP5kTpL5Vv8-sOkc|bkXhZ;SIWkk9GKjYf74SvC zwv<^4>p)nG%nLEbQO_7JGNJJDDh=W1)#Go{yj~rRM9u(q{@gp#LUTQv+w|$cEHB}l zQj6)Q{$xuwOYXV5#5mZ#z7LExPg{rt{CJ&%@k2r0joj%2CJqu8Nf^_0RtSN2^YikL zLIj;*OR(1%e8aB~%%r>FckY3~QC+3JPctqyQ+M;mbiA%b%deXwkXC@XBoNyLg(g8< z%4^O5q9GrvfpXd~o}JDb|4BaaHF^`uC{rV!DlggQ&BjY`3a@1|7Ik4+WiAW8@hx|G zYQyG?=niC!@_9gA>>KDy6{E6hRu!XSuoe91!SLkAzME`?d>4H51D|a^Kq9n67d=aZcDzNI1p6+X9D;$dCDB z3t@s=GK3s*$=pGovm#Bo@e1Z$(Ji6AI;w2hd39Uv*VulUTO7i;&NLTVmbuchs>0`k zvwzR_CFZxt?=4y=dkqf?3OZDkchypC+sEY&z)yw`aL(oyt;1bLi+z1ZO=;u{w+=q{ zsFwOd>pSKx@UtqZVj+FDg|iBIN&jiY@AMZ#JcAaP*d;ZENf0y8c0?UzutM0xz@}mq z`at-quA<7jvTeOJ2|K*G0)wIF-jJ}Y@;0xw+PiO0KLfhPY!CLxw9EBG$WP^>cN88w zXtv3xOffoBZ`vTErT;3-r1pr3mER6iPzttQBN( za->m>y5n9{FLfzgX(OWQdmeV?ZdX^D^`K_@iSdZmhNO%rGrh?PL)me=mSnnifv<`0!5wL<=>bU<##0K|2}rDlA&e;9P0nRP)v=Ptb=YfQ&zX+M|*WHi*KffCif60^XSb#z@04~%&+ zGIS_(S5pTGqtZ@S#t%*2vVP6_e>7cnR8-y9MoE#9ZbZ6UK6A`^p;JJ*1*CiE z?uMZoq=cbUYG_8f8Jh3a-RGRWpXWJypDiRbSh5P*vyt{qd`8eWlXb6l z$t4B)TitmJ1lGXcn3jarM2n=XJvUK26g2vvJeeL1q_>H0LJW*Ob-$(eXB%t;Jg6Qr z9BUZ)S+>8-zBYF#J&U5kliglIcP-R+>Igz1o)I&Xox8k@ubF>RGF_w;P_2D^>C68M`!MwNfyMv4E_j zqACvEh%7A-_QrhMG%RxKLX+v2)WB#8YT$Z59!~GCK0=h{^!L>w(MLmt?%(T&f`1@J zDGiRqVr%rb?LX>`DY;QCm(5=~Qv+DxV^H4|?ZzjT9hrgvB^l({9^-�zr!Wq+LDk|fDA6j;h<><4(Zv6M%ia}6OBaBuA8JeDMF zbSM_#Ti+&@KY2q}+H4Cs%&9hO64kVE`|tXOC*9-o!z{Wa&zn!7)H=#YS4v1tRL?jJ z**>rN6Y;_m699SfoB?{107t*Fou=3ioj#P@%p@)H@VN&ECas8yJGdP}THbE5u3j{~ zMIw?@fB#rjf`io;%}wwUH4D-~w0cKP2I-+2=WuKqS}!^(M0{b*q(52OPYnWjZ~p$_ zl|Bzi5&!*KH(z01h5F-)_DE_mjVg$Paa_I54unT1?O3Lz#rnSG5222s2tX#2IZC5`gYnV{&-lfUbdl53G& z5Yx;X?#AF^C1`tg`)VbchHrN}+V}W}#;nIXu)Ey-U3N2aaq_4=FyiQcBQ~M%bATb! z==g<4@r=>M{~=*R`7luy5%i5a*NC0FOKwYnp#_&L7gKPL;F#;XC?J2 z@?|E4mB9J`t}-bQLR2J|NV11|HGh9>9O5v9{yMh>Em(9h0OpOm9+)s2Hpa+S=iGw; zj`OF_m?}G!^J;2S!wf3z(oRua2qNtHf+^$Fez-U{#okV z5JD!}wy*22a=dl zMZR^TDxW8wY1X%NV>zcj0m{Me1@^6j5U*E6Ep{`O`Dw4Jrt}J$bRwAW4QF)+gOeWU zQ7+iGpr*Y_nmn`VQnnFV*Td_aHxVVm?NkTfEx%gVv~MZ#qv%Ps7%4a6=HiGI>wGtJ zMlQ@->v|K^$}@Wwz&+abYhDjx=y{pY!9~(QQscx|T1Th33Bt2XO80k$d+AR%UN6P0 z4Kyk%IW<6j+5Crk{7`-bk#unyNYZA%czvRYk;<8;z8GRAi|)?zLnw4b1!GE=Z4UIs z8T$~pMr~{SBq$}v*%#-3rq|dv#nuVyi4|H@pyZ!(%L*#)@10dYcjn*RvikTH%iqUi z{n2MU1G2qpDtT;qUpO(E)Z%i+awYV+J?pl2Id6V_1YKVb<5E1hhFLZOJz7TIhNbn* zxV(==6`wZ-exb*;K&q(d*{*|AT9$&`xrsGl!W|Ela-54eNNST%XT`HBB=_20Fh=;s zv3>Z8rx_g5Xs#BQtg8U~mUA$oXt?=k2XU6Sul&>+I`M(>pseO?I~pGVtC}8avOF<$ z%iw7&yOmaV}_jeLDX9EtPl_x{qWNxx8;bfAhzpy9w4Ha z<{vm_1*t4Q*EX>9U8>tODfc$9PjRYux5$*M+?6ElS7k*Y?q_>gQ}bQXl%#5VvbM%} znwge#M!pi1FaROA|L2pDLJ1@Au^f8em6le4{Egq&Fa5hZcV>LXA7|5ayUT3-m=(He zSTW7gB?HWbGv!G6)R^2jM#4JtU`svUw&vIIy z?es^f`Gg2fTjDaZ@nKHy7y&zXW)9?P$t|<*Y!COfd@z3f(!EdI@|5f){ZYNV8=JS6 zHG9Rtd4|>T1l5r7)^>r5EzsW5diV})p0{Zp6z06PFq!fBwYH#j@W;xnc01o5!flW6 zne#7}-8wHx2@JxQiwO*4{O{jJOImjl(}(qV?Q+}`aaJ@yaG-BRX3s))zEXs5{X0a% zPhSpAyqTVLTfMa1|5hYNA2aOuskfje2U=Og9lB!NpWN6{14vH-&5atCDh<1anrB_* zzaK;V7G6w>yN+XdN8wc{X@%tC#9Gx|L0u0>rJLk+A~D)-V;-4{$Vp0_3OGoB+wDJR z{Q=ydV@vK{f?rr(_)(XeqWk>006<4cUp%uj_}AYHFp2+A9a5JcHjvj|bKi)X7G@4H zK^yJ2$>9%&s<^I$w%i<8SZs;n8T&td6Riw2)(Ct4F@0uq|yYl97=*d9zv6 z(%B_=^jqlQTN0OuHksRu;`uvzFV9Gq$p;(znVu%c)bAq|GcVyu?y{3w)HiJ@N+bl#gs@Q8FQF<)$bf$n>ezZKlgrKnxmqqiL3k z{HV0mUDsNFKmJ44gSLex`Uc^ClKOm%z(PlcX%ju%u@yMFuZ&t?RQ2NK-&thik}2zE z8vMm!nnD>{?@Qy2Sf7dy)XoW!QmbP)o9>0V%B5XjV|l?dGj zLS+TcC2S>a?R4AjXU+%4#B6d-8fw8E=5N6Dge5XJ{)m`Dpd=nnh!^1DP zOaDZo_!i74JfGoKoBP7vhn4`%#dRD}J?LkhcnAA$_sa)^9a~;`G&3Xs zvSx+7k_3`B@f4%Kc3BR-qXxRe>fG3=9|okLskDDR&-CK${XRNtOM7EL2qg0)zHl^$ z`kBh=LYK=o4e9l%ZO87*H`~9hvHiC>ZRc|R`kN>bRzRiU@VdakV2z{LL(GbVH)Tcx zSW*`_kAb-7CM9`}Z<+rBicsFk-8KPxg+%H_hoyHx!^cg%x}MEfpQa6ifo`{H>OZM1 z^T;jLReNBI96hM=o;ZE9-}wh|!b;D6eAPTx)qa5Ja96R)v+xAJnAWpU=ba}1isfj* zhsiaCQA~5ZtOIm9kSU}zP2Kf}Ulb$iuSlnWrWE{1sHU+c%V2;?w?O|D4*cT!RcH##= zad_Bb6c&j|$RxYygtA?J;-4JxR%49RNv{DOH<00n!$;=@L~>c9PzydFAnKN;*dK|& zx*^0wNBS?*cxFHKR>D*9D*#;b8>J-AWrkrwVcavk--6Ykw&)L^6=ukp{8uJ|(RjFNndddPeyyT{G`F*z zCd8HJAZHyN#o$>x@51pUw|=4)&od=YEHAVmlMLF{-K~D%=e^;XQ*Z24ll-gkx9p(| zfG$T3|3^A=M=cl z2=8&B>->USG^+w*J=ruVpvS!Kw=_vur2-TtYw($y(DsZ~f5}GNZTPn0w4Os}_>Y0s zyE*muyPUmaTque!Nn}wiy90V!9~)Dc#y`^yAJh`A$=LCm>*hp3geY9A1RCerLOIGO z7AGjwWLG@R(U7+@nlX}JmKXwPCq4~0lL&tC%)eH`H++_g1e}s8-0)ggiDVh$hxf<0 z{yw!+Ln7wMprxjXUpvOTXuYq-M#E^=J;w8DCS@_C3O9D>@Lu?(NBkthR^`TNF*z%R zq!_&+XdpII#BMA_uz?jh-|M%|1&4b3M-Us1$OGdzdNX))L30+yV}B~Z%Zz?`+ax6@gH2Mk4uR4 zd@5XuDmi^&DfaaH8!^yQlWFSjlo61&LfvNWvF49UyxlCaJt09$O^sKluoK^9Df5%j z>ScPRrUgexPM{xB*A2yTQSnFl%(2@pCA%CtVhJ%oD4^T6pRI6<9-SYGVFs}@fuq}$|;LaWZmV~@(H zjsltw70#_E|7KRRvVWqN1ht}u|9pN{Af%;dWL+@=bLC2aT?FHRymrVf7HMW6DCfAl z)jKUGb(r@PcxT(lFCC6rFqO&W1i|4yg4>2;Z5)8FA;JHoU5xrwT(r23%*Rhap`_n8j z)3hK~6mCyLXX4X;M3uOtX9Et-(8DN>?|=+;((ut5)LRy%-uiPKKjA4H9Qzgw%VSW- zFeA#7HznntiV2Mm((@#=B}h>v@AL->c$Esv~(z>SkCPEV~5&3T?A{nJM z2~j`gsTrM_L`h=o5h=bbG7wTDL>-LE7+p|bD&ZNVQnNb75fvFW{^vxcy4L$RvmnIwkzM<_xV=23hd*UdLee7X9|Hs>}? zF8pP&{Fy?wATdmUGr%Va5$(=oZEYTz*7x*u|y*OJNZ7%e^ewOR^JpOs@>> zU3KYp?ho4(oHx@SHboVv4&|vE4jm$TQsh`jHyB79Y8Kr8D zRxGPv1ErYP+r<_4PD1AVm-iZNpZQ$`MkyNlhtzXVNBZmCn7z+955ZhtsymJR z51en?B2lY9&o;nQ_c;Qgf(G{U`9taVK=gU0jD54kb7Q72+sar`)*1L;+=5}Etsw`B z`=?$ruz(D*KUHkntU$Bo4lkzWfW0P9sV&Ul59)UUNt;>s7{z28n_fQ_OusYYjacy+ z?Yjx(*S&&8%*`!^jNsAa&6M6A0s0}48zshS&l-sunXcBG<+kFVkXL8ty?i6QnHj>I zE~_Cu*z1l?3*&-*X}zc#dBppP{)+8_F5Dp9{6>opSyl90MM<({=}}2Z)!8t)`xVIW zcBtqC85SC;S=m9vfawdJhWF786QpCN8-;#X$-kvECSBhZ`(4}k?7sfx-jd6b**Dli z;PltKj~@Tke;9=+8*^Jcch|&xltCi~xvu{HwOCw&p%hgVVeQg?*)X%o`bJ61v6sd9 zp%7e#Q&e}lWT9_=xlbk&4Rxc8L#pL@!uH0wInJ9;_a(l5$izl_~ zL-%aBB093g)|n=%)IA=SjA?y-yC_pV*x8UToH}Pey?HQhqfqMKJ)< z-*th=+;sC{I(?1nz{xtE^!_b4*{8A6|(kf8Iw zCF42BSX&;SBo$BEQTA0^x{~cY*hnWD?__seZY!ZQ?N_oBq?Z1yI+gr5B}6vzAB$fO z+$xh|jrIq5MRl$75#>e8VsQ&`b#l5&5tTCprJ^r%Er70=F zxFgBos3kB~cMt$N-8;g`f-^T&%-8QHTNtJKmK4rsZ2<A&bTRuf*S6fr*h^i-g zUilcF;x2cW9XWcEG^B+g>71KkNp**k?ey|D>5S0XRbG+}y{~7Ns5V5ACryzwdN5kg zrY@B)V~pHV!U^HpydwNCu(fI?a$f}8;~?9?igp6yyX}kJZWdgz={r4U8_0PMw)^mj zo%ko8vg@p_Ocn^M>9C$Z^qzyP*u^=5vB^I!fd;qZjA>kYg<#($+g%y6zcU2Wb~wLR z!GYtXB0}_=HL|wIg)sEJJX7>Ulv~y#S_&DKSandc_hS??qcsP?+RC-M&N}TxT2_nZ zFnhx7fH2#RHwDokzZP6_nj{FZ!54SS;&|l8Dm8hT`6^IT7p&ysj`4mEv&g*OfCUcR ziLGm<&O?gT(%Jb5Bb(vl&T8-I0ub&Xf{rftiuAC`GLTcN6;t3p)+%bie2)%5Vf52SBZ+Ck$k1f#slR6aJesrK== zf!-=Xvs|R9SnqC)<3eKIwbHa)IJiott%;*y*|R?X{jhIs!?Qt-A(vjQ&TRRM2Sni=nLIzLaE%Oys<5(U(+0H^gM5Jdr{aP1){q3y9T4w^wTSTe(6vp2Q>UHJKN z%s{hCfNf4#*h5u@KsIWq@!lXk#1-{(B4Z2O4 zU_U-CEs3>St7q|eHdwY-*NMDN=m=>fN#5zTPXE(I5F~-oOH*W?>F@yL`eP(@HQ5t1 z!&+-pcA0XWk13k=M`T3apV~vTKX-gbmxFn;v?eEr8VZUmE-Z3^uakH3J+ncr&sncC zlM;Z%OXS{Ff5Slf!oMHe>DOD}TrxaGF>W(jh7Q*K+;fkhL4sax1lCAAk6t=H506bq zCS2Q_)X(~Hw1|NQvQS?1U`r&{S@odV&vR_^vFuE)9e z{g|KyOS|3g1n<{l0mtyNfQdX^x8Jq%wM(NKE2>gWNLzJTd4#C-2mx0VJCqbBYz5Z! zm7hHS%V3ELO%}(VYlM%-wvwl!+T!=1nHhUS$Jup6-oJ#>>9I$Alv~rk!>)=?^eFyZ zAk0*NvCTQBfJO`L$lsv{&DL;-HoL9LKAOU`h-k_qPO_~y37439z9w{#FZ_7uaPLkD zNxU6P4__qY&-$q_d~v5!%tjCnk4=KS0!w*`P4JbM1CjOY=BCF-yo6H$ZO3$g3{HuW zxlOlro;4%?)ihF*3m!Kpgb?N=;kI7E_SPU+mL`39Qn(G+ooMs#^-g%d%V!;^Q`o_f zHLjE@>s6(=YlI-W{JE4$ zXIH(fLU`9pM2GF5USte?`ag#QM45%x7H)(KJ1-MuDTBF}H3(6+&QcL45^->0J=-py z+tI$hKKXLP781ilk7hN?#fY7X(@uM-Nmn^yAvstvW7GY+z-Fn_wW94KB7aUp{^*}M zi_T2hH2A3v>7CgW$f6dDT5P8aql{^5xS-)+_u_kz%qvd|djk59oMr(@8qD6K>;%z2 zRXomBNwy9df6^`;I{%aDSwoh1k@E<7JMp^f3ixn3@CG*8v1qn3O@@V=re+n8v@fN) zdt2Ya!)&%9eGpwAyDX$tdiDG4AoYo!;aN%kX~A+gwWL1k8^7symp)Ver6qsXcvQ_9Ux~;Ujl3IkWMKZu0KGT!=y>LvBUma;spSl_n`OJ-A9E3xCwRMyNjPI zToU~ZHP^99RzMk>XJqiV z$kO98^=>jQ9kh@ggd=nrJYldx_k-lx!~9HH1HlZC2ZN?&_3$Z9(XZCmhLF~(>2yim zpb62k*YiC64xU3DdL3uVo<|=T11q}u4RQn=3<(t-9a%opmFLU80F+GG{}sbY0c;5j zdT>JRl}~^(RHv6>S_cT4YSgVCKBm<{oZ_7q=Id)YQki?AhW! zy89QqtGW~TL(l96$6Vz%f+gt~v@jrT;@*?yLJkDWPM7|dFJ`)#-3(u-e=HTQmCuU^ z8u%w?DryoAb8wxp{;wWgO)md=eLm zN=_5);b7~kvIBBkd!R_t0JRRwkvC115Sci#6&Fk$!`e3^&%=co(IzgxI{E%bW5?B_ zh#y--;~I(PfXDl-u}87K()Vn#Jq_y2wCjrMoo}HcT2zT=xZy6N_cKI-bybDt=^!7< z=o=x*^Ezf76t)}JDn(J3X|hZ!v%3I& z^$QjT&uk4sWSN3D1ygbCE|&Xt?{_vf0*8jsi)Xgdi^ypw)w4Oa2-BB|snnj?h zU!_8{Ow2=iWaXk?TR`3}1QS^n*&i;E3Rat?yNH%;s$#%i_u@)rju{!;4l%N_WSAaU zXS?LUSBOw^!laMUkS)5J<=;8K;x!|ky-L@kj~62DZ55caK32g@H{zD0PC`Qpx6S3~ z%TQzlE_{Yh-k^3Ke9hQb&jrJ;um$l5ct7mkUqx}$~w9c=?H{=!sW~Ud6p2JIxDQBb?0c= zU6E0co!G_i@k-mGo&}_9G`l#px$oiNG(E5Ju5#z-QLGskSERf6T({&@v>rT)Tl(cv zbPz-G)3cI@(RXy8J|Y~%>N@IwDz)>Chf3W3LN1fDL+sENHcast86PSj^Y>s)6sp6V zjD`n<=u)hx4R?}i>-1?VN-`E*Levk@$OuMY)zkAgS8?)Nk#3N$hU#kDasX|)zx+uP zLYBff2^BQqW*&dnCxQ}Lu_f$wrCLi&GXal2>*GxQdzTmTpZ+ps#W}RF@%Q9cn4X~A zX8QyJ^~2IqBV$vBg-i%uRzhBN#yLXV>TaB-Pk2g-I}tL>tSQd}>0wA0k?t|ZTm-=Jo$G7ttuqu`?8t$r8sqNM)6*VP zp0%!clF-_wvafBv9y)w}LTJfJRxG+Vb{Y;G(p<0O=idvc;WGhMwQ}dmbNx*f@kbhf zuVYg#T!TbClSXSe(q? z?-^pk@m>}Y_HFz;^BA?_&u7N$;msKH@bNMK;9JNJjT9Erqb;q+@-ALt2~4zzYGACe zWt?G2ETx&LKfY{hSA$CKa7y7b!dQ1 zNXg6lAG#D7fMLdb0Q+SdXlB=Mje)TZ7>D%{p_krknIr>&0d8T1)yLNu`B%DLGMnjR z0-Q<~*pWhK+V4muvCx7esZ=&Wv_Jln9|iz%7>(ch{fWQH`;7Ce1MM!q$6t2urHyZP zUsRu{rNN_!BkM24@q3orc8^SZRat;B_tEk1tr8vC;ldzQD%lIy^DqJr?fp+8C}lO z^8Gmk8U+Wjk3^0}(oPXBs?N1}`DxQ`i=wiq?CZ3W7Dfn_&HyQGCfR_~?`Hw(3lQ(( ztp~eQ#s~^P{h?KKH37V@b`^Ub z#nWhn{|NBzo@u5q*IY zSAt=Tl>3$_e)Gj|MWp97Jsq38w>%l|;%?0k|9I>2!Ghb)uJD#K=C)e*L!WUih*DQP z*b_x9nFs>JNA|K2tcFJ3ns-`Cwb90I-x>MEX!6QXo7D<4a4hJm!j`}L4~I%$`I5n8 z$AyzYMO?;RrOfAHy$xXvkOs#KJlBKHt{=JKJnAZF7_b`Zc8h!~veeXPG^7tTtXT*T z6#}D}dV|-*gOg&o=w{wz*_ygq>0=h?+M&&ypZ~yB{Nj?raz#$A=Dd}p{tn>H>8V%m z$S+lUBhrMxO88o-NG1$tMtgyo6lbD8ir>3-#Cz7i>8CaPo9{cM7pg5%A{v9xi@_`0 z!PGE381YUPV}>Sz1Fbt_txL4VXcWOmcaCUC9eB+Hh_K1opbX||H_B!hhLm3Q`$wf| ze`{Shrf4W{$AW%Xv30E0w*_fC#|Ar;IyS}#^LoYWLq+f)F4E-dj@Aw-{rly?qt#5ICIQK3FUEB;Ss%=}d4;%jzOoyK0G*iG72$#e$PFc$F`1Qpi zq9q}Q+2A0scj|G&G9$@!IlCiK>K`Zy(qrv$cJooxQB~24em18j+hJ+%HR_d+>T-Ea z%{S@Fe=NvgfID{cdy=935zN)+9sbt38br1n`Rs#nx7j%ojc9%?S>1=YZ!?40;rb)m zZjl41%vz3m4=%cm5!$(7(UY?YA&qx&^lj`4pwE5_)Q_Ml%>;V#Xc_X@i6oG;r?Ksa zEGynLt2!OkPz2UNLWk{%o94n=NHM29PTi_N1}JI!g?GYy<9I~=3;U zECQt8;+eAInc?9|&Lb(Jpk3O(Bi^fCHJ&P*-~1>|+xZ56>#${j`2CTt`$KXYszqoV zGDMm)`NAv}I<%*!qCeMw0Kd-H+N>q8V zll#No=Y4-Ir3>DBdNMNZ_M4lV(@x$IpQrP(8anCr#JD@`?3!;R7JH>wLuI<$ufvu| z4=H%VrquI>t#ZyVq4XVpr|d$XeFnMYx*LWP$0GZLi0zq!ALHIh!h3g`N(BGL4QNpn z4u^Z)Usp+Cw6(X-gyGU8!J#o8B@oCL;Sy0f!tWko_HTl!_wVw~q>T^VejY87MbjYV zzUZ@$C9&)VZ&yrScC!E)7(%g}-Yfxjr8^a*%d zXQ$XOZ-+_LJ{5MeA#Pn()yT!2>6*0Nn8{la%8|+c(2$z;zqM2?Kt5&|4&O@xhWVxE ztBB9>p_Bm>_{d+0C;^6h0_&XF*(uszI(YIcp8z^ieaK>+FkYfNz7Z36@~GP7xvJEa z$y=Q;)2j~-JhY-uq?hpLLCPgKIPVx-&QCJzBF)?TU4`JEqP%Ir4wH@^viu+-lIWrg z^Y*>Fl)Jb!h#WBZq^6qCI^dN(rC~ufCOw&jxKm$HAvd+9|3q8*-okM;;ys+_sN=Q| zlj;I#{ZtIAc_8vMOXSJ|%W?s%xuV)&0(V>SX)p-xT$f4$$tSNGD=DwG_t!H^G#*P*0a@jB8Xvl!^8j=8x!|CcP!5~duMSowmJ6fj#HO|0iYs_>u{xAnVD21eeRt_w^$Fr_ zmGop&<1eW-+{!8j-`S_oKTGTd^tedbv{y#m#35)@N7j0O;X9rlRO1m$rllZHYWM8B zNZyV|%!>04M->#1=aXuAGc^u{!V&J!?g1w4M0&uSD^3>8C} zo)&?nB5@9P|4Nm*k~-|rQ}$}mihL;DrEmMMhix*`tNS#gaCaG~L%!^Sb0y-_)PDH{ zmtJV`)q=r^b%fwaM}b>x@`e&)(#FxUS&^65SLX6)-RgH_1;0pd=icf&MwQQPsU9Em z^b;cm482L$`%W;_cD&9x-sTO9&9m-7RX+eO`-QO2n8dNj;cIFZ4VX%j8NH@vn`65$ zSi&fkRChRn@K1Or&$CvJaQtwF=&4OuKCE+l zntkD^y_pjdX*wJfUcFq;H*Zxbj)Nn&xj}h5_&U82$^}z8^W?sdcbeMT#%}KJ3s)Oi zNn`4rt%a(ZxROH@1sOtGd!6H*3!PobN17ExMP|Kt`nme=QKF&hi#X7LKmo@nV!3>; z0)DEAAu@ccULa;V38_;Ku|^osh(F{Fm{#XAC&5>n@+345)I0r~waBpuwgr-`9D=yjtu{vU`jGm*oN;1Y)Xu!pA{UqEFSs=J|WB`L~&jd4_r^`@W4@x8>%J zb(l&C{E_cKumfLR8=oKUfl7qKjIX5a0tuQqc{r_!Pv5DYv%eeJTK`t2(-{j8f6mm4d--&oD~-IS$Ih#Fg> zDCE2f=2p_?TwvawCm>I{&XG1OE;)4|*l#$M@*65o4__E04pV_VKEIRI`;p6ba%Bx2 zcBYE)Gic`33n}~jq-Zyqqm>g4KGCm#(?wiioYnP=ggf|G_+XGRhUO)KcN)^Vn*j#- zyjz9l#|*y@EAy=dOR>wS<4IIHIu*Eb`D+nUmK@+AP{LC&$V4x!xV-!ec&E>ZqC=6; zm#q&tKS-ajZ0qWp9~*1jy%09UjQyE%Ip_VTwxBOP<3c89Imqm14zlUkx$P&#exF^_ zVCV9*T|@Q>s}2=uJsd-+=XI5K3aqPha&a+@{vVLg*474|h+7Y~YH}8}s30nq*wn=cOfA|TeA}}cR!cYnZn zceR*`w=vJY3UXfCC!;i;_Hl$^xo7+S6NMmaSlj4#eJ4Hay2iddtozge7`I+iWsI=n zdRm88GMZA&*Ont?yz~#XwOao4;V_aAPQ8wbB)PlxLjT0ey2ctWgUUv7EVQG!U$wQ|IL3$ad6Mx`c)vL7kXj?=&^bxQxZwCSDVvf;@)ob~DB4!=K`k zuGqPW^w5e+s&zA%O@DGA9scpu+*8tYn@4$hv_85R=rt!+W8;~|KM(PSS%~Th2K6AQ z+4>X`zKnk=Kaj6qR74;UtPw%AuG<}mkpn&B13gQzyJpS?1H-nd8L7nZcZ>X>kXJng zL4^q$Oeo51O-^9sxOvD?^ujz#6;bA}x3o zxMPx~ojfjb=<~-_^A{2H7?>tiw=dbv$Jr#!cbfNAtynelcJF8G-WO27Uh&de@n=|z zX0UKzre#<1>Q_jLofZSRc{y7qNJ!1!SM=Ri6Xtb__6E9Zhm@5kzdQQa5FrBXhm6UKbWuwMA4EqHY^h$vrgjAS_zg>`*VG6mo9a% zA=i=}qvDdoj}5v_nZrrNyuby=h@ip|Jzr8Bw-oxjg^P=wat%#u1Mr<&o$6i0T*->w z>QJ3HE?S!c{#d?jNTc4zcnhG2@+aMwPw^2##fpyT7)n%nIu#*}@ z{`eIvKpYlQ<|i!#P7tj>#JOmFQk%raP0*@P&@5`cXyq)?_*6j*(NedGdgrE3<5#mI z8WYk~$sKZPUthxm3GU_PcZQP+k@_`uTjLKwf&)V}i>6rl#|mUEL1lK0{)}Y@IpEW| z!O~i-dgf`vguje(mn=}%4El5pi1%p+m$cvb*Dw7p%#(9riEchRJBSpVqXf_LdBzOYuJ@i^mJZp)z}BLn^Z zXryA>Rf{WO|AhDJysp=rY>XxVxruYR-T27;ZlRvf;s*F<6?|Eugt>5ko3}VAFeV_*m z^(oZePrA}}+U}*+4@i_@VG~qlfH_#T*wFp4!tS2O$1kBi)eY4Vjjtm^_? zk-WxgaoKT!Y^%$UA~7LANN^YJ3h`ff+=^PtbMrJ>=9QE7eXUH30#LrcKRIgwoMpm2 z>ETn{YmzGzv*SDIBfen%tz_8z8$Kx9gVAieO4GCoW-r=_qm)K{BECo%^Zo3BCgDkX zg49%m^mokA55{$jopIlV$_=PV?me>?hSCLdLOg%;yOC2p-qWtDDq`DzG-#vgv#WH6 zLPz8WR{%D}m_1H#xWm1e_P7$BisovTs;8_9p-^{#NR;fk-l>LaF9>*pYm-wh1tMJU zM+p?$ydM5CNLa@{rafy+Kc6K@*o{KyPYx9w6mt~U31%FC8s6op(sTr;OpJjuoKJ85U+c=@j?9%iX&) zs$Ucfe5GPGIG#EaFm=twiW^>RyhU~}y2d%|eZB7|aSLZ>Yj zo#u$RG_&F9W5)t%iVZsKR+j+1&;?6^pJNgg$YB@EAga{xuFKD`U$J9u^X zY1(-1X@6ea4!n^JD!acA7x%ddzTOZLW{dzcc%m>OSY~?y`S9-{~^30#5{I)Q@>SIclQ!}MB-Ok0h;U+m5KsiI&`E@8d0pNb z@&Iy&H{m_Oi}lGu*g<7^(s$R#2F?lZsAeq?VcBtR{+`a8^bcBO1>r6qDr_4U>4l~t zDEJbP@JJ}%kY__E<%R%~HSe@pi2%z1@0Swc*bUlb?}sD>K_jb z0Ej{P3*(-nUe{u^h&WhDF2PDv91su~Kps|Ef->69mCGDdf6M3O{_;$u7ZC<+()fYR zPMX1^ijHov8Bme%L$ErxgA}XrKdWhZK-U+Ta!s$m8#dg8xYN z1-ygDf2l)X@JG%)o-5m)^7P}~$t0wJ1_?>xeBLIW{(MDenM_J!h}F#XWCe0rV)hSm z5=s5JFFps688whAwzKzAV5xhmkWt61wT0Xk7l%H#@{BZA8XF&;wICs>z@;W@s}XJP zS4A&(JVicR?f>~l%{4l?6bv&}|GRM^Gpeqrs0iZ~m8)cbffN9f?_8+)G^I<2(GWQ~ zTekxIZ^ArW06>}5nQ3`|oSd$Jka5kFe z53Q`*n3Fz|&>N*b`(Us)h=w9DFol*st27XtXWemTps6W>%O#ia_s~u^RFE=;Fv!)- zt?1yOCSAECfw@om`F~_!>ONm}J~(G0uW*h2QM=DJ2!Z)Y(&{CWD1VTN^2|S=(WGOT z*=U%J_>-CHhUhT-xupYeF-IV@n{cb@g70q53Wy^^&VBMkCtfN1Z4A?u6+8RmeXZ6} zgOp2DhPW&06H@}5;*j`NA8z;N72s1UqNeC0^tdMUahq4|IFCEE4HvkMvn~HgjuBh` z_N5YfM7}IY*BVe9d3C{?FOZNZ+kW5gI4#FGXbB|4zalV{m~6yWzCYBHh)Yur0f=;V zXGi1{urCkT0Fg-zz>+k#@$*(SPpNQPr&cotT z(%>L=SzR#zq9lOb4Pf5C@PQ>^1DHuctwFq^EP?;cecF-?FlIMT*nPg$)xp!Bc<4Vt zC5b-#Q08;@)&8_q1Epd{aTzf5>Y5s07!5kxtWYU8!)C9C9`Vu4894n^dwGJFsu8fP zDheA8kY6DAgt=wTNCHo7bxFU&F8)u0zW01?|SJI|B%Z$jMbd?A8 zhKBY3NCy)LyROjXED#$>2fRbHWRwlB0*TL1JK+p!jSGWxiz6dnV~5d^nYp^S)ax1M zW8oqp<=RWIO|WHYkbP2Dad@D5Ev2EdB3!b}tghOw(3z6p7k}9fc4x0NL@WBoQAMet zt+JY$d;9wp5&2&Lr-Xi~Tgnv{O9cEvr=~QM zi*1TKs-8ioC(~YMqkPuPTcv-}x1}X~1d_KYq-E$m2Im_&4M2Xg-$rs@i?p7Ky{{LX z?Kkgbww*;MbOh*=|K>$ye9umFe!07A0a!bLPzn6V_eoJu6j(IU>VtKd<=Ee2POMZa z+u@BwNQJ?N|8I2%xtv?GN{}*}r~PsY%-tOD5oo@;qqwVS7B*_2ho z+SUuN@>(qd_!pPy7f7P-UP;P*-tjb2=L}z7I{Lr%zC0Yty?^+&MIj1hU!pA8$xgCm zY$bz?C^SW~WDQxeq-4opDj~}tBWp>a~fg ze!C{_nfWfCeZ6nHlryglXH3i<9XbBCSSLJB*llejrBo-ZbAN%=$Pk4)PYgxULBrXH zf_u(^K7x$9D6{*bWTL;NwdTOFhq8^uLuBjFu+o*!W(CqCo~2xaLt}FHZiYEXa}rG) zDJma;_g}V0cMd#$knby1lQp2OXO)C*9+QnzE_G*hoZsnze}~myzE?5PbyUZEx68?y z87>D0$@&$d8hz%Z{jGWS$O%%xEM2E)G9gFI;vy1po3*+m(`tnOdwM{8r(ZPWi&_I8 zJxywftG{6L<6RUkNl0u4OAfzZRkP%1_?UlB_MuC-uoTBYB?iQsv#-&k=7{^woT7t1 z00qj=4zCg78*uD6Zd?3PmgYK zlTy7YZF{4%l$Y^SGfq~_Vcgzzi^$UuIrkcL<9Jbg*YnqnpR;yGMlRKrR53=lTs!~P zZi#%mDATGfs~}TUc@e@}nJgakgsPV{IlOFcHRRQ@URPVfruA>JZw50zI}dT+cu+(% z!P-fow%^nzd(%5QL8zNw6h}vPV<(#A=5ZjOdm+UA!K3={+&3n3?GL@=k0hJhk1Q9z zCcvs(87UVIuY8}W>?wM)iU!yvDdG$Tpez_6^cL%4q7|1J8=q+!+WbyFi4WOoY>Vw- zM$K=nmt`_%+^tr~E zOC+g|y|zg$^e!J0EVK1ou zRbD+7pb&o4PO;2&TfL+6+H5`j?qJ<;Zm1L0CHoD`Rv-;UN-OjJR(#;-COPCV0H_ax z2iSl?Q=9L^?=nw8&*#|ki*KIM$ycbHlhbzl%sX%h=>iXi;V%^0tLB3?Z2w6SCX`)F|Z^|eDQ;xxlU4deeQC>x^ z>+;m2+FC2S9j)`ng0i3_I>?>3B*R$1jC$m%K8*hk4>U&JD&fvDWe&dBs!?7!E2`&u z29l1NZZqsxu0?P*n{D=rK!m{6-ku}l=naaAWen^cO8&*1?h ztQI6oj~yybD%lZ9c&!dm?Pe$(yQNQj{%p2$=XFrp;FN+oE&MdUtRG8iyJ<}Iuq7sb zSVV$iuzborUoN!?LA;4aW)|IJM}o{D%sGB+^UO2qX|UjOOPiYS5!!dVW8bYdv~_P@ z+m1+u%+!_=%6!;cEqvDVLhv8PqGT!aJBk?_Jq8ZCzE*J0{5|FFtp<)}Wgk((#C#9O z;NYNC$9(gnJb5ES#=yNoO-XSsgNDfqDSQGR^0*~O(L17AO$dRrl)Jf*u)aAgyiB@(;)%Z{Tt^M7}%R(SN?>PX{`)v_J- zk9x^VQj{a8-|9Rvgk3&{*nEP&M?G3M*?j0-11Pm3?PaY9V-o%qVc2p{3UAZ8J5I_+oR9p_Zf9M?FfFyR_K~ zTisu+g}+}>OQ1tK88{-(#zuKm7iCyIJAb3@eeHLSW^VOSPQ!{zjb@{xUa8odde=V9 z-<+PF7L4qX?QM4TEFtc2w*uC`z#%rMS*V@^VyaL!BGvO?U@pytyb< zdVcu_;nps+^`d;)v(9x0j1cip1br)^R_Gfkx?~9cfzBPV!K>Ql4jMI`3rC>_a^qQz zKhIFzse5+r*z*G~nq8+eCh)ca8Tj40;!9B=I-SB_9nT$9#nlmF@N}L+t250{tyu5d ziU)e|8zzG`k(HC%$1NSm_-1IxRb$GQ2kISD+%BE|MW5s)`-8?rr@+@OP!!lm03q@d!># zhM%UBZRkdnfF~c>R$|Ld37qRNEu!h9H+B|}-R(wNSyXs@VA&QN1+pr>?Y{HITtq3@2V?*t+tT(wTq zWAdZgP4RIu(Ql|R;6rz%R+75;cYpNT!8S!Qr0Jw7=>95@q0r?yI}j-6io?Al8P6hqD?A#iMyjoyjpo7r+tDJpA*K;+! zDBg+7Ve%28PGb4Emv&4@VSeA&Iy2V}%VT_eE`9+4;Gdg196L7l>5~ogHgvVMwLQN6 zj+#vTa5Vh5w1zu9O?HS8W%bg|4XtK9-%B^B@v`$|JP-t8j0;EIt^2FO)>i{%b})}D zzn4hg`Njwmk*+l#U+aBS!mJ%Wb|&azK#3RBkF4&O+Z=y?bksVZ@PSW00JuIQu{>C- z*}k}2y;u3-%i1Vr^K<-r26;-5?|0#U#V(j$gh-F#8Ag--iI-?T#(NQ zkberghr9%;dQNNqN@c}OU((Epho^F97~foC2Uf_H*riMpx-;@)=-%(bG{|@ByMjsY zCVxvtkR3B9g9GTzePE0pstnXRUfSal->uvW<&>fN(7i6ubXNn7c)3l^uZG`s*1lgH z)I^0RFR;njJJ6~L4^ei;9Mg;PL6CqP+Z;ECjhMcqfcH=#2bW<{?$aa^OBu?kM5m=f zmS_@%UwiZ@Wx+Od^2JEq{%14VovL)uTR^gI%xw9(l@YOMwzGD-@R7^nW$Aq93-l$` z+Z~4rV7^;Ch~Ed&TIos8+wJ#1LxrKKQntgzpRKS!#fW({xaX!s@`6pb*?>L=a$>2H zWYhO}(N%^Rwvye`X}}{GQGZLl@DM6@$xtNoOB)}etGWX-B%xoevDqB@3l7!umM)h{ z`}cJj+A|%%+GQ=o30YWOL-XiA-uYR55Kl#cyTOsbn&sHe$S`Fuci5V@&vlTChL}Pol*v!xj-(he;H_tj{=52jpp%0A!)RYjkL_qyaRaF%u{fRi4 zu1Ka+xVE5*$|u}POkx;oeXbrF?=lkWr-xy!t{R$*NaTe;=Cz$G>TDW#Jra=k<4CD88 zvfxEfZWmYKrh3#@5BWrukh(y?}(?z)>@*3t}4$Nz#ff~UrR3zppuEiJUjm<82P zjFn4?Y<+o8-wH?IO}NCn^&m)dyL#KHC1`g_w-AT_m4jZUT=6COTAcPDY}JWrX`SyY zzIs=YX7K1ExgbW`hI7SYgYF?gj`BtqCoB52B$cUg?5o2cW+97ZJQM4gQ~5z>9KY_)95l1)UK|6(1{)RK_^J&wDP`~J)}=nqo^E7b4F?jbf9`CBu_ea zQY-A!Glg&xmICb~8$nQDs4!T(Z&Uz2Je+J)U6a zvSID+5XZ*5@F>o4*|>#z3C!M(t5wn+zU`9cR-{kwK7xZ`4IMrAWRMKPlMsg;F}SR$ z-a@T1hqn$id@h0}vp6x!^sUOgtk@DOJ3QdFcXd@;U{=G2&k!mP&u-Yf-mD4n(k_|U z9c-KEfITfdOF+cA#P=X-sEQ@%zBEKzXWpMFjpz@-1C4-EdQ5BwBs+XJ^#pw06X!SR zd_C2FNvm}pVDfIw1!Jac{_z;(Xd(YknE@X)E>e-K^QHMtTgKbO`3~78>j|`I6 zBonc(T$vEW;%SiGM20)oIL=ih>}Vu`m}BPoK4b16ZEsS?&b~9<} z#YzIELBEZqGv`#b3NG-)Tw^RaHdSIw?iY(gua&QWsUwA-Ecz;y_$VaIsieMnwoiEB z!z9&ROT-M+eqwMD6m(_F8E*iay;e4R)RGCRoQF_zgJ&%3u=o^Jqp%NcTsCEc0W(kL zjUYrDd!k2KHA|XpmN>M%SH`m!$r&Ghp4l@Kb?(V$bYNp(B&@h!%;+n#WAf*G@fVy=vC&h3lqjk#bdLl#;g2ME(Ptt74XI ztQ9ufpaLTvsbIgv{GiPwt|?X(;a4iV^y-H4#WDI(2VhLZRTpyB;74tW-UB~|8I8Ih zmhK}GOW7E-;gbk)iTLFnc{ilt9G^|vC4nmbw;FG3pd|Cz{mf1X6T+MawP#8h2Z6_1 zyh<;YMSBA6V{A%^=jAs`W6o$4at)u-u74CJrEEEh%PGNnsG+^L!6kl z2(V!3BU}{jPFhgr1(}T=a|gNS3l2WjWO$JdleSpz_V=!2M9A$Ot@AtJPvKg)vcB~| z)NDi~=(ngL!=1`$qbSO-f#~G`02D?x4V(!EZ+Rh{?Ki%>T8Zu#H2@3J8Tljx>M$tE z?)ECev4PXd*6l?ne;A4%b)${A&4k<2?grfj5h?7k*{at04@b5Vst7j;XDH!i8CFd- zcQ`hX^AlGpVndT2c2b@-T4min`9(!qNofV1?0{)xH|~AG&btE%JwE(Mmdw}sdvoNP z2iHe?+l!nJS&1{5Bi<+CAwuyA|N2`cT7t4F1X}W7A_xVeM0dx)?aFR?q+w&FD`!wK zRS8zFX^@vYz2eCV4noZ+Dl>4jW%jhF**Gna(IfDj=3Qx)1YPel0;j`}^SPKKZY+CY zi;p;VKTEucMtaZvk`Tue`9(?_r$3?pxo*g>)91(OMvpE5Jq{|Kl>bGJ_T34!I_yY; z#p>DoB4-P$)89(zsAOt40HlOgh)B#j7DNFo_x)$iQuPN$YuDWkj7P9S2EIz-;|>2< zE>LvCSA5+4xmu*y@<+})?0qp1EKh?xsKC8v5BAOZoM5@la4yzoO1s6YLJNQv#%ZTqb1hcTJH1Buy0Uu?By}a9(GRpuN)hfM|payj093uR7;d| zLVkw|i?-&qnM%68YUeuFEO9uipJxNK&Wh!U*&DAR)kI7W_>c*Dt${=4Zm&OQ(MJm* z&Q4tECri`@X?4R#id!^Fft&;Plm=O2 zTT=*)qELdNie_+O{I0?H7UI~Ae&!9Bbt%?a9d5++ZIN5t_YvKj!qm0L`*U4A#-?_m zln+^1w_D=-sT_Mg_cb?HU#l-IT|^$Ff|bu%+)gpLjx9RiKrvpKSz3aob<~lG)yDcl z*DA(|DuE?3p_RM0Z$gLScN@EX^wtoSJ2=|z_7;j+9?)lia?A3>{F+pv5XOAnMH$EZ z?hwsHt^{P5*&c-##SlQ&ro8Xmx~J5(iEgoQRvp;=i@^{#SMyV_>wAmvB`t+3^&hrF z(-~P|uGv*-)8Kk}^;nX%{hXzPJG!5@G)%y{w{hKZeTB1%pcUum8&D9GPW-gVp^Pe9 zy7`d*dF62hgk@?uRjgZ7U`kfiCR4>WJ52hWuZYCr+qaSPeNv|{dwBiMnF0^5x(psn zUgKt|XV^XCU$Ny7+wM?o(Rx_;`k=(+S0~Efv_w0COaX>95A)=;a*yoS3KudY#eIl9 zQfKKfxqlNK57>F$zN$4P3b*qBm0;%!071=uiVACndPj8-B=cdQ#ZvqDyy&`2vAaWR zKBTUgPbn_$(0q;z^NZ_A0P;s7lbJBCe$f&hC}-g(jpCysX9f0*@@@I zQ4d;VxCuxGqcZ{y3xkzPL6!rQ>7aXp%8|xm4y9oX2=ZMYPJ5aO2fk2`V06JnLLe21 zIO2tYpyJMTqsh z%QyCY%&KdPY6;N`OszRkw7H$y^ z^fLln$r~U0U^ea1c?v32uD$Bt;G(TjAYIv&#@KBr_o7PAAuyC1ilt(pJID8%saOgqm!pLW3jO`bAMc07&18s0S7Qr*}O%TKBf|Vhgh0Kzfq2* zjj&>mqy-I+keR4+g}H%gmrL0UaQ52ZY==>$gyB@*gbROh`CwQ)FX}o@RzrIWY{j>+ zm7)=|dq_ohs&QPc4zNukH@pjj_ZKGn*X1y0bOY4K5y#7L3~^yJSEC0Fa$bZAfvywP z3ASd#Bqr@n2%94f*M0onImw1ZG*a1OCuBH_!91B2wm6AF38HV@66pEn-`NT_`U{uo zJ?1vggvY{c4TeJUBefp72Ie3X+#*%v>mURWycC7KVQknd$rBGDK!w{=Xd~!O?_RyD zE00dobErP21_Y$qHGX-~@gv;>REH=+bmLpsO-x9Cfb96#bgtQtO70Vog+{*UL3yI7 z!ZYvAq&{Figlh3@CGJ{3Gl3lsCj2Q0KaYG+xT|vN{F{YcGh9TIEjgJ{AUMWU+;g3A z3GUMN5+1je8A$TtpeEZGX6!Yj0M&F<0z8Fm_Ab&W4Or-neGeS5Sc0PI1|z`Y|3C+L z_g7Ug922Pk`JS4QJWeFSrTL~H;wWJZOl%%3U--<}r}#K9rYF_oV>$`(V5&;p(~y|l zYhLh- zd^q<__LYIUc5b+HOdx@z0|of4a4QzgaN4Q%aee;cvDqz&ZHlj?Cs*WQKV!Ic8+?d6 zVr?bXgYOi?aP7OBl2#A8K=1d>$Jv8_V2z1IY}L^IlQPe}V{RsVg=!$&GB11Rk%P~l zRDAZ9Fud@F4*7BfguY>$(m82WLCV8|ifX{i=4wHj;iEjF9EN_+>5$lXI; zDO%(NqbofPa@{}sPt;&M{I6KgHGSYPGxRBUyRoA4 z1;o^7uSxTYrB)jesm%wXNMYZ+jJi8R4DB7)Ie}ILi9~ESdQal<<#mt(s>?N;2JIDD z1uLTF)%Bn55*OU7YbTn7+toGS6})A}^j7<{SP*It<)jSQQG&#@dK%^?L>nks5PiqgQ2S~ zhX7=Gx+ZD=572#|*<@P&E3@{$V*J0!!T-PfRV)0zjg7VSuamlf0z~)Pqs2`esZgmw z^r>FcC8}q~;sy>hHwY&pPXJ?g!WeXV!!=;j2ob8M^MCIbnNmU?zc0@6SBFy~C_@W_ zQoR$AhfV3|IT0o%CZw`d1VjDg=YZS-Vs3~&AcL|nlJju#bUTIh^^-mCakeCt;`y6A zyW!FW!;c;@nT#V&+t^v#NX#oVo{F3C{F-qd^x?5V0QW1SBTdTv=*lh1`*^JP zJw1kfK8#)u7qvimSoC1$5dC=H=WN))W9|F>06o%M3^!~Q3$ z)cnIL9#~KR|LH8ezrcea(9Qa9XYuy(_V=bP_20t8|Ce>dfdYSr$;rh9dln0b^7`-L z`s<0D{$V95j=h~cv1k8-6W#oWb-aDNPWxbeeg88Y_58z1zJ5-A{{Q1T)Ux)UgBf(= z-*M#T;dC17E2rn?=i%h-`v-VGbN-_MzP zDK&4Y2Y&%G|H}HY@D4D(6IEUPebx{zAyE2+76`FZCINH_U!`aix?X0hy-_KuVy**F=egEk`6}3k2y!gNigde|*cz4*} zFX$}xFT4MQ_JiQF>nCBtbEr@=|1t~i{tbXLd3pL_Jva38&kcVb8-HX!J{6vWPJQkB z%S5q@pikUf{QQAoA# zL;VOsef@O{W{C3si!GE5e&0e}Ur}E{QB_stfc!o+b$ufx)nB*x3I4A-kZPL#99o97 Z|7@rZn=)*oevJeEQB~)Z5ik_;e*kU>x2FIA literal 0 HcmV?d00001 diff --git a/docs/penta-pod calibration.pdf b/docs/penta-pod calibration.pdf new file mode 100644 index 0000000000000000000000000000000000000000..5ee152b51dafbd90cff1a2accb2ad49d75a97ab2 GIT binary patch literal 87116 zcmeFYbzB|E);79vcMb0D?gV#tcXxM!1PJc#u1Ro*;O_1OcXxt(B$GKabKdiv``&-= z?>5cuCC^$_yLR`gs#Vpb^1`CDjC5?!q}>JGt=;wA+0aY`3RrM-u}ZX!ndnHJRvT4%oImwS8@U?bvz} z7)V%YGN?)~YD9em5xG?xIh#q{+cSC*MLpL|YevleSc@?4Xm90X!0vjtoKYk$%~+oZ zyS}|?mVOFviry>Ei>Fz8IN0;^qbJ8I{1`$FlmX5r&ghBV)eAKE#7et2kEZ(5WFGEG zZRAkuygj>H=~oP|IOgj&T`V{(Ns)Yk$iC)U&Vo@~8#(r29^EcrY{iXd-=%Cs?=d z0C7CgG5DCeZU9>nz3kYSd|9QLq>4qFmt6>~rT!Y4t4+Tt*{*G) zPJlD%TE+Qk(ds6sLm_zy5rJ};twBe#6<=RUDnuBY!Kbr2YCx*h$q+g=yN!H#red$5dAuQazt+Wj$VN^y8@2>iHaW zitF+urQfk3_U)MPeF@_TiPDike=JtnfTnBXS``yyipy~tSotuEkY9tXKjfAz;n!(X zSS}Y@9m_VIAgn=AY{KWdQ5(ZQg#%ah88NunX%4U~k$}P|tQOLpR;Phzw-z%}z+?I)>yu!bhc-jgp63O< z^_Q@c5m-F$Wz9J#TBqIA%^DVKNN-8_kM3qmomzqYxDnX*cy~9C?!*+xQAQ4IXgeKw z;PH9P7`&V=I}1}eKft*1-R$R(7AWH8CU}>@TLsY_@ssf3L}u|M0=B(2Jn#<9*B5w) ztg^|@PDhjk-9~%Lh_z)c;ku9PiW10>GyPj(k2ZHDlvq3u;P{8axEviucqls)WC=+)&6ElrG^>6KgzoqzHYHU?%U^lBEyZ;^Fa2DG@;s0RW);oWHF9GX=y5 zJC{QqT=Ji_|CAylo!JShm;F=tiv#z*f-9QFYsuHrEjy`d@daP~{tpzB5j*&Oejvv` zgnuxw>(S`nO!wr{wmFeK-%(rg9Q$VBI9#c;$#DsPCDfXA`0~i-^{#mz#B|~>YoK(k z)KOZvy1yiUQ78sq?i}%j`p(g4h9@eD3)534@v<^O#)Nff>(8!YTrH(5FIzt-b+;er zi_pFTWbq#VWvh`erx}yJ|1bXU1pFTLq~g^oUInwGxA5K3LWu6V1gnKX(Yu*GmsK`A zIj3+sX)d__MLNU&nP4j(zD z?EPZ1Up83O&$yT_(gtN~B$5?pq@nB;j>qt4&EBpc9*5zFz_;cw6P=9c4Qv!&jdR*c zWmpIR&R%OulTO~z`AhGb#+0h!;4HjjJ4M!aiNLb^Ie;ZC+vzrvhwd-Ufl4L z`Of5E7fp^Gw(@W7YWE&+T^C)c6h>MsCWez-b_4oU1tN}(IEF=I2k{)X$C&F8G3Twf zn#dTx=q~MXoJ`j9jC<9x_PaS{eqoi1&L96)53k;L_*_*c!lpjnxDzpdv)JcQO_q1G z`~DxbV%%%8G^vsHNceQItC-tOIlE?JpoM2O`8jPYKqfC*_lPrZSZ4{@ zXmzq^yoR86Ktm}G%1w2cZgJKw-`gW8Wm(UDij!rG@1ZB%z^dMv8GUK1#iwpsyX|Ji z45Y(-4DTV;aNU@*xL_5e=(DLF*BCS2VutD0)-mSD*`@I4jK5b3B6V_l;za6toZ~v( z=-a5-)ZWO`+*;)BIB$c`t~YK=H1p=kf>Aa(uUhIA+kWeKCTUyia0nm!BJ%B{9ZYVr zjoU0U8tu#&(dV)sxoU-;31za@&AVp&e9a88HAjuTiFbsA%^_Dv93OP(`ss`6@sZ<%eS&zJSj19h@{N~f2O z(+Fy*Gqc?22g}h8^~{k@8hyH3I$4Kb!B$;`cYEjh9^2{KR@>(Hbna6wZufiZ!ECNz z$2@)Zx2*A^JX*}~a|-JfPRh?RJT&)c-{Eckt~^G?bkq3r2kZTi$tzlq)5P(SGsAQr zl~xs#vN7uFX+A=eB4O*=vq%lAF$5Qgb^$gAguDh`D^`5rHSz69|&RQkJLw4*DHcGV2kI~eJd28K@t1?QKgE(;(o|97O;b!<%1M6zV zO35?*w)KZvZ{LV*jQhsc3ma2^n&S=!cFU$c^@?|iVZB9E)3uwM$fDrPp%_6T!&g{m z#0-DDf4^>wJ!{-9vl_YwWy!v?8uO2@gHC_tshlkbiK~}U_35l#&RBZy{V&bC?va8e z^rra9tfFw+ktAk?YaS=le1rb0$JX?VlbiCQ`%}z2%o4kbG%eqn(MPVAW~!tzt5i+# zy5#XY!!UaLI#{fM;?I*`8yaPtvTZSB*o>A%S|c5H2X5wgZ;A4N>-tnA_k2dG^NB!~D-Z7>(GOKB7S~u6IRf*hK%YPH>58uPu zBIZ754=3d;wGIg-zV@(aqI1w$5|Q2Et*bMvsmn$o$Q<_j<$yV2{uXwN!878ZJ-$i5 zavLyqQ8$=vIm)I+w!8l2czf5G5hdS&+nbUlnXS)`PZe)-40Kuv<3jkS^}!Vv+Ozj& z@`1wxzuwjfhweoE!~HL}nlW>d4(a>QNrwlO`sv$l9qSrNlsxlDC+$VA zfbvb5FDB2FS>r%NDeQB<>;Qm4ttGa3b01=vy2@=qH!1+Y^cj2BXF>JW^ZW;ohxhZO z+tu4M^z*>5&%?)003ycxb=L6`j?*=8?S6s_^-uT z&<(ZMh!=Htcv8BNT*Q@2EW%DSw@heLYx9RNC4u2Jx4FT78w zR0Wre#!zoXM1JW`B5*_&(6BslS(A5;}^!J-qZONAhKh% zsCxUvXZH09*@B}zK6a`7fy3{?yoUa;vE`%LbdWzPIJ@AYUQu_88!M;K5w;qbiyFHVC(vjLrE$zD9RRxW% zAEVCe(r;Y+H{kaLtjQ=o>j%IxvoEc#JUiW*?CSj=8X(72yk3OaBkfU&`7Fe5MX zYqpNxR&dQ3S#@eYu_|jkuYjBliJ~3Xd!OO6xM0uUfIlzvHW61J%#FAn8bVwXkG>^? zmi_T-0$GoD+KUM0~i&e^5weMkXJa{F?wj30$ z>3DUsv5t0ikPHTY*}jGN;*kS2SEew#f+ihZ)5BK)`##TE-o7u_yZ+yZ-xuryvZiDR z?psnRXIGJ8%eL_G#Nfm8x8W`&>fBLWw>AI(AI)`*S2U3S7=dRt`#^0AQAx}3=Y8wU zdH3B#6^wia=OqZY@+mv-$~QjmeooZE?;oXrR>|c}4dgsdXHM>%_!nGAd0kd6A_4%w zx3wK_Ko}R&NsB3^x%~a))>nWiRBJm}G~RCqFf+D7`zK-e!TA@IX08fv?S9X{^ z8&ADS8K=Lqzu2bfCKtGb|CIP|57Ym!`6U>`^O{|jd5CTX=l1^MI`wv+w=vRZ|7Yw! zr69#5idX!0aE?!_UaWS$Dsw0vIsZibXO4?mfS>&~X4+_P-?=F{oBlX-<$pEb!l;<7 z8+-mlyyD>T%uDxT(3m~+p9}b>6ezRSs9Gn-DwRgmA&~cwMW=)R>00IF5 z2M2yj3;Z$p{yEb|0!2hdVPrxjAY^_o55_>GPb>h=B1n?+Hrs}LLji#SKikA|34_X) z+Q28@nr}K6RCA#0IlTf*tzZViI1-WqHhxfJ>N;v6yW~vY%2NepRv^?~&#xGevO#d# zn+8MF8Q9+tsMy~lWkZv-Z*oWnB~j%XIc}_>3(dn{A7Kah#OH6&s$74rj%oDAq@&|o zOO#)%qA+-`z*>vJi=@1}!PKilf*D_qpJ$UX%~@5<)A}Qwh83wd6i5Wy12-?WF(3}d zQgu`4+$|F~bzEbzE93I&G|$v%p{GyZ7AqsEBBok!5QapFh6YIUofx&YGIMXr95>?S zB1lG+7;>DN)R}dazD;7H<0qAQn6juc(@jG!hq}>@gZz$H02zl4Q7xxIMT zxms3cC%R@EuUS^ETc;GEKyW^rhHkFmZ-@u$z@-#Sp|tDt0Mj9=Y)n;_C`gnx<^V^H3a??G*sX$1l8d>r4nI=Swj7+CUf4dnEUe6{{*CMezoMIFuk-%}lC>iov-(94@ zC&`A!=mBxY!b3oMc@Hh>$ZUgoyQl2uk>Sav$-cRW zOSgdmCz6Uf%ojUnyzfDI?;9J?vQd)HIgR_&Aa}Y4 zrp?O9WE>zk{9XZZ#^z7Q2Kblg`7eUo`~%vVFM{@iSEp2Ru}R80VOJ&7F?k_`69kp3 zB0&Z+IW*3e{@hOd3(sKHO{GaqD4#2gU8CdrGN}u8oc6=Z2XNi)JR0+YlQRJax|U@n zgKr43I_dPF$zzQ`7h-Ih4C4MRjk zSfuZJNx4*%Kj@zP)koHLa;I#`J>?r673f@boa&Wo-A1=BSR!3*_R-qd$)G!(Xq|MB zbWkN4*t$re7r}DEZ&?8#Nh&?EvWdb)1Uuxn->C{s>qta%%@$gA2OXHRcOy~$&PSf8 zNm|2N9jk=z6>y^IHJGj>Co6%5x`CJ5>|@YtsDmLw?!YeCAzxh?h4g8m>wDM+4w7F` zaI$g{R|reRHYp6I%5`-D3fm-{?@tGJCAUQ@c0O~FrTIl@K?cf?m{V6V*EC}k8Y+1N zgB0m?aGdrZ_tO+=80|yn%xFR?;4wC-8Qz*hRbM?M8xzw!X#MU^MVUrGa|OCA;)PX) zs;uFg2wxv`qrf!nFqBwcPZf<6hBlZ9C#3Qy96If3`{Ig_@G58IC}d7axPT})s`Y1W zA~rKnLwj|Z`>+veR@0yqbi!?cIxrR5&#~hf=$_*mN4#ce89Ny}X*(%9k;6#pVP8q| zaxBn8Tfa`qRr7wA7psVZvl?R-5jICl*{m&fRyr_TJ38^%W|5grSy}d1PgE0`G*DJn zE@Q0CH#5+t5FJveX(h%ED73cVMkTy=ou19@X;d4V5 z=2QPx=Q;jFIK-((qOwpGnMcbisxM*T&|S7UqGV{yn)4!CLd~y$Bvk3ejaev2jV~Hs zLTw__IstKDXrDQ_1VnjbLnVC-Y_upGHnSVzl64K&IbXav*_ z%X-4U)VcxpZ1*)bbVvKV0;s6LGUo7cYMU-Ph$F^@PcWXvpNM}nra|C{s2lb?mLhDa za6VaA8+fFZGgOE^R)~wEGgN_nqA}pyYzpnim{hDvOsi34C?6MLsEDXBv`Y8u=83Hd zqvm4z=08lvPKPwGSO8huaAMo=6z-s5En4Z`T(sD&JQvf8L}$oF?(D!3dD-5;*tm*n zNJhz4dfVADQr4$xIjY{fNn`w%IywL5?3O> z9>ZwbtPCsfbnKSiK&kC_9|-Tn%$&oSxVgNeVy+}BT6B+r#(L~xuQ4^r*1dVb@0J0zbAvLfp7m{PMNY)R@mi$Mvxz!Uvd>|=?!`N zIcO(OmaqFkcJz9IliZ|kSvC|}&Nne@7HZUs?HN`ZAxIr6r%m{v5aZbo%a zUyD>91XEN%6i1^EpR8IRuOH^G`jm>?R+Ed{iT?ss)%^|!_;=W7Fx#S z=Uu)9(EsYny5!R)5$PYH&Z`E%Njekqy={vCc)})^OKd9OCE`5ga zzEz7=zXIadjaGk;BA^DKrhLFI(;1J+oz~CT1$D2Qgkf2Cl$l!>C42%XSL`?4m6dX{Q z1?Bx?(Fll16j_9Xm2#^(&-MK-evK&KMxOjYuYj?8a%JH)I>CC73$jt{M*Ngf`2h$G zmHBqXNTrxE$Ed<97GLeVPfOZ6YKpqY{k?qh7~(S|mInao_)X}jeA4Iu z@E^WfVQ;JC&|;>J9!(;w4H|-<+^O6a7gexBO_erQU~t%C*B#h>^V?Wal{m;E!)T-5 z+cb9@TI~*;q1}6nZ;YH%Nxpkm*YbhbV&?;Rt`O5LRBV2VJGtDoj1A_UY zSP1j1h=A=twGH4ttk?ch$P@fwz1`5Ek+T=cMnpJ`jl#$~x&~}Uoz=L-ae3CDQ8}jV ztH%;j@KLU8gy!%<&ZTHD8W@g4deCG=kh3k1d<5u%-S>1!9A?x7V!PmyAL20_Weri0 zJsx-uI+*s&gjl{C?rjGoJkKN1IS6Hp7ht2Wsn- z5O78Kwax8i%r!JqDZ>4rB^If{;vr$lQx!K^CLP=srJ_D0j5p_eEh#Mn+B02MF`YTP z=A9ZQZcP>;yjK&TztA0JztA0g`|stCyL}g5xrj$&U3z{8`Q9wR1$1;1qq<21Ce8XI za&{0`=CQ3A5lqqWAbS~24N>+NRxdE8F9$zd(MU-Y-8E$1h3*9Dci-vBsQcGZ|A^Pr zwoVN|uZ0P^=TDF6g18cbG7C@MV0cKp*T$LOsC|(-fBdl77My*bD+ahnwYJi}_1{bb zmrrA(4AGFJ>s6edLKOyfJ~SAB?K@^0!+Q0;KI5OmW;uau{!5Q3YREx^Vk1 zeSGhr!s6I2xLZL6(ap&OW32{*%2x2fF}F*g*eI|u{9HP^45jhKDk!tvd=zo>dpeD6 z?1OfGY!mp*qJ}M%;CyE2R#}M`q9^^Sr7qp2bt%6SJz6*s&ghr_*g zBxrX4%TzINikr=G#AOlejSA}m5u_Q#fSQ(OVH(GtA z6pz?u4yqmk&oaOMTW=7#h3b#5CCa{3c%;sLG#k#5S0Wun7nJD|v-EHxITuhfl`Y{4 z-5Wee-4KBZ*L0yxnVl-jMJ^4VY)>;L?P98YBXy^HHWN_lY36o(rMpz096Ri8&(z|%oni^dVp#ZZly^7Q8{rRpfX zYcZwo34jBQ)i`zVIhsOFb zs{Tl1y;{}Na>`V*F!~C6gnzBXXW0im4!-q+iqz>e2UV&spwwbiIyW!?4)&d3$w`Hx zD+GGv9N28bj7R;gZk;_U? zzPb7TNcKGJmz_h<8_qW>CA^*uYwkX1=~$0z%eb*1W>yICz}=zlCIc;FYnODGyij35 zHx@xl!lz)xotX&G0zv!(F;wo#4+ei+t*7tueD33XIEIQ8~8VBVP8c7x0 zBX%tMFFRYwPlr9OQxf|{TdU^FX+?}9mSt=~L#=C0t&{ybpNDthKU0`4WFNIo)>sZZ z&T7)j5Ns>2;m*U@S`IwBs9_7LD722P893FaeU9TfmhIn%=zR&t>ZL5-v?6NjTr+>D z^YU#j1KV)lE;>JL#CB3+KPpFLi=dR*b~sZftn>bG*R7lxP<-0VvpgF=tV(7*muG9Y zRvDkvOgygCNR@SzZ}Y5yJFH4~gi!3&J*L?h&G@B4qsQsA(UgSY@~Hk!!Kl{JHA+t< zQjJLsyzA($*(k{s&q&9;HX7%}xZ5nC@vx`2IL3*e2}fD8;)4aY!t$(#1#+WVu|7PYyml~23|I^b+nmr(I%Sp@sRJK#ZHNgp8Qu#p%PXJ~5D5|+D1r&;JNW(T)`9=% z*0bK_+ZIBXL?@6M)$(o8jC^!bL5q&bm*1v>Ha?|-?#_?L!=vMEI)$}EQejT!{!}d9 z*tG={HTd-sjpm8}y6$%U1`2@;^v(hGY7|wnIcNozE5Hf=U#29lx?)C6)wsZiq^G?dFG?~WHF9Ywglg3KfXvPite zwp$Q3hbCQPGBTJcrzt0wpvvrQSM#Q})u#;j6j9E*L~BqTNU3Wdf} zSdcEHx)ytm2w4p6Nt+1^FkB@AuU4|@53!0pbIeIdr?{WH8np!+8g?A&Oj%7?IgjnD zWPyr?V=pU0NP7_N$%fX$=8-~w1R!&eWf8h4)Ic^w4Wtt*w&y?UDLm6$o!6|q{bkkY z*63Z<;9h3f0&}pkE03y$Q&StcI17TLIW?-tpWI86giqV6lfP z6UOd21~iwhr02Z?Y{2k#h#ae{t9rh#xUcY3%+s75u*siF^0skxTF?hkwh9$mRTOzs z8tUT&&{h{2=}y}hnz35xPnsx<4*D&EbBSqrN zPwmf_%&ZuM%~RCXXU^rq9gMo>yEH0_=zJ)$$)S+F-Jq~}qNvWDW?Z2W$tRC4gKL?2 zuVn7K)ON3Qy@O$Zse~=bRmWIce?&uw8;0|EgMD7Kd^_uzq6Ehk603mCgZJ5LWnP_T zzJ!F%C(KT}mRp%XpIy_Z4llPW!-Whz<|8Lzv0{ULSNe?1N#X8Q5WiyKw;?rxJa&Cv z$+LOr5AtNUW4p45F4S(Yl#!dblB?i|p8o80Ji&0YLJg&woFGB(UbtPTU15oCfbFcv z$#C8^i8Pd|)8nCvDa=${pGUjPoS5yr>*5_u7gID%?t8B%Mc-8vbitAALiJ38-AHy@ z$CuhgtK@uI=0of^%U)N0eIBBF`ayhiY_7(<3;tA3dJEr*g|l6$)EGLAiL<4}cRE57 z!I8@de)80I9+C~gDc+$gTmO!;O(=-1^V9{ev@71MX#v$R;$FsFzvjdB&xr!_Tdo-h z6cX%b4EbZ9*IN)lB4k8FCLm&XFRuW?q;KFrETHHgn;U?_EU0AoXTBMnANZgV%xlKV zfaCx!L`erhEz-3f#-Q@h9HRI_YP^T4V#UZ{X3Uu9t9<_^N@^pw3-|qJ?iZg~UCffP z8d6d&(t=L@PnNf`8)0qFHzkyGDnkW%4f075FN7~C&&BqsZqMX#R~4;a77$#A&63g zacKO*P6S0HBqSWas8EqL1?(y*DN(Qafn$om2C_)O9%SS?2GPWG7!guo7AcR)hU&|S zx`0p&j&$%krV%Nj!a`9h0Ou4G`t#fmjWX{c4S`8W4ksj(vT=C4qf}sRj!R^ouzWX3 zN=p6acMw`v=@oa5@}$Zn959OH31!Hp~wjyXa}T+zlWTG>Z5(R7YuNy{-}%`gVI`t z9~>f^f=NK`3cA5^H%EfNH{DIct1HfbTo`Q2SI9b=!XGG( zyRw=40mrbrjOR#idBmM~5Ry3*+Hqzxxb|ouB=LcoJ7E{hwOxca?}q^vp3NMWc%|cR zHw1=3lYIO9f$*~dOHorYQyO_bhY2io9`@H;_D6*$SaI@1){&+FOTL-A>0oVjFlK*1 zo>gXmbLxW8EIJ%oMD0a7Wx6cT;lr1?PA=(VCV1`Pw6r3NPVU@Z9y!Pbdj#Fw=${Xx zS-rT%qgdV&ZoJ_q@(a!A9&#os=4A?+NZ~zfW6&2$`$g`LqXOUB)iq3fEFl;yJ|NDX zoTeEC512JaIYfndnU+(oFg}Ha8J}eu!13%-vpQrQO(Q*^Uh2ug?rBIL?9p7gWDZ@Q zv0hSLc%ozSPLngxfR1H3M(>z8ehE9VRhIb%mC;c>mc%sil=#y33Xr^btfjQ^*#!$o zo$lf|M_lz@(t-=d7GPlxg5xoIizjCd4b=2U5j7QJxF3wFIAvRqY_^I;Ims7hQG^H`Uu)0)3Nv&&&LR&z!O81;4pk?u1}bIyE7=h^^_98 zLHG)IH)AZe-Aj)xzPjy*^`J-k3LrJ=QtZv5;lCq{tWVmxb4T-A2wE||3T#EZJ%Mu< zUH2zaXqT3p?2M)zK10pRMR|a3CT6D(aIs(6I#osz0FCin^};M%L{5g@MDTtE0QJbR zYQ2O8toUp&%NtV=!iNe%3&)NcCdR_R7G!x;7L(QnHTiZVB!sq<)FiK-}V!7B%+!m9wQAlpsXtbf%Q2g!K_XbGC9x79%wJCcO>3l=K+6KVn3;Ten( zBePJLKy64Zu2d)}Fg*z8>lkWy0~LD%mNcI%*4s(&r3`eIu^Cx~Q_F;%zyDx_eq7PKeham~0`$AB`lYg*gZo3~ntqCm* zV_ZGVzttS|s?aC68SS?glCW}u=+bBJ8 zbhe!KN-ij@B9D->;cbYsw*-19$KhlJ69@Btt<#`WM zXH%ps6wY_(F?lODG3|K9$TczZ7+6<@)k9AT@UU`ZI;gOP#u;cpz7Hm*Y5YhSvm)dQ zO0|`CO-?evkS4h~1r%)7L>wuFjMd`LPo#xmFN>2m;nT}MF<24Z1t+vTM^@Itj6GiY zVPTkh$J7OgaqWXX^-RghjWvJg=zVXMg9x6MrhhAw z2!SlwWNz*aDY_NgFB~QOq0t~$8=82IEe0m5psu`;1@&P) zd5WnB#PbAUf9Vn&�nv36gCMe0LRoq)50b@}S1)k^`)-#AF&{0%h&4U44Ac=p7jq z%5aOEN*Sn;>e+D*g7+2CwL(s#AI~e-wE2|!29Cvy{0TS3!Xd_3YDyae=t(EASj_xC zHGo+j%ghLQ>O(ohvL+;;R70+enP(F-wxAR8t|B39W5->XA`qCF6pnpIurZg5#S`<- zz5*T91NN=rR!`%f{N5Oi4S5dM_<5mD&{JJ}MGrNAh*%IC%aFJlOXO4690qh`+!ld& zD(yHSoAme4BPa=23Bh^+Mk2-tH1JZQk{>1BV41gU-wmjO5YF+>!E(LWUFBDAW^eVx<`|D3Q*KR{EUK^@D#l`F>4VmLNT*7 zCzO*|(qHF*EK_NbOLhdYu(kxbqg@^mb8{^mftEo-Ajv}@Wl+K-{SKMD>YaWtUvcCN zHZuQ(_*@NUu*$Y&oX=GH&9zfaHJb4 zhv%xd(RLCq>a+q?F9(J(n|N=!(Bc(M*YTFfLKTs^)SU2Rt_{>` zM0^)rrWIG71mW19H^Utz8zD1@`|-p)7!MAGq!vrNpplwI{JWizI@JPIm}pTH&|AP5N%M zh$N!mA^uj1aOg~=p`sSXliRW2)T@ZdQ~9DFQOxggRKRL0)gR4*2haR>)^LeTzK}p^ zCMb(leRqOfbp2*8#8I`u*(KK)07;wd?o$!H!dGg`==$6bq7YPpc9~2#!qIpREEa1k z2znwMttY7!N3j?vg%SpuX)KzY5S-Q=6}d$j%X523YLP|=9lug?eXBBb{`rh{-q0yP z!gNq9(D`H_I)x-dhM}*sMq4Qt^DxghFRr_baKchZ2Z^5xxsC|M@{={WC8_7GDgk*C zAqzH%33)<_eDdAk)|$Nyoho%19Z)CL{Xn~+yM(U?y-Kblb%(j%`MPwxxr*5pEO?Aw ziU+gJ8peHBj(3DwpEOOS&CEhfnsNJ{Y{kJ`o^GDa$8@O2&}pa|`2<3BiyfLBnPM@p zs$diz5PpC2_Z4gS(`r}{5kzEp#@3IbETlBfLUyVwyz36fwXF~tFoE`5Uh32vvTE+9 zSkoP6ah}L4!ctZ0ofK8}Ut_AAzw%&K&@TA;uHp#U>6~*}F0I_+>$-j=wu3MfohMou zEE2C9maIXZNE6p+jx@}V8u(JJ&_Q)QpU^vVcPHpV^bq*G{5_j{};*Hs9i@ zVvMQUY?>SEJ)*37L(O;s86uV$*{=GQSQ8DRm=o@7gkwRlI_IsyPx)9-%7ar|@r71` zLPvAp*&>h6(<7IO`l77(s%CUc(zf^G(i99|$~`rtD)sEdf5Zu-C%acXnrHfSS}=GoXs30283QhXUn zN2&_88L>yX4B91e=Nx?szp zGenb#f6kJqwgWCrelqqiH+Eh6lQSgV4ZX@cMxcEIMlc+J$%lTJi%aW@ z1E&%MN1wN<0OOA? zLA$4ayQw-+!_tCp5Xs{iI3{4S%;GaPZ$+$hsdLos&Kg_pOKPlSwuq54l`=`0;2@hf zCvs>0Bd_{oT15)K9Nqkxw6bWqp@7wUOAo1v`m=#x61VeZ7Dla%%#;0 z6Df|b%(Ha1_~R=ep*O@f_2wI?g>+&xto!Cu@~v@2BwYXYSG$ZveA52gr^KUy*{RqK zkq0UpjZn>xISt^Yq#3V(>z%j6O3Bdg1-aBZeL7}WB%B??LgN5>`&M)z{NP|RTRtB0NdO*Ph%wYR)?opTAc%R z#*auzf7Rg^@{PUdqKD1;)LwIV+3@WN)&do+2yG2o>QC)2JmYY5^?XKsURKH8^{Sa= z^RctY&H9yZuU!fL-^(T3LAD2hjT@*DGUzpM`Y{}RMS>$TvyIo<1=jlaa=!x$!7_BS zQ2$UlC@m@C4C`w&#{Ikv1M3*So}9_HW%t|Xd4!wyR&?w56aM<@+rosITlP1qT(w7Z z8_8W+dX7nfwddbX2LkPWSJ&DI|4|MPWfM|H<1+(6INW*G_6{ljzY`25$+=(+K>-vwD_yb%zWnSZdC zm2=Z?wqra_<9tif_4#k~ALpp$E8vaNd-}}}3CX;%-8gUTd2t>0*`K&^v~oF~tNw4~ zZ`z+HpPw7g<{$LvPT_CiPgT{~)73c3Q}!P)o^z53rr%l!IJY;|Z}}gD*S9~}p~$U2 zRrai^{|3A8b^R@g()!cn5A9{)hxK2QH&-O=f0i}W4fSVbemfcdkZm+xCc{Sv_J9xbX)yzsyB|{@e24~)$hL*_P;9W z{~M+JO!XkWrMm&ZP@q3EJ-<>tK!BgA9svadhqp9O6~p_^N%@U)f(!jWmd}3fia~q@ ztd`KG@}lGqQHwobU-lapMS_>yA({;3k*Y;-^m51b`*PFg@mi~5exGU)9dg3-vwBC^8PF4bl)T=xd4J9i-f6$)vqagm+BLQF{v#zu^1U=XN+ zCKggXHY(NqRkI-sFH+Stv-9IF zfX9}gXL>fR6%gbBb|0V*cX*O*Zi+bDmA6^i2A?qR!RP@s#)9T{xPiMLtln*eyZa7t z7_>sMQF(y24}dD2nnuJb7Py9_d7ebEs0wkGFuK|Z;rb+f?VyL;x$2W2&|kfDg^=e4 zw8<##W$`Y}%0jvN*qRY`Fbke=k0V5&Rou@$7>~LJBZAChOb=pZ2&+Ticw}e({;Qe1 ztS}1c)H|@r0OMu>CVL%o@>78uTtjc>Z#PtNK?*IWhVYIio@)`-U^{>o=TPVX>=(uq zdzoEA)B21Nu;UgX1{P^I#6`BM+Oz~7DUd4j>eI`tfeB_yR4TX_v1!)!@fAEfL7;4_ zL$I`_mmH5T6$rQbTy49;1Oy=8MMy0Jr3r#QD@+j5vUz0EouMB^UCWj>B-+&o#XU5gzBMvK&(^U>|NSM*WGe#kE0Q2BYq<+6^RBt6C+;R3yn2tE& zl1jBJN+89E#FUDZkn0cAs2XtZ#NDIaiC&n#-*h*`uAE^Xn6)@lTpC_Q93F?I(aa{% z_%@BsAWu*o?hI@hArt3q--dj(`>Caq~CRor7_|7z3J;82SVYSJKAUDzH< zbGBT2!2iiQwPqh5h4Ekd+82L}BrQhU52t4Z}xQnr7h79N6m;@;YqAXRFyKhuXal9JMt?EoRZJW)>+ zkZB9C9x5$s>1>}C1YLO_G#qeG)s?9&?yJ%&7k0+2PJ-Pt;Zh0p`QA`}_H)RyAISUm z*wv-h=)Nc%UW~ID;C`bE-1@yx%XFSldw6Jc$JD8)3iCZ=AkQW?Q2ej&2+_n|#$ix*k$IDd?4=tj%z z=@Izm8ITf7#nB{fY%nbqR^cVw8hVp3nLg>@A@Y@ojC*J@tcs4Vj-aXsFX+N~mGLbs{2+QUSJiHzu`C*Ov7>kOX?+k7sB5S{rzd5574><5?YkNRGYYhe#*|3jT+t%{h{e`x^nqL;eIJiS8GAkc<+5W^(KQQU z@NI*aL0$ySQRf50`)&9X^BmSJ{P?2U?*&70ENx|FtJ%-QZ=DDA&&~q~7#s-nueDPo zLPW;5trtJL4+8nvs!sjfjq{7Ywq785lzrkTnOkT7p-OGiAz@k_yTU4QrVAywFM zpEDJ*998zrFt;C^^ z`;V;F`GU$l)h_7)!2JJ*y|)UFE63VK%j}rhju~QznVB(;nVFfHF@~6#nPX;Vwqs^y zW@hYD>FJ*7`M;iT&c(Sn7r*LxN~*23mQ>o>f-UKNFD5ryV?k_{r!tX>-0il>f4CK< z@s|-}=0jJvCMJunI-JiJ%lFYxFB2ht3GE{&W1aLz77td`omw{%@{HeMWoaA!zM;gp zmfcFh72+0RVA`Eri_Zkw^QK#nHybQkgz^JaKB@EAlB|b5Np>F#)=g9x#~zwQ(#48` z=L^}TR5FxFD0-T~`L#>X+bG!krWX=T)HYc4E59=mm=(qNc9r59RxN`lcZ{cOx3Gx< zsO$7`8u_ttk0t4n+qQ37%wlptbE|+ktT>sPT{+g5qD51x21vxydBE$2c zrtkHHG)YE7)CpV04`wF1R}4M6+wbFA3pNBHOVO~JJ^G8enxit>keF}3&=h2Bxy zL{y&$rAzRRu?s#WFdcP;w>`10Fsz$5InBdBWO{@F{ zAkquM9HfjGMFyaGQQqF*H)SsCSH-Bh2GK>JBc{|QD!;bCyxL)vmNV^|6h;!RT|7>y zyf~(D7+H+6`2}u+TkmJ)^l`klP)3d`Ee^U;M;ktEdm9yuRByv&`b03?kENH?ZcQ%w zMWK=`G4~&D!!~B%(ZwZFc{8&TReaJjhJP2%hmj_%zsk$Mmab4*=zp19@e3Kl`3<1m zVr4(4cz$TbpWB>gup{Jv|^+C zf!y?SrsKrS1B2M!)W+(S(B9PB1p3*enupHn+7_G8V?s~V?+-RL((ey85K`yQ1;F1& zg#t*x$C{8II4-1@1wPsTz5s~y&U$Hk`oMUr5C?eJSXKob@_|%d>m%+vBC6`Ist+pj z65a{z`Y)(eUdzLAVsVWp!yYVC{Y zu3(Aehe@XN9IUJ$g%8{kF4u#qWcAXN0TCt7BzT8q=%1Ju@$Cqy;QT9#*fMOrDXbnN znNZg8U07g_XQgVrc!KvObe;p{a-GrSaKH5~e9#%xJ|nH;6Wkb6Wi=qjW)PI7aZ@swWH zxUl!?V2UWfK_TJpjBJ-r1+&8)qF5rwPU=p6*j5mZp$ zYo_^HDCa&dWieh*2J8NKD&-fao@Y;3#1||q=x?^{m#^{z=@moiPtq8jN z`RjAd3(k@)ndTDf{PP#a_bp`fPzc5qrtNP!xrm?&u;+qCu~)WdPE?plPSrDKQf!3Q zQok<)$lZhQnbbCr>~f-u7Rhdi)$?YCaM~y}O73h~KLi;K3R(O^8qgvrBxgz)mO*=PChQwCIqxzUo zHUnBcH}_qYoP8QPP3o(b@%mY$dX*?dyjqa69z#1>kV{#IuQQ2Zwgq)7zvo-9f@q;~ zI{hr@?0~@?B;5PKGfsw$Y#&$x*;S{BV-30s-?4x*kKV|a zq88Rjnrjr`AvF({JSZ1a?$n-T7kd$&yo)yUR%NnD*nG_&%H@R3UUtl3xfTW+FxiM0 zQ!{52UqW(4AcNQ)sGGm*c%;6kOw>z3ZZdl)qU#<-X@ue;)Js?)dfaC57NcarA1Ty= z)L(v|ZusUElYj~t2eJ|wFfDbtc-S-b9lKmX*Foqs5;ejEdOCEefs7|_nxhtFbxT$H z$EKF9eCU>$t3b`Ln`8_;Ml}v(9p-|m7R8VEdrWlYktAQ*fSl@6QD$rlTN`RkFPyF7 z2gI1!fB<+(Z`lF38G%!g(wHU>Gpg)Oh7-#To(QOJ?4X9`PJ3L+(^;2t^)a$&>=-;< zH4zQ7&&xQOd;JO)kluPj;r&7nXt$;E%VBe{9OeZP>Lw68WUxVKRriUN?m-d5imvYC zkXn^6Gr`fcL~Wclknx~Abrar*qB{Q3#T1~L%CaCilc6(}VH7qWQE9O+=U=MSNou*; zx55h9go^`gQ>|7QDhjHHiA-H&%^z}ytR=ttZeti7b-ZE8#=Y2A zUh4y6N^6b2{CVzjGPyWAsZ6mBPk%0{3`uoqPz(%cdc=O*ur>vC31tP@o|vh-2o60}n_9PsGqQ02CEd^wn~rByz2*;iLWvqlGGHpgszEHDMI#$qwdi-j)72h5{^*C6v@`%okCLp)5~eeS!n5cTz7xw z+;!8)`9~U#4wU4tFRpXIsrsPO0frs(rbVy7y-4n!YXmyv)Hh}{g6BonkmE#_i`+V@ zWjf*5936X@z{t9+)96~?VLl<4u-feI^7Vk6G|sQs6$yx@=P}ePZMnk@Ub-IoGy?g! zKMjJmv#tu>vF(HL5KT9;aC{pNyFN@8OoS7wV`3~4zs#QGLgG4&^&b&=jUk;qFp5>YMNcBF!o_LSW_2&`R*OZ*6pHy8K1; z%~4%Kj3GDr4jDJEaXf5u!q;@5yb!>?oodoBh$v!RGZB5anr&pi-R6=mp`MMnERDZ5 zdXiL;H1#z_X-7>J4J$0AEyF#6nh~j-#*%~AU1sL$rXQ$8$u@`EH!vI~3$~2^3FMK_O+5Uv) z-YGwBpFTA0G4V19`F3~$-V(t`*tK3gyL*X1HLPA;=gKPvTRxv{CTdVcqHO0HR?J>5 zzQhUMNv!ftF75lFqNoU6Y7z3mEWpB~M~asZ=b9|Y?J}>vpYxIdz1c2awAl9&kxW*7 zpR!KJZ0?+_l!r*2fYD@O*9^N_Q&Ue`qrV7FD(47!_7igM7zh&FbF@31=_&OIOQk%W zKjfsxle-KpNY1A2_ki5H5O&Fv_8sFQt=|BqEB-iD9wf#T&Y>-cUmEF5^ImeJ&cZkz zaw9e7DfUDfLq59YHjakAys}(!3T3$l@8cYCQ*#Qa-!%&i(MN|96>?}p974ur-)BJ8 z)dHZ!VHWRwA+X4zycsUzWJ2ZJz@Ag_4hB-w70O^XPkJpKO?FdbVuMWaESeH64$-OK zLK+I~G3H#%xm(Zh1bK+iz~XqdLYh4i2%K>%nJ&|0`-`VBD|RIjCOOmT{m9f|`kyRU zuphBB0WTsWDc&N0$Z$|>Y(bd7nx8d0p%*9^BE9M30ou=3;A91)y`QofM~`5ByugchN`lZ)e?_I@XzNZJQLHGt)KgWaGf&w*qnjC8 zmcm07RH*Q?z5o|boKkHFyZzp-;oM$Vy>d6l+IxfyHLHB`q$24*EQ5#1kq%D;M4g>vsTxAXQ*#ItN-Bc7rH_7&D*#f7Z9}>aE65a`7;-RsiO0i+-{=VUsevq6Z>2 zE&(TD*!xsuFWtyYBo5$=Xh!KbK!^pPX4@ps0acwwROXAvc9V1HaHw(6QE>S;=dSw? zc37r#`-AN{u$f7=01M|=@)21tjZPhiz(BAQD%$L)>j4lc&=2-uAYOjpN^=LZD^tN} z$BAta51M%81MHTyGT&nZ-7;M9he>ew75ClRSY9rF1CWasuN=Xcj(KMWAK`g|rV3ZJ zAMiVWo8_$;P;!h<TZzhGW_pj{D%2I>*K_m4tPbr?}I_)7F)$iZbw3 zhE5xEswU&XahMGp;inSQFsYF$83$;|NB=^#US{-&%i-yiz)3sxY?6n~m%xvj7q)DU(tf%mt zbU6j#^|YjAi;Mx161MGWp?W%Be&#-OQd{&*b9#{&&0`_ZPLMw)uc?~4X-_KzgL1Ne zpZ_MrW4Fr^vV2YB&e5MR30zG=&cm1Ruiip?-KlBEhe7XzGt^SvfRue(h1M|tAQ;ZL z|5UCiMOHY?w)Q>U>P;APmAk&J)f=WDUgOToBQ~-k=tpfbZp(PMXJ0#i_t_3-Yae+N zsZ(nAScv?r(@wihH_IjhZQ$!utu|Sl!V!#?CuU?0{F7N&vJBWPWaxSc6(Z9yCO>Co zRm(_EnzjGZ!n!i_5dp}pCYz{0D2cUf2?-sP{k{~{`;DL7Ri0{kad_$kSSfu+G!rD? z#=Q-jAm7sQ(nZ$qY-U8ZL9B}e?VeG9qna-&zvoBx6BhOvQ&amdbWax^wA#wl~^;B-dn+R=qg0F*g}Z`x7W zN+eFcclzBVXWG(HbpU2b03VZ1S&|}#=&KcRvm(v2XhcLnb8XYw%ZHsKV|Q2DU8|JL zbv2D$;+%aQf`{8?#X0DM(rwmiGa)D!GhKQcS@&Ir&?E!Q+Mlx5u-~YqF2HOHpT^G9f#L8IN0CVBWWs9WZc70DE&B0kw z2WyG*ya{ol>l+f7Lg3Y5K&J@RvQJ#ElD0dSDOdST!c|;8(yr5zWn=SnAg5v?sTwy6 z%v6D2qYMjT?Ecw6M)gC4mB3tZf|ZjFWie;3P`A>XaM96&cgN!Arz>>~CxKp}$?Nw9 zc6fVJobD1OlVb^){L@MpwIlrc{>S(eOR>?Nm+NAo-Q3rXe? zC8mPlcR_V3qIDF$Kt9Z!2P0Ls&^ zVmQanbF7xBX+y7nk6cUAjg^Q`9chu19TYlk2XQ;|z5V^RnuiRrAI&*FOnY8~HX<$wTZ z$#b}!D`%pungXv8()$DjzcFnNHMhvdahAn@jqk@16P{D_5^^sOwbLnTVIo z$mkb7L-1eDGGzdWY7URVgFd?@FLWSqT)zPnUe|nLOHW-9?O$`r$~!x+lTlm2cEiC$ zD?6`MOj^4l`)Z)^4t+?Q?dd>SFXamaoccTYhQ5ZeT(a&)UnHAcGrT4#B8*PHiJBt8 z3mtu^0dXS-9%0q_ZRu~Iw|_xf|AN~FqWb^8LD~Kb$oAi0Z2t+K%?dOs5A!Fs_FtF* z{wD^vn7y7G3=og|7jFQe1|b7bQw!!_NZYRIXWbz1z^z6-*$*;Sh*19rsvQTKTK0v#@gf6J(zKU)BE)QVWh>b@y+o?qBQVn2JOc4jWv@ zi^?HxSLl}rZC?go6D!O!n(}YBp_!>rvW^;tbWbk@U)l%oZSEJfT+4EVLw5(0A|UU) z9;7}R)pZwX+GG1G*n#5l6eUfxMqSME+55fgbet!ijJx3}K`R#~&)&tk`+z_cRp@y0 zVI{wHXIC4iKGfMWB@Qz8c0aliAdn@qU*tr`a_rN2)9dBDkvrs0ENPB@2AmJ~IGVw9Hf<%SoZb2k@C(k(1dKMI^<#L!dSqfCOgoa1s<$z-_iTFp_&-OY8wtn|XT@ z2p)qDMb;^YwaYkF1F+q}udeL(7`ZjBQEds_i{KGCl9$V9n&oX`<#NlBNe_}xMzLl$ zw;NEe(3Ha7*T`w2)Ddy){jTiTBnp0?{AnO_ljdNPbx*YfLN4k7Go(!a=!8OT)-`B4 zyK7)C&kSQruyG~Unntp*$7*Ju4JZHnRY0`79@thq>{1M7k`j5F3TB z5}hjk0#i&HP+ty4%=Ss5Vk^=bc4)lLUQx8m_<_ZJ6ps#lH@InZrknff73;c&2^Li# zFhyd%;q(gTlh?|WL#7hm2UxY!b&L>A<30T5g^78zo@RZD9=7Xmt+WL(`xQ)i5X`cn1NTzIvt)7& z8if2{X>X4F3mV#y@wG z{iA;Y1p+jH{7#sG`#VbK9|sEm5eekW0EdJEf&O!c^gkFgUST1`1%SJy&b& zg0o3x;x|r+o4JEJB>4WXdcPuph{A_J593^H&7rnW-;%?rNoUdZA&*Vm-m(LoVy>BK=t9Df7b?J9_nNR0C@Kl>kH49x@VdUl~b9!TSSF_ugY_?@$az9Iyv6H0I+(tdd{cw z(hVp&s-c5}RuwRqtH0HUQny}gT=>zrT-E%BARL*Y`1Ozw@J|Qvj0yZF?P3N{=I1Q$ zZ8<)eZ0ftL`0W1__-g>F6>H&=bqzn$qwIdyNa_qGb=9c(4vmy;q#cui|DTebqI-gb zpdM~Xx-Eq+AH}RKdAOH4^ikaD|0(fr0k!$Abmy&Fog`K5Of&bC!j{K9FDTEM zSgQV%gsrEUB|dS$H{jI3vvp3LcYlJPZWe1~Yg%o4Fy9n#`BU!y^wmr1)5>w*u%rvO zZM&C|lWaUkciPnzgodP1UNYF;ihCg!>J-qkHUB`CBI%%ukC_cBswfivY*{Z9}wB>cjApOJm!^pfLi@{1{;|ej& zKIhGm1vkxJvoxk{Ozf#QF75QvqpJ2F90LDm-hs&A>Kx&2UKjRtn=NhMnP-xel&jrr zj3gb*dt^k(tw$3u8k1*Iq|_G}KDXb{X(D<89?CHvk5#6_HY^>oqSvTmz41rl%S|K| z+>sfHg;t#G8>&q>RK?A7|7TKvTsaz(8na+$)8}Ljn;?Ez9AM?X@8r6!#Ehzm_^5k{ z;P#wp*t7ZKK3mCGs^3GEJs`^6TF9|7l3Y);d9#oioc}N`9o>$%S&H8wnrZkz`T_oT zf`Y$K4y^vP)An9!Jf7LBG*5 zD|ZtI8)sFr5c7MMLQEu7J<5THmpRWBxB+7po^hIVxZ*MR&^k#2? z3=1D{g!s9AZm>LsKrF$R<3*96JOj&7GI9jI@~Vu zNsmhjL4^1`h%HiVQBn#2Ln?qq>p3eA#)WzV8F@;~18Og*2D^8A0x3$ycct6KjxmKC zpVjov=;@Uw%eR>$HO|HMTZ$O_6Zuk zUz^WDD?|zYx5*-;)!SGs*FBJ1XwUiMz`46!1hw-VaLIpM{0*Rz;B7-({=>1c|Bci# zg*WaF`l|b!w}1Lo*MlEG`Vkpu5G>!soS$Y-6pv#)3g${KZrQ=i#!$)uA5;cNj`cqs zhJ~4d-jVtK8*fIAq?m|@NkJ+5>cR0iA7^9cLd@PV2S;ocZ=Lw-9beAV>RH@Ih_ZbLO{c5|}~50!9GnK@~?lt+Tz2-S3kdpc%HH}IDX!k6h}hX=Lax~8Rm z4>{0wzM{A0(bsi-nEnjCZ$91ZUif9W`O&j+-g8{C-7_LoUV(t`R)^}&94p-mT+~=Z{Oz%r3 zOX?`gVG^85UiMhJr5qJHapr4_dtSLKsYs3(oe}uNtw?^%YFw68QI<3R|DVoQ3!e z;Lv{ulCuZm#jkT6+?Gq{_C-q`Q!#KYDs?&R`^NH9W!|i#nr7Y#DwG@s8F&ne@YjgZ zm82YAFRCohiK*8P$LRA<5H=~k{Dw`~0+GvV2itKj_(RkyMJo&0+y z_txiJNJZ$sl_2^qJu5xge*@&7 z-PrYxJ*zMB6fYZzY2SJ5S+8;IIKD^m`#zaJZj>)0#Nu0&wD$U$f46Q$MqcqiCcyCT3*f>O0XOI!U zh%IwIeRNYapx6k9DSHZOjv~*qMfL3ZPicY7r>)+$ItLzgxrUhsZ=6XsNzjHbWM(R{~>R2T}};bHQQwDb^qD9!lzrz*E;eH z&U`!J5hd%N`)Du{+`gAEpV&JHsv`LJHbK_IUMp61KFq#dMy&*8J^^b(+!V=T%6|9R zp9-L7R0V`i)#CaJ(hn17!j9S<_Tk=JxEbLo-Y&>=lA$A2LPtWs>3)cSUMI* zXDYqvhz?r$VE>yUFdjJ5pa8ZgkF3vf&1EiXVgZ)ouV=@xORfnqasR1V`HNZDTe^7Q zPnY?g<)Fh??I+Ypi`R{L&-99KRb*~ee-Zo-L1w0lU;4~UF9wo_Vud^wja3iq+Q7}8 zSvj?r(GOk!LG53c|B-(Hn94ZDUF6A_MFsW6Pt9r_qphu!3g3T;{fAJe;P3occ#R!4 z?ufXPS?g?&c5r%Q~Hd z+4s-PXRR3IiykDxY3$5qB?Lk&R;&SIE26wBe@s5EZs~=8c0TSe>uyTjqk${&$^fQsJN&g zL8kGe5XDdH!+VL0)7sKUceJ0P^QSc~%UqABWHt5oi9rYo0enB=)-6fL;rmQkxiuva zcp(Q9$=Yj(SInpKql0p%Hx9F-K4(0cvjXXLFL@!B#5k*{2(&aOuRf6$KJho_TO+va zO*z;jVzqYd#8*{s?O0YBM&-P78m|eQb6rnba#3nLxDv9;O(Y&vaf^Qp2VzdJzYskT zJRP#)CBV0GV{?Sb+BzQ@3@TSOvnE%7snGV1)N`f>h%~An3U3E8$PM~y9Lf~e)HK7= zTzlgqEF@CwBQ9>IqHZC|&1{!jjqBPc;yQvJ)%_HltOk<}a%dP?uzcSL803j&6JA1W z%4R0Xe)egO`3|3haFAnVF0-;F8D9-`g@hqw)TklzP)8W$9hhW9b>kE0Z-n-+VP#eN zQ1_hqhWQ*qM18qz=d$7Rvgjqd%C&xwtz`w>5|hl;bJR&gSCvN8`WwJQ%*6$9U9-Hb zY^-pm2hNxJTJUpbGe;6aF3Z@L+2!5g0S=d$Yp$TZIv1V=qZqXc;-3jdE0$M}+>U`q zb=CFykp7Ya(ghL2?kN4}LOC?)lD-XBPgc+m$HSv|n^p$-^fSTraCU-;f)U&isu^+9 ztcH&p(uY)ZEke3eM|C6{r6f!?@C$pZ;nFaJ2b)2`sgsl0`J}8EEb7aPXpdNTEL^#B zqloDAwmM=w_f5NJ-S}@3rcO1UL_=4Jo;x^c$*bx=N55n1;a@tY#vX>5$suC%sb+z< z8Jiyb2y?{SD72EErY-os!6t)22%GBKWO=CbwaKR3iKh?MRvW%I)8A@}=UM7#1Rvok z_+xr#B+jWJn;>hTZn)Lw%M}wRIZXIv=~dEvjy{MMu}-m0c~RqOYH#guqGQ!njeP1g zY7fdZSI1|6D;n5#cj=2M6RX1On%`Y)=J{T9VauKhWwX+7;6FYi5F;%1W13_Ys4DQK z-{*Rvg;%amHCvItg{r2`d%{!H*}@e}v+kZ$&5adiC#mlHnazb2pQu7$ zwgsE2X_+M=Pgj9f&m!E4 zf4D-IqIm;1C4+Ks{fi^6PX3$~vx}y~^*1Ujyjw~en@zKbokC~EqmQ+XKTp${?P`Gq zh3QpS-qud;a@g1~vwr-$QybA5O&Fv~vESEhPNFp$Nw(j|Z4RQ<8;RT-wBKpATWuQG zRH3CxLLLdf8*ty|F!qLt&bCyyUL*DzSjy5Xm#7YtDQdZvjrvvoVn248&%00^u5Zr= zM8sJKBx|7rFH!gBM{0_bg720T`9f$uSzEd}W^CjmN}DnAG0D(cK@NOyEnD*PHB(|G z`TBJFd27237K)A3)1CHWo~s~hfAJJ|!FX|(0jtomwQJfudv+&AVVKBdjVe1>cno(n z`bGM|$tGv<2uv|H>Gh1e2@O7;#aUo$1=MlWJTZT$bRCPbaECV(uLgX^u6fORXr`4& zUarVaWcLw_)KQf3`$$pB7EEKnabrSSMon&cRnYKrkbs!citVlQfm6w+OVg5SLD$vR zQ?j8shH4p|*ia~GHR;9Wnf8s$1B=)pui+D-7O~A~Yfl`2uY-a~N?2yh$AcIcH|;Ln57%gXG?(rWT_ct#xzQaXhOpBg; zDi20EO0qd~IX?40$2w75;W{9MCvO;JL;rNI3WSq!c}>%Grkgk3BNzt@iFm3rm5QIk z6^7^ldzTvJU{h&?dfm0@?pos%z=~C%>-HIHN!hTjm#ThR-0$L8BJcyUV>lx8KaZ~N z;0yA}cpym4?R@0+_0D`Yako(1X#ELwbP>4NskRbt@Dt}mY*KHi#mI>J6()+n+Zc172H?5ti_d?N>p|#uRd>2FM zVLrUDyA}p6%+8KDrV#XxFWkV~AL)>p@7q#&{t60ufqf8Uv7jp+Jld&x!K2U$yUXOI zmV4*rK&+h!Sz^%Al3q2u`stOK!F1k2I&8X|Wgg_hKJypIT1Zzj1VTw~OI7q!xE%D9Ftg1KIHXNESg?po+)e<3akH*#ob zM;{;X>62|pkP!UmnJ%F)+Ol$u33t=Bj%m|2pWv6{X|;^-%%3(o?uWY#JzuCVl-=tx zO)OZk3HqF0aCB;Frri1(GU-S35~r741!r-@)wWRSJ_f}fZF@LK(cFDs!6f@caavC^ zrJT0msm!dkq|yF)UW}IHW{KHa!-^Bbg`7uSfN5%15%SJx<<{9)S?yY9NX+hgG)l6Q zE4UH`y!6_Dd+8+u6Xk90y$#u5wP{APh7JTlB|Q7p=sj-QL>mMb`#-Qu@kPWCgFN+3C2Wu z7r{x5(Z1Kguc>zDCQU}<_^}SAL)D>LPATVk8A@;O*umhc{R*Pfduwq&uU~~C$_sQ= zt8e2uDUE?A84cz(IeO%g=nEYg(<&9_yKK;(=@Ws~o0hXpjCLDxDY)PWd#P5ztuPDA zYL+{?VXS*jwm@Q5VF5#hy-0qekaird`I*u)Co@F?ESzy!jf>eDV4ftcGDlzDgBD#E zU+So6)beS1Y1bn%OTjz6wZVRyI73N4H}l8Wz2bq%>#w+&kd!U#Kdf(m7$i{;FJUG8 z7#sHJVC|gp z;{>DF_KZMe0cCW~^%Uex2<$58EjBXxhj%lr zSKz9P46fh&gs|nf=kK!G$0xl7~S|?Phf3SihuSXbsYFE<};XO$G)vDuAZxJXS3HNxQ~(^@Ug%anTB1U8YyVH zEeGZ^o1{FI1B%2O$@Qjw7U!Cv7G2|DuflLomS`~p91fIVt8ZqC3+U_u`3@qsm*pLtX zuxe_}w^Gc2J|{_p`a2{vYJ)GIK{ehbn~tv@oR{iPm*kM?_t6&3HPXQ~yVQ^p^f5#9 zt>8G7)3@ckJVZX8wS}2;Gd{bMDTJtRNOjd&CJnPv?ICARdLe({O z9P*A&%$-^Ef=>(?sVH-Kg}l2awnQL@FQv$VSmwsU_tVQ@DCELro;x}7!AlRDgu8uM z=H)u@F#H-~IPU#5*E{o!qidzj171qmlssKBvpvVSchvMQ=bNE$@j6jlV3&bNMqkhJ zuJ?PWPDoh)mKeo~kJ+>6%8Sf2Yv;1w-rbu5j?iiHGJ)Zvw*hv0+}2aL`Mvj4g!aTT zL*-Jq#k~P)=0vze@d$opIB%h?dk5ch1O+A2mp*o9>{QxC6^axLtu6hd8*DsN-8E!N zCbExM>7dMNWsD~dDKGAy9p)SAOQ9obI0lxG8-=CJ;KFP^!;tN);mglFW#zlc5M4Zr z#b4tC->tgIk^FokJQ7YK!B-r5Awx*`>Osa`5`T{v!1e zJ&I_wERwjs3o1o0p3SOvk%ym(R_~XdtYWX=2k=d^SFLZb&6i3@m)QD>z>upVu=5-T zzv&cZyaRb_^e}o6Smh4WY;#en+NbE}l96Hz z_F&Q`7!wYc21pDQe;r5akxM5f6&(uYLC|;e$>;S1SIC!>PLhEB4RADDwUplp0-mxo^H6HU4FvfF-sy)waT&APssb3SX;|cngmi&o-b~E zI&56wnKOuS96E0;$wYtJ+&3K@MR821LEsx?;c!6?njW^{lOpXVIo6Qv8mv$X0Yv3$ z@DtxaIiNC6mbsoQuvvny26AnBF+7K!E{>!t9EB^y7!P>f@zKwgzyjfEOBU8LS|#t~ zw!QGMb7qqH)lTvcZaGtx(U0xe<4o13m%q+if-4nv7D*MJaeZxa7Z-0d%s{Af2(>Z`xm~ zpFWBM9eQ~HgX03S!^E#9|1jM)v^*WRxWsN0QTZ}Gw-h&e6Id=yQEt5Z>`dtpyV0-} zfmhnejEW&@Ye()Wd)&@Z_U3r;+ArNsBPHrq znY2%d{xLMJRb^tt_f&U<0qrO=i881;LMg;LgmatS=K21~EXfG7&Tz43z7S2Z)?vv} z-UQVmk(+6*zz zddp`f#|qU~Co{$R$&i>{+Pi!yNAX#@?-vy%0gVy~8r*%zmQn80Sxhw%O>8|zvo8JK zGC7JE-cz)$W`XR%^#(6Q4gPAlhszO4I7np2zWhGWzM4Yl6I0YJH^n24omGRMbV2qS6~ z_OSNJSu}~H#KM6c93rr_z~XeY!#2;@jBcl8o{u^4DiD=%Fm1xoZkRUR0VkW*GI=!u z{%PFSv{`F6WKW)SJ}cdeDYlo{77&GD~@|z5VmRA#4$427crc!&$UeCrtf= zw+@zU%^2+|I+|6QT#j_alw&LOuA}jp>}-P;@7oi3B;U_MAY{c)nIx{TP{?DlU0oYJ zPpfFPVRI9aq7^JE=%W}=Tw0#t)btE$l@{kkHYW+Wtels7j-uX{JYkG9T;hx=JTwJX zxx#wtbXH7qlrw3>?qD4ATp#3bYmurN6mt?_Ih>mx%$j7Cf*gnZ_YHkwG*8Xy?YJbK zVN=(J%ZkElslHC+jv{wi1%7CSJ`Dh+R=jmSj>0!Ov*veH>0ppPj10L8hi`R}E{b_c zXmMVTKG_nc!8A@ysX4j-VUT;|j6-;`skOy?a=0=*Qyv;zOE}bMQa-OiyrM5t6qZX9 zQQ=$jBQ4;}`84e_mFkS~afaqijg!R1Y||)LJyzl8%m3y0t^51NCf?b>3#YeaMU zk7CCbFLKHGJX!CU^tXT^_1guEw1B||FT55HdmP;wldVu-p`kNtG5hyuW?j{IjjXo{lO##36>(nRI+0 z!czd|F*H<;qSYJTqZ|vyVK&{82l+gsrI0HSxwa?S;*4)9!AMO(G<0}lx$(Y?yA+YK zcev`hjJxpL9y9Ap30>DK_WjzoVY}IkqFW}%vpM$FA|MqJa4^tEU0_7@Su#Jq4yl<# zg_Lr)Kr=opHpZTjR#b*6#wXq<%I!t!ooDAvp-;~$s=L@4*q%0QKXPOl0Hzg0;%23W z=Oj7LGp#R7!^*3S=|%dzIubWnD-dvM;X@M{XY3kt#^prrWieTS{a#>-=p&eqX;?0G zN(0hNi_UZ;Ss(RA1_?OuWc=(z*lh;D`R7bC7JR*AV7WlSKsQT-zlwF{>HZ^_jWxw+ z#V{rvdb#0Z@>-DInz-NsPNVSgN64YuiH=gg?q*HV0qTCwm1oFxKg-&(6Z(Nvd{k=} zp42vT7}|ji*NAGn#(d784yrgo7~BUOT#^rML~xwbseGs7GCoBRWdY?c%iODSMq;-72LPk|InTB(B>WfjLzNq)@3aW6GsWpSJVDl}J&mgI;y`m5Q z+b_>oa9Y7#Qd)cZzQq&Vds=eujND=$Yvfsap;D?b={BQMoqdQ8w=@6D{_&%sLMRwr z{ZTV0r~{aGT5q!Y?J6qZV_>Ct6B25&O#W|xnBWfw>!f~myJFKmKZktbe7D;=^nU&$ z20@U9i7YNW@;3l*ri$d7>A8cM;#SWfzu^_iMtkrW`03D7opI~A3<2k$S`nEo}C-S|Yd7|7` z+uQo=R(ni`|A)P|43A^i61CgR6f;xI%nUIzQ_K*@%*+%sGsMh}nVA_9Gcz+Y-_G9W z%RceDp#x3OKVB0Ds@|{q&H4MQ1c;^h`kd{oWx^R^^Z-eM3uVXGAJx8 zEIqmfvriL8I31U=7`OqU<7?j_H>4l~BZ(apexUy;4m=vAl}eRU*EJ>f+i9!iJZc8- zniD3L+%@PeT6Wef`WV+fYYEiCYZz#4-=vXsO$GuZdf1oqmqOe9HAm~MW5Zz z-}DOex)a3Tyg^lpAgNCIQh5iTYr1K1?!1R{`5l1u<8WZ{{Fg~aJ0CB7BmGxn-i6yx zstF#?!*Ojhi!>$1SxyPfEA4_GZC^3Zu9#~fwEd{{t2niQ9tH>&NII&bM%+eq_=vsz zSqtd;_>@ALLaLtD40N;sg?LfbV?{}slDgt&y(T#-V~`=8c#sYX`=hLQ3X#*-7epDi z9SYhes!3@FE)qwj@Z2(GIgF9va2mY8?xAxgryv7GMFZF2fs36%mh0wlR^59Ol3%g1 z`W(8YqUX*hA=eriN?EN3?Pu$8+P|)IyeJ&lriuCTH<3~*zE9)-9AX&KNNJ;uMwRZH zSz22-v-**i4@ESBnYcMQA1Gqxnp0-WL3 zJ~^1#0aL_698G*5fd##Ptz1NMA2|Wp{5(#2Vm&k_>s|rkmy@D-tIZ9mxjD#Kf7Hem z*bxaA3l$KgKlKzinr&R&4VHY&rUIHQ?s)h_OKkugQ~9+N04&KC_6EF@n=ou*mu?i;v&bm#7+~9h_fQZnZd4 z{OT~Az3clF9GJgvUIE>5r|k6gm=lbU$}^A0VT*PNXizUQe$|H@hVtcg*{Ms~48by# zrqg3K@3?}Ju5H!*$pYth7oct!wBd`mBJ5? zX0#?3;J9tdvY>IOn~?niLOm4%W->pb-i;r=WXg;Tf)i3v&+(~>C~EgHtGw^|Go{Xl zsUq-A4&((~3}-MDN|ti%zM82OFjr8_i!KeLt4^)ZyBt z7eUaU%q7r{f%h={L!TfBhpV5IJ{x@^LLPYWb+2H!XoW9OFvVDe8^w1BB$girF8P9b zzJp^NVyG&*8U#bm!1|^T)(7P*%P3?Bfzvr40$Dqte15~=3$2z;yzo853a2K-PK?OX zx2NevFxD}@k^hb33oA1bhclI|e|8-OlLYA+@X?OO&C(H^lpOm$vzVhAmAezC++yV6 zUE&aCI)RUOq`$xqzUelle|76H$=c&*gBB8@?J7g`nHI7Z^hKEZ7T#^ZvwgH6ND-`&xOn>Hv>Iqx1A(J3ScI&=2?Sb7_0L_$69E%xTgH$A)QYMKX*- zuKrn+Ga7!1uzvAEu8aSogl!>!6BQ+U5yC+UjKR@wxj@0$6sJWE+_$X{K3kN^gGJ+- zn)gO@Xq*uc;mSH)%bx@&#w9_7E9o#utHw@*`-X<(3WxSHPtlKed$-P4l3-{in^`p6 zacRRVVj<=+&1cAO`4WZ_1kf)=i2I{VdVy5YAWK8GFobe%7l2{xv$)V#AvYn-8LNre zh5=yY-ViLtqR+kemwaFg4{D9ErBlZh!EpHEpiOpG0z}_ooQQ&4=a=%PEXtlj9$Xn; zZ$n!PFO%k6Np-Y?LMixa7&e=J?`OC8);<#{5Vq`N%xTW7$yrd-WN!WP;fEMt3-t~5LyLxg4s=B0 zx}ONC*&ehAY7JB_=3y5HcH}jnA70<_HhLqwpxGDjVIX{+#lN%y^ud+RPQIR=-(BdH zMVURwXL-U^4omiuqi-EDXXmRyOL~w!9tTXia+qBY7@8jzB@yX?s)klSU^@E+#v8Ag zh@`vKuqaje5-vvJD@nj)q7JF$Ty-ZjSo-i-`VfraL)NDJMbU#^!gqL~G7=^%XUb)< zCHBdNbTK>ZJ|i%p@Q~aDFpZ+nlz~DQ@*rn(q<`aQV5{6?^dFmq3u+3uBgzZ#qM0&jauy_t}O}Jas)pwRO-*A)_=xbvTB`k7S(p zG=!~_rP+fciqg)L-iL98On_Zd3~c%Uk_K~Wsi={jovlNo%k3`q%B@j5_XCa?Alj$k zs7I53MGE_5b z&Lgx^Y`mZ3y5w*OCB3;FK+Gb?^>P-=YKXsR31iu$;;aD_p%hvM9X3(yY6UNhTIPdB zdyT^MBd6gcYiXelhaju#@rNipQDlTJ=1ENE$fsAcT~Pi#KrAg$+Qn5`%EdRSeG=qL z7>}qfGq7SFK>+cmgdntvUz6KqX|ways=BQ`2bzGSLCXyytl}<}4U`h47m7X><&~)V z6-9`v=$xi;IqzsJO?|J?G8vt9fNMi2-XZE6rJEwN-!MSH zBMv+$a&VmdqD<(<@TDC%giRH5l;D>65bqVUN0T|m)j}kcglz?9Nb)e0$4tZO81WWG zFiM<_9j47A%PFx#m4Xg9mXMvOa)cGq1x4-^Ui@fgwXvk$ao z4hLx%S85E-??E)H3?@h%hRn&23UP4hTavogt0GVRFQewyaf|+=G*3Tnt zLq&6*kboWWY`A;;Ami#C%m;_3!}+b|85u~kU=pM)7p2S`--4Bg&T9T8ZI58LFJ3ib z3I(31&o07@KO>X?bPQliPW1S+Ji<0ZY~YSDjaEfX1-O<`8!+NDR zsayj<(oCRgkahe5y6w#*p^aGqh?5Vji;s>g!lwMe%eZz_(6nOToMB`^XduDc@-7)Z zLD;+!W=NZTqO}8LV_jCESCizzxxaFKYJ)x-0Yd>PiC(O1?Gq%}c|w4Jgb0c`iTVOs z6OfHmX|)<-=qn6984mJ*+iMfX2!Muo%+<^LT1H0%64_hM=XeD61!6-O9qx2=w$nl;+DLtcs)ec^KKGtC zfojBPGr}>sl{RnZnelzBoR>Xb9X7E(eAK!pt)Wi#weHZT=edVmW)*^8!3?o<)9&sk z9S5%ZIklj@b=q%qIGz`CDN)?J*kMj=9~dzRt+Q4RYt7>ACP*nc&`#G&r|X;tcIBDQLFr0 zGJpN|@xR~EfCA5&cmI>vpGpLt*8h8Le|##>d)?RZM*;q4;k#$G|AlE_OOion{mXkd;0CFLJ)iCn|S|1+KFdbBs-Ki~dK zmeY4Yr^$b4>0%u)#rs>0z{KbEreK?YWWKlveB1N1tRyZi&0Zzb=5w-|rm(7-#Ox9Y#S;QTq9ae!deV{jt>5b9oNhJRbDExEC6`U|b+ zBWNQ3-@7&G{eP70Um}R#-_BiywUh;`fJW#%lXUm)%ryR!;$gN>X5y@G5U-C z{i*7I2fPfdYDoOF{8RR03oRMY*5B+`^X0v@l%(fp@c+j2(b2lqwk+aFj=0q-vKQ>(9xamfa~smCjVWIt^3WY;60*Xt>3496aMAj%W^{! znL`tMQlj}BZ+64k{GGBt>UiZF=yXnJ_q%|PzS2*i!hcuu-)4TQKy!HhY45%&`5n;p zFDLP@1?f01N&csnV#ch7e_Q!Rf*qfKs08M}KavIeXSTnpyB-$^sO0!-%9U@>zjiDC ztlemQip@Xcf2eAz>-=lRzr@@A66f6>=LIKw`D@C*iBn#WQ$x#p{+mz#VtSPKdejo@ z@2m3{u|EX{+2!T`OX7dYn+HreE&IQyR)1F#U?F*LW&Wj){yQ;X34a@H75<-1|B;=t z`2V`vfx}$Cc@H3<;NXz|TooSh$1oRgkPF$)FXuPyVe$g#Slzt*bCe4x^_vycyG~3? zNy+=7;{$zL5%mq9+KyD{oQ0rP%CHR1dEqeqAs@C$o@}ij55BDD9Hd^(Ga zV6zSTWUw5Ug-eZCr-QDWO>#O+wR2N}4hxL=N4pk%C&MapB1e*{pRiXjWs-~6J}nMm zpy4qqD=Vvc)EzJ46Q*Y_`C^3I0cyHsNSW#6Vlc-pRqp_ABqB?gKF18(TuG-gOpLJL zooiCQ5wVSVzCo6U?A_Pwb2cWWupV8XjSKJ{GtO(i@Ak#u@+@EaHug{{SmG0@5t7Jz z*OAs|m#WtZ;?)*t^KYeM7lh%B`0E_}O(cT8*ms?75VP%t=9+wpHEnVrlyN12!3lG# zP+vF=rWUK}laOD?c5e)ZEHbO+-?zp60H+I9;8^2RY`a^5B&Z)2zBo}HAS!LknzIZ||%2+X0jX3$f4OlBn zU-yFxwdO|umi^4SUqX$T|IC?PLy@;*D74f!_3Uf*{BXDEump*9swt?ESa1r=yrggm zH7VLu{a%7uumI>Xe^ZCrcB4UAQ9?1O(dlj+Wc>&-DP!G8;&17glLvqq?7grT_>-1N3i^`b}$}= zt)dD|ImmL}fM-h$B=vKLA1%P!bO=Wt@e{xrt?DHkI+kXW_Ay~0?cSm#I!`<%)`bPH z+mgtH`N%4QNXHV0&Jc2?RP86Wo7$>d)|jvV?Sk<`Lt*eqnE;xb5Es?K6nKE^tzNqr ziW}x03zuTi96gWYc(|PM14$wp0w9dWp^r)3EV*jGQvlSNR#{&7T6&9hj3jxxq%9Ij z!t@#O$5YbqO1py+PAy@RZ6dthobd8DM+@m-loRv&VX&1jt-4=@y5HXcUX%CfhsuMc zA^jsPbgyRpbn#+LVSdb{rSuWElr#CZ>$koiIW_?^wzl?Mthc3I`ZcmpLq7GYx}?8m z7UR473uH8Xa46Af%YO)m)N|HnCLEJ}IEt2^A?L*08tdn^cRR^pH@77dCL3;WS3tdU zDzBV&|6p*l){%HF{NYgwxUgT&u=gtEcfv+$1WOLHRo}^QG}%-VWya|TBlxvMq6w8W zZxmroU#HSn&HY5~UmxrVDST#8a?xSoVjE_WZdCAi`@MpnDfG#I-E{bZ%1N;7^Ux>_`r*QpKH!80lSFPRLzq^*-s>S(t#RzD^AJ_ z{cvQvJlm}FihQL6J_CFbdX`A*bgpxw!_+uA=UVStJ`E9R;<2*!DqBhN=~rdn>Z1}- z57w;x{tKfu6Tf;PUIh{zWlF*g1fD3`ms-gmHZsjZ852=EPu_(rf}J1W20pFpim{&V zes=3zHhe9TQqV&rGdP}t)=X!@@x`*3O;+;qopp`Vf_*K#Xd$^=0Fe@0l{A59t5PY0FOhJd6u(RE4C+!a=Or`4DraoEH76xFQkObT zfsYwB3xzuL(1nE~o*GiJVIcUDj9!2>H1a>k@MT-?AC(%>|ZU)!F1ipY_QTRf8`L- zcTyH^B5f0^9UM|>${b9qua@|NT`}@&Jg29Xqmo8_JS_Ima zSU4;BN;J6eQ5}7nfEpuDD3E^O?rKMrl7&LV;K?%YLsc&4WelcA$uw`#xb=ix8ASKH zI#FHBq`}-+_Dkel7gnnPJCX}p^C?!0tK0;$GdRwCA>n9*NfYamYDPyQT38sb;0Hs) zb2tcSC*Vc44K1<7x}A7ZgW-b5i}v*SViz1|I{5_*?H=#d)PWk*PdY5%9(K=;3)f-; zHUJ*2T1J0x$K`4xI~g_wr>Qro;=!S4BUByp9#*@I1&20MW+rP33&V0V?^s=x?Zdr$ z<~v}GQMteO?Z8C+z_sZGp}0W7c+RA{bR^DX@`==_>>codwdaQRq_+!^{^OqZLw>lA zt%~o^!3540sms&2I}m+2m^O4fk{~&uZ%XjcIS?Y90A`3fR=ctZ9g||;`to+!@I#(k zFx1JqbCk+DXSjA}Fbi5Q@YUMmp)9jUIx!<1KvL0n}*h+C2u4RXJ@yxaq` zYk9-rp$83KKeoEA-_Fy+59?$|7Bwl}UXnr8I~)T;eKPls$(P^Wd+I-sPGF$mQ2)RI z0=@UYkxq)A6a)?ICW#nzU#zdV|G=0((flkU;CGJKY(cKhgS6(OJo z0GuUaRycx-jjua(u`?AY&(j}JJCZ0>haSz4;Nnk}IeFKOIiHm>HQ;E_%}3W9_k_2H z{J1wnJ_aBLM~U2g*j2TndKJz)-J~6OFcWMw-X2K}+SdrvPH65V(X`-2*Eo1-(P;Pi z)opynBuz7ktTb3?J5d9qu^1_ZHe$b#~PMpI>UIzk~3{g1C&DHWT^4HNN zTKO9Fq`8V`CF!`KbT2(4uOram-!*0Sopwtv)AdngT!P}W4u-|2RunL|ed2}VK|buc zfDCxLkNI8KW4OcI3YT+uHcKqk$KcXz%Oqb6I^vpCKA_tO3yUfnoP_xgB@Nk~qTo29 zy&)2}mWY1tLyC3Wo?~6U=~E{QI_0*ot(qntxidVB(!E@wazy_O2T5t1yhS;aq#_Qr z>24_oR=qeos!#gGJc^CkLYMqh)DQ7P#?RM{P!l5sEqriG&4?x}$NBtfJxO1*7sz!` z#OonnsdD=P*>=to>4uPZfH;!tE_Uc5jW$|&>Q^&gb%h^qrV3}V*kIQX4No$r^H763 zKK9%l{ID!A&f;`E04tIozLbv=b*9ytuAB&-S0Hp7ce{WDyqEuo(=rUGfY6bpJO;Q z>U#8lE12C#V(9u&z4A4%^_K!+;)GNp81qV&+Y$fujGP_SFjepM>F+;*!0}CYzn9Q2 z?*P;{;kO=iKA&;0UDD@7y%airFqfb_R+=?C4St3GBdd}f3lTs0^sDi<8~*Ew=W+RS zM0>YyoT$Tc$uIqM0x3Ba%NMLkw?3wY+@|;7vRj-)X(Twsi$IoGK5@GMb)bkUH+)5f z^w$dz@yLFGjed{|+HMq!KA{yOBs&P);HzM&7K9}RC+z~c%h85~$bzd#U1VHR4l)s| zQEJ($(KB@2Bzl{xZ#`YV$Okh5L1bF_qvCC~5vbjJ%U(%8@2Au!c_UQ%a)|rU_2KH3 z1vh^E^sFj!~fIUZM$sTik%gr8;(NQUbLGZqUHtAM4W1P zi!@!cxC3OooI1AS=O&^ZO;(Rf+G@N!jc(PByR`|d7#mwyfy5Sg=2aKE!x#r7t80!? z;Prxh0%RMXzK!Jzto&HsfQX6^tberyGi7n7`^oUc-|y`PyuvvTbG90k_g;{a-LWye zenK2LGC|WBE3dm$Eg0`kgk;Xku;3NAKHWZs^rCpc?Ve}X3+iNp+T5HVY5Hqyyku~M zYeNxSAS-yj)B*FPg;+Ozh zH?;Tk=yLkPR-9f79TbcYvC8Kz%1ScPD4jf7hizED$WK7p4plbYaLO9EA?N?SSo{_M zK*L9(fBtnIEax=5L6xU0R9(yD@a;~``=$MyrvnvcR^uC#6lY=auEb>Vt6EWV`@Tz0 zqq-Q6PSXUmxmuA=9e-uq*`ph558O>-&)BVDr&bsbH^QPCY~JYF^?bK2L_;;TVUe4VxiB~7~ivzyPF`va@Aqg9C~&WwmdcUW~#TC87ex%=bq57;ZpJ)6K{jM!96 ztt?Lb>jCP?uY)eWzSy6?Q6YZZ^RsNGtHPHTPvIMM@%wCDV-f#3e|8;}oetgRk0fC! zwP-m(CjUv>$6%7 z&&Qg9vEEG)^*FnV93&6{vYf@}HVNn!t?aksgAhWjv1jdO9O#Niw&2>}t+F_Hh-@-B zD7PduqJC*aOoSru0Gqb6EXUot3wS20(i?xKW*bDD79mDis|i&3Xk}$&WWD;xTE~7$FIYC$!u}eDOI`!L$lSh-87I;QK=I_$3D@Y^0@#C zn2Mw89SX2REhU9>LlV|2YI^jL&}w`iS{3ND=%>$0fk7U{yZ-&_jMZQvtyV+6X8t)urxH?O|0Lsq&xNw`Hitor+(gd;8 z>O`kIEYJZW{+LfnuvYHz4bW)nIL}^by>E$W>k=dyi*IT(QrWkD4CV4|Z?1v$puRg= z^yh%RnX{v|&=P_ce)1wuH$XQQ~y%QLGij;SL7&zCv8$q1=CRXD9z+@19? zDdHw_3I?=JWWoVNb!+)QF%nwPF3M=u^UK7mQ`DbHqT;m8%QTQ%oRU5^$bF^a1Gf+I zLVdd%EeNW(I0S44BvGr8=Ie>=j$|(xEo(s|KtI{4wO)OGb|Xd5iXmcOYfB*o{^}Uv z6;kqj%g(RSKZMT458KO!TQBn*RBr^37y8lD;Kw!7W~iYE-f)((NO?^U9fKs`G95w# zUG0VFElf1z3JRvnvH@vD8lZ7ok!cRTBGre4fnR|O>?7%( znS4uAKFhSjj$E-rENe?bOjddbPGYMVVoPfowZ8(@N1>Bz^K&RiQ&l6y-?lapqrT0l zRPOF1ul7@gEX5{WWBmTeXqfyJgj8@90d^Oq&?OVNBp$K*Lpy?s3W0@FX>Z$eV-K5V zVLkn;$#C{sB%hH%3BV}D7hSt>0x(GQV=}GRyu!c>BmToCW`G~FDYDwCjF=jkSlKwu za3V^-`9|1~EB6&@@!`A!gV35yCsD%{3B@q0zf|?E0-fnOy`J`gbXY^ZtA7TUq6CSf zXH-3g*x^KQas_OVj-FM{5?+`TyTyE(m+=#u2MS2ys_mAV1#HlSOejW(xk=8dpEylE zq1JaKg)A>*Cwhb`9>>HZEP@gy;}ys5bBtvkVM@hO9ojSjZ!t7LAxL79N}7e|ZfYKT zYoH%wf^F{izNQNpsv1%-DTqa?jD2&H!6}0!uy$~xBIb#zsL8$OT(5gNTvxzQ^&HRS zjIPLSJRgdch5GcgFOAq|#gro|cj(eCQ70NMZOo&go&2yA90phHPL;P^eesBkr>>7+ zx%L~HgRZ>mj`AIs>D;LVm(7`McFuXT$w_I;EN9sQg!KefhMRWDg1*^s+TbcsIdeaa zp6F2o*%jmNik4NWr-M`xx&|wh)5V$%Hvb?s|lfVxV zNC(eMKh5hqdXdzeM)Gr2o~uAaP`P|tXlWI$wr;`emC2E-LI7bmesf}H@}Q30SnkrD zW+-`4;oLAX+s+ueHMTI{pSVrS#L~pq(5$({9M$+ZW9;a0=V|ddq-whwKqCdC1!=7` z>p1r!_C2^1334VV=J^uW+85`0-;c%IV?;7FCftKE+L{X-f?BN}O|pWq7JFRnuAyqG zluvF@+a!u^;IIHi2yE%2E!fEod`tpsR zbQG69H^Uw%N>WXLkXd%Y75M%HJU(#$R;|pgIX*1u0$(lTxIWlUPqi7$8*!#Kea6c%%5nauP%8b6Q+ z25Bb&^>5fQS~=b5Y>%{W-+qVFA}bzKr@q`#ooq0H{B!Skw^uH#0mY{`$y0$l5Bb+j z;7=N(LcYGrl{=f)%%AUo+EO2O9|NXkmU)4y#J#uq%%fL%C-0(`PGxlur_PdBlb5VH zpJCujh`)8itGpHPA?IbEoxAl%cn|~#0p;cO;`Z^?5Lj-4Q<88o4|gFCfhi75Bh^+jbE{lL}AlkuqF3r8b_ul~$fDd>xu{nGP3@<m5;gbmo_%V+%$bg@t8y^Z7g9y4!!OJj%E^FY=;?gQ!MFHy#E4tD+l) zZt>&wntnFa`f7F2`lQj#e)p1%JUM40++(K6c@Ox6`MGeAfI!bgUk3J)F%NS_fqchy zNUCS&cvm@sj%=c)x2No}H2nN`2{6-ce1aD~4U+1Xi<=offvTjP@gBx_>B)zStm5YA z0+pL_nU1Mv=~IR}nQYX@>V@i4oNAl=lipgyF?NO=o=%aoSJc)UQ5}jR@AQK5bM6)mUBye+Xj1*e25UOB3aYem+;A3rr+Zc*0pWrG z0s1&&`L*NF6qQ<1Cl*KckOsRTQc7nO3v?X?53B5&gqSR9pTi9AJV+;4p25(8o zB#j_o84;y36t$!`%RtiGaN6RObNW6j`Elb)CyiS)O!R^X%KEYz#q|NIYrCGIwtFX0 zl?Xo+jld`1Yhch!Cf4idMKavV$qpBA2B{;KiV>PasxxY_Ayxx9o%-{WA5OyN0|yqe zZ7@d70BOWJ57T%&eHm~U%+}+Bq4}jqbI^w=b#|JeipqH!A&uGm+r{acS}6#l{Xx;=i}DZN-8! zF1hz$)R&_v&zIpNY3KvG@CuK`K1UvBsTXW33|!G%?Xrk$h0PAPp z)^cS5X?XU;XxX8D)A%d@WI)3i?bhW2=?E)87O4~Vo*kbz)e?gyTASny`+TGxT$w_{ z5noO;mv=W=oVfwSBHzM&&XYlt)tB@(m&wdqhSO$0NT?1`6{7m5sa++a1W~O&84#x+ zuG`kXB3U%OQH-6eAJWx)ZbSC1gc}81z9t!SW=cWUHNK)+RdrYNOOEN8!5L&Uqo!bP z(f$L(aaa>JhB8FZnq)=B=S8Hcrx|H#J}YkF^V>8iN!R9}9Gg_rMhOu0T$s}9v06fJ zt#&*Cfn*6#R!8^#4k|+%9*wprjDa5KmMQ}Y!K@jIKxlBjX6a4@7|d!4mNR&ead;W{h|JNL>AnF9!x^|V5VCc4 zS$8PvRg^1X=N@S}ScBYXT^t|L#aY=DHlWHaM&Nz1)hI;xd#J;y>fPS~;UtQl%;MDh zS9Uno2+2c9xV#?bxy-XRLk5<-Es3*!eF)7uGl<^@)5`|c$6rE)%s(+Ln5@0gi#jgH z<(@|oiH_#%Fdyk;d-%7YqQpb5wFPwxUFKjal~x2lCPoIK2KA5c?3BhDXr=}j4~(nk zv^mqS7sZrrJDKrmGkl%{@(G<+^%p+c>yK1flkM_|7*id+19G~5AdV4(gUxKQc2~I; z#DM#*F@4cTcnMUnZl39bjyCqkJ^eCcPGZXM3d zh^ij}Ra;MP;4O&>kX~^#^&PTAa8Tki8jD4<(?BPiUW-kavRDB>`@{vowgx^gJ=GG` zykEKgzC8_G<=}x(hFW}Krn)O|b~%`40!kl9A$8``Sh+f7y$A67Y?WhI0Y_}xmYrda zQ1n+^cj8CQM3*lWYB26=-nwRJiP!Y!OFYhAka>J z6W5B&YiX7>Ra*qMEQ^OztLhlXXasahJ;0}-!LvF8CRCk_g@bnht+T-TS!>%OLApOG zW8IA*2rkFNHmcAEPAvT0junE$ql6DRL{n%_?1^I0<6V5oE~z1`sYIc%oCP5Vg9Z4Z zmlMAGeki3Mb}#3})oAfCp`^}PACPL!u9vOV5Lf*1*VF|MA0Mt)Y;KrpHJ?4<>9Mjs zRH2b8*q=?b>+0P_wxRnU*sfrxD~F~u&RT$YP$M?}DUU$PbEPV5&`n!>gFeqxLA0J6 z3OW{kM1ZVfZg2=;2Wi+dJ6*I!(t>_l$>3o<9vDZ(b`SuSYgaL8dS-T?c6GtWH=o?z zXwritrpG19D^f*U_)GV8=FPMHw3Q#%sXKou>Z%zy^+-?#4ra1RZwmxI)Fk@SOP8Pfhd7=LDvdU9Gf<}N$pIJy3)p^ay zL-dL66!p={6u|`k0KSkD+aHM`&e>7e!m4RmT3BJ_<(*J}3wip3$MC^sCBL2~Hs+j@_-fas@S{`q_B zHEs%W-}|{fWCIVsXBH49OB;Dor8pF9I>eIs4C$4g7*i3+cEU*`3BG!jKB`VB%Fxfp z6xxpEt^mI4Z-F`bCx}79_U3{|dq2QLZ|dTNsdP0rV?RQX>n%#jJr?zx zr&6n)`2}fT{h<6@?JXDi=q%^dd`mTihcrx8cK!A{Coot$6U5##e()~LMfjlY__vXr^Z_Gw3C?i^8@yEx87 zqF4Whc=JcY{%&h#E~fuD0nC3P-u&YPF#iFb`5SuIKge`UM9hqw%&dQ9d7XN|xuVV| zzT;m>ELp+8dz@uV_6{h3?o_W= zKuNotrF;B3=RIpSK}1Gy@sNaE6!g_t(Wy}AU-%G;d__&1KG{xAtr~s!021XB*;&I- zS5sP4G$IVW!RPkXcwck9i3+Jh4!Scj<^};@H@WDo{$&|v(s<+g5TBDt6fqyT9>|*f z!9m#C;^2AZz%yc7XFJP*b2;bc(1IhfW**= zi%_?OBiG}usLXvI5VGIZ&PA>OWtMc#J)57J(f(TP;>)+cQb~pth)l@53+)KT)j- zQp0M$y$DUj)TYPd2@IvJU>pqNHPaRUr;=<^Y_RG4hHu3#6R$$ zdgn96sY`$y?yr%f*hBOCme{6LZaeK*al*6?KT|@yMlv_VW_-an9NzTLSFe@Z?n>S6 zk-TEm{p9H#xBRO;>HyJBkHRJ{*mr)6Y`K|3u@ZGhe&={&=EhK4ZuSBB-EPO}!@PhD z2`|dpjtGeb`8Hmz_~+9T7NkOGo0?qDC%*&&OHeeJc0~34sNHC6a}P&Tph`##F9^ zY&_0}s!AeBNLo=^SK3?pQ}~S1g3^o<4)tnEBbSdu_g6EA&4FAGX_tgds-Mwxk#u2n zrlU4ArtwR#!jC!rF=*5)F`YU30d+aHW3bi`>IsG;*lhLYPgX1N!k4W0>e`Oeby|h; zbm`8cvi+h|CDYdXg=&#gcy1o!>H+Hn2j^K14`+N7^qzfYneJ7m+0!0h9(^(=Wp2wY zqF=TIKW_(Cp4~M^@xN`|N4Bq1GOX)px@UeJ<)QC@Dw$C;Un%P*!JJYk%8}Yk&T8HI{}*Lz!z!8DyMM zv8pedB2YDN!*M!~ZoK_w%7HGLozB&;AL7wu1&!W#a{Hx@FP@^)V&T{f;Lj4+#09A)mFF-e}`LbmCjpt0~}8S zE8ok4MOuT^$|_bn$TkL zR`BTf*U;Q~uD=$XzUWBVnA>RDxK}Qe>LgEoUo1WTc{F>EGl%UG!N)QegQke}sX%o` zAS{_R_W7Roy35PsZp9^tWrQ&E5$W+h9b}FFb%dtK=lbdri6B-l32JwJc#!GZ*yyY^ z@$mq8Z`mzmQjnUCi)u;5aH8j{j?dGk3KLmm{w(h8el%4B7mw>nq&h-VC}Q0gfuzX7 z%>)f5G~B{84dmz`HwfozQh5Y;6~d(y9ex5tECh-u?S=8i)7xeUzmZl>%Kb~OD}phE z&+DY}4kEqB(fF;Y`rI2bfzuD^(cbjuiw%)|RhI;Ny@yHFFi3YMcom-54-7D;$Vq+D%RXiU^r)6Mv6feFl+>!DySc;|Sj-QvT z@ASXe?=^-VG;UR6yB!Y5F6Kej=x-Emy-oEVf_-L)8f`VBl^ivdV8S8O!e*QLJjO$N z2(N_a{`eDVQiFvCsX=y$(QNReAS*1|UdyDrtihyg!SoeZ61J&^8N53w+ZHRYdzS0Q z8%1W*yC21q@ngEhcu(Lm{yGn%!@G_Ezt7vC%W2kPW%KE79gO<&!nz#BJ5yLyz zbw1|%BixyDMH*Pt{*UF=){@t#t-+-PygH}J>zz*s!QH>|>JQjU>%JU8ginyv!4Pjo z#Q6I~ZFY`Bn=U9Y1KtlmAQ* z+p~!H+;B;o5}h+8C73m3v^JYnpjKR$@N*b$_jKslY%P`705P@q=j0gE&tdej5_B{4 z!>>#d{@MzttPl><>MNh76^L2jM+HAbo|dS7ObpbbUia|!85rJI$G35LcdYls=xsiE zY1KCG+zV|bB$zPksCyZ@)UsaW86I053B}s4zp9MlbJah0HjgIS8{RHfrsA?n%}C9e zG}D5+VnQtlD~Eu1WXomm^yM&kTj|-iWVXTBW%jQSpOgo#-9VDZQ|*<)wm$_A z=YhH~@`W+B`sA6-U(snT0ejn%(D$duD?;ZdU3)L!(&gBrEJ&|UgB@Tm>FuZ#+!+`i zIo4B+jlA|%O%FqLW}_ItY^a9QF1qF$&WF|Qtx49DhQEZyuB9OvNnCLx~?5*s~vUxTYm-+>juui-Z%rmLy&YZboJ&eyG=*R^o zq}gdrb5DZziv_D5A@34xa%O)LPodz;l(OYLey?TPT2d#mkN8{VwVSo5Brk|QtC=aH z{8EHAILln^u`U@VLr2Tm=bz>BUdLMUlj}N|cZDIXeDsf1FD7k>txfBhoL*1hZ`4my zd^LEt1rHbB!Z(+H9Pbl=2bF;^EnO`P=noq(LY`&&M}7@_XwEgT;|~kpb?$?TzQ0!& z@R$z`-`NUn&1|>DQ#@S?9NNgSjEha|zY+~%A_~R#gD1lV)L#%zo&1KkEs-8yZ%+k%bq~}zzqSS1& zX}sw+xJcW~tS<4#^HQbTe3|}&?#o6LvQ61E#Ru7SmVr%T!rnUtJc{7QCt|0vPc7#^ zfKO!=%`io8zaD9H-H&3<+QH7HRu*rw^1|t<4{Da}%a?4+Z0Bj8{8SOQ9$u@6x)u5U zn#RqJ%>S%T8M{4=qF{W-bCg1wCj;qJMr>B7(oVIFQnj9i=Q0MU@*h zEfH&0%RLuoK0STJS)0FflgT|78}-@kNJC!i=TdPL!bht)7xRFedV}|osAASh9dcDw zHMzv4c`3Fx(~mfJEiGeld>i!1Wf>W90ZO7DgE_VkDlgqf`lXZPilj3t*mO$${SuWT zOShTfj@wGL!&@)ey3sWbBPA-T)UTlO6@G9X= zTT^`@^ECAyJOO;hyHlz}^vO8f^FiDsah)`1@Z#+R!(Ooy_DRC%)@+jnddAM9 zCGgj(FpbOMTS1Fku${!~ZLu}sPc4&jKMkX6&;(8xG!ZQjh=xB-g3}L2W{c)WIJ+7- z+qVYj5PvKJpG4e=QoDmBF>NRL8kfubWiM7cR$}7RC5Lws)zQVp4NOrzVe9gdXHpWC zO1weP9N{UK&-5*qIq2gFLSR6qbz^e%<%1%VkB7^QG*gH$M#|*RvtQOoqEp+^&fu+i z(1oLwu(=<4!l+`cT)+=YxWAT+O4nn2_7&kClVl!K`6|jtE82Ddm48R7qWWr(OU3yG zH#aCMEbK5PI};JUOd3OhH*f zct}S29wl|g6MRK0suuR0+hzrYW>E8kY5IB16}qOC?fXZw>}KvfEO$=9Li*@nvx<}` zYXx;IJ13Wx9uoAOOR*OkF!%u}=0qeRlFY=+FjSvz_NQD2E#_wGFQCSTZ9P|oj70GvhaWW1 z8IlW+v;KH4SPkb1wLcXjRQO&7^R(U7<|1Y{C{dvR-I!e3J}pg1*+OcIYHp$I~e9R{DCyP4RA1LHiU^K(TkV<(Q=?5?Z*11Ws-N~sQw zBGXE+U$%ts?KZ?LvSLaVa&F_a_@|%slD9u)%eU3|o<5qt=RUktCzEDl^MggYp@0ri%c6AQB<2K86X%pYy_RE^ zo&HBH2b%<2Q$@)l726W#LdMX{;#ks;vXch25lg?HiaeM$dnmVq6)a#ZD8PJCSzf6bGq6cHX5A*CkV_LS z>eV#S(svr;kRB?-R&|z$$j4J8K^ksIp|{Sku(C`rKl!Cr)caLO(5%D>CoK(gq3>x= zRMttYsJ&V8M|BSMT$Oyk{2$8RF}jkkUH9&EY?~b$D|W}WZQD-Aww;b`+qP|^ zWAmi{d!PO6J>KU%XPh-gt(vG=npb_P-&Oa$dRVBu)+@y3>&Sp;Y&W8bjqD4hdM!gE zFgS0+??i!bQrCwWT-(2C&M2WA+>z*>zc~|OTf&=urUpXI?;(H0T;f_1eY{>U?G25In8#xN_m>As~mfc6z8RPb85ie!)~%tQ7Yx$X4JRYb9VP$d!6$ zQokrFZUYINg*$3O{M6_KI1gKfkmTNd(Uk#M*pw17Xn;V9l=}l>?Zg$t88nemCajr5 z4x=)+EksVQ($Q(RRutzj29{(Hu1|J3TEe~egPat3WFfLn?^9*ofUO))K@ylE2PiR4 z6b|a6niZ*6VYF*-t)&sitncnCJn|b*`9iDWLhAGS%&BS#LZUL@FiTglKde#{Nl4jF z%jLweq2WBT#9y!gF0Qfw4hh*Q#xc?<#?=frpVW^s!Ij*u(87bbpVE+$izGm+& zPJDkPWwKy{W?W^NCQ@*>(PboSt059F-$|2*+&WUe|uY)Kms+9yGJqApHq*B>YL z!bTE*Tu-Y_UzOV1IN4EnDk^E}&AkwdQ5KbdRua{}e=6Gg)reEW5m#Bnk=w&znAZ=D ze_b0Gea8TWe?1x)?T8u}Jq(qd)6l0wXPV344o!vCZ~sQwrGHeKJJhwRvoi!^Z{k)= zq?l7!qnF7jFX2ZlxEM!&9iN!*FBmFFio{CMcS$K9x}=EHKolrw9z!Zl_=HWWy-TRo zA5rIw^z+3YM@@`O8_BNUO=vk2y{n_y7}nc8M!p@YWNuGBliUn;H20I3&}SYc7<$Q* zE7XZiJ@5=I-a6lws3P3%wicDPFg8H*`x7RAn)Cjd2nXa6xLj*EH}+&vqFpFKE`fF# z-L2#P$^eWW$TL{#JY_$7;y4CBHvk-8Bj*@PiJQ+Un()S4-ZxpKK*#^?Koq_IlHPpJ z$f8g3(tdwufcai*UEew6c~?Gq&Sbt(`w*W_okG+-Cdqwoa5=@^yqnA-w$Q)gZm$lZ z57+1;9}S`omFYYA5_4ZUKr>np#tA+&XUvRfmpSetY)X?&ym7T)hB}U7$u3l-LBRU0 z6K7=$GV}dO&@hiYJx6YFz_J7D$nV&vG>V|!8-K#kx>%&JXK}Ef+QYEw!>Qa zz0y@8wy-}1Y05Z=YPcO=_e|gvPJtLC)3DcRwaIpN+KkNc#ETTrniL{G!|*0S?W!=25KEKO*=?3n$>^4*C$uh8c#aN zKuSE_&VMb!;GK9}goMnJ!}z1of{VOoLV0M~H3du#&En4!(`XhYpr1;VzN~E}a<~-} zeSnmk8jM4AF|;)4MBiZqYrqi#K2#jkinT6>eT36-ec-L+NnLW308!JbGXn3hISZBA zUo@hw79VBPd!baI{_M52LjYi1r77077KMkvC>u-1{mDt#7?zrutO#&`SXQY#MxvbTIV26HOMnl z_QGUs$a`3B81ko8KjWB{;n-DB#cFU)^=I<>ttAI-Uj;u(r5O@(OZf$TW_+Bw5h+HX-Y{&h*_#dRSSILq!ZNyI^>^+s(6X0W|t??kUQ6jh&_e zx7Fm8k5{OKJmHy*LSk}-=c$8wM-rTCmp#Pg8>c)W10z_Tr}#bk+V*614nH?WezYgd zjST=wSvv_=E};&WBiMGOPjoT0^|ugF^OA*T4|a)@&V)xd@SKrAQnup%Fvlqk5RZ|( zUa3Et2N+E(t7R@*)np1%1y8#EK~z?OIl$0I?7-qxDaBKm6u?r_=PL7#OFg|&Zz%I1 zF3k$=Y%VxN!j7MlOuLF2H5=q4Q}c7m_vfzL%Ls7F0M4c!Y~#qNFz~LaCA)J&T#J;j zm1Jj$7m7&k?eon}cm!nRw39f?Tpkj6A>ZU$SQ%2p>j_v_gp^|rB|Lu5u>`v*#lP4d;T&7*P2a;^RkOT#1{yAVbQX%;%+)iBB zg=~^B&Z@kRzlR;32{!1vi-q9pjr`b9>89X)&c5|QCV9*0ef5iG2@uhBDe>@Ww{AP&L{A3U#QiJn8c1;ak=zKa z^F#Vxt-gtzU$VSPt7^l~0wLk*!vh)e>p0dv1kOuT3T{grB`V}nohEUKqb|U?72D!x z%RKmO2v5ifK>i@c@{|77Mbs<#h7o$sy;k!8o3!S!HbANvG@(;{iN1;~H`>08w66_n z9*inJ#v`RdDEIETSTgpYOf~wf?vi8Uxbys|1fLl01RS=iou|b+hE1PW^d;eyZ&&Hw zKS=rJf><(CTO{Jl4T1ekxTJ@!IX9wlU&bjJEo;=est^-J|9)Vz@H^$)*$U1a172N}J?t z(V`I&uW+*1OMj~*VO@{@K1XzpQn}T@QMUG_D9+4Lw$i0&d%g>?mvINtb!|tUApCLs zC2lBwo{J+%XSU@fd6F94uUyU5Ys9LYz4-NlmRMZ;>sAh)yaTl z=1!4LU61`W5$5DUw~qMsl+u-s*A*G=n_N&G;LQZ`jSu{D2HZq^`|(jVaBJ*J5C5$a z9&D<|W~!%a?23>1tq@Fl?8-*z>Z3$?=beWwFrY|%r^AIR;Bm624fQGtrYmXZ59QMm z&XW>;J4qj1un_1&cywdFmU^adgWCsOw~c}XZ%hP;7u?H zf6TTPUYk3XuAQG%8$+xaxiSIcJx{9cAi{ed>2+LX)?8KNb<*?-0JxTuDY(c5 zbV#{;!tsv%UoYn%A7uhw9j_`Jt{xvd3Enzj9<4QgtiOI=Z}Z)Ha3Se!M6I6a{nUc= zR0yirB1dl=y^6GN2483&g3`EHgwn9zwx+Qh44uGR4oF&6{EiKK)dcW-w*cEY19(n+ z(@E6xhv@*Q(tb?5-1lw`S9^1>ANV>+$5&T^bQ1QdV_wYj$$*t3=4b>Rvxj8(U$Hmu z;RF~$j3UJ3)FCL3RgcONm79Zh!Qh_hk$fe&y&Bz)?V%B9gQ+w(3h$u!gnIYQ7A04ADgXej{o zv_Kxr?e&N!=HbeHZ@Xpnkr9+L_xMBr80P6~_ae9xVBWkCqT%TGA!zj^csPuMVe>mn zo~;MmIt!;n^8`eli4jyC4SJofGO6Miy+V+N$v#9=mOtj)eQyL#3Xc?(KlL2l?s0=M7WIQw}}&v?UQ0oSHI*MR*je>-M+G@HRu z`a$5l8TmXTjKFZ=NYHo~c7WlSuHg4P7_j*TS>TuZm;<0pm{iQX07*0}q^xf~1MqLufSY$^Hh%&0 z{TPw@H~jn`F8-IFv$C=O%fSHnYvB1$2ZN%Utr4BDjkTkok%NJ~nXRLZ{XbP{Ju4$R zLB78~DnTQ2J!K~aJ!^+A(~qT|i30)CSK(_6KfjHu1`PxK7m=r7VgV2^u(E&s0T=;V zbYhNrmSzTg)+Uxl1oTjJd=3Ui){cKme~NDBM3cyK+(+! z^%KP~A@Pfg#i-up#Cd;P25wM{Fv&V9iRNb0MhjOc4DTRUeY~-RW}?!`KGG5lj@F?LseBS^ z!&ACA^k*W4F6AdDUR~`z64=&J3nSeIh@7nz_Q}|2g@(;DvZe|!7pxt>3SwQrfa7<| zA`x97oaFZ6vpC#_Iu$cRM^gt47J7ODmM@ zLw^lB|M>*`Zw;~h723a%(SKP;80guVS^m4I4%{qUH5L+&)sJvG&J84P)|8QO)vlp= z_n%_Xr9F3-!vwy259pE*H|meX`dLAWg<^w+D69g(l*~bUNt%gWNLtes{ETvA3YsNd z#}wxzCXvM$H8h=tv+9!05##jL`<-O+r@~+;-}kxmb>r9L@X>k0l1Ej;1BZq^VIvs? zAi^KwbUTE%R5@WDsGH*3IM#Z)Y}WE03(_YpAKNKe$E9J`s4Y*(pHM(4S)0u5Hm3J& zU0+@85CnUo7z~kNt6zqYe=6qo>cG1PBdp;XVUYjlf09#gR-v2_N}ElnwQs3tn3H) z;5Xwfqq?!FeW|+7>(5ze#$WnBlDc27UO@xUw@t2aOs_`yt*QHv>XSwS`q zpmwz`wmHI-k6nRPeOk#iL1b}L*l^?XeqIm2Pk3BYMAi7Dy1LrOgdafgGg;JvjFSg< z!4857ZOs}_Sp?%;KjZ28Xj|W((CqM0mb7XzMB-x&Az-h*xm{76`-#oo2;Qvh%Pj*9 z1+e}`{{Y!avX87U>(}vbtD{xij0&Pb zS*4++12}D0g$XNP-o=Acq~$#g@Y}S2=?VQeI8!29aOJk5LdGc<*=ho*sXpm?m~-nw zh2-91C66C`W2;x#172{|QMKYI877lmi>RN+K)cc^)8*#0;M%w65QP)7vyC%i&$WOx3yCWpmEG`>Wcaa{ArH1msNFK+T^NM^Sq=J>jPrdDJAp4 z`?Sz9#olqJW|`Dd4tBfGdRS*T#Ze%a?q3esq%UI5{Fdn{%^Gzo=BO9S6}yctP^Jfb z6{8!gg-U>m^wy(4maUdZ%mSek6_V}n^*E0nm)=NwOALcZYp>lurBti*T(ZNp;OGY2 z^?T2h+mV5hKTcMzGpz>>vr^&?LQSy)u{mBv2ky=t9@&{L-+3lj5PBDQyiPVRq|}|4 z8hND1uPJ}<>K#|D{82x#T{&{&;EjYqL4$%5T0YR%Yqn7j%w(DwY_a^s!Vsh!Q~>S~j`3$c*yX?|QI)qL|S z4h6HKPg+ZV`5h$Oj7S6vKe_hzbsDL=c}WuERx1?SD5Jo&+5Ed4;KSw-*b06#=*Ck| z%MZu`FlFhpwWE5>m4v%;8<%F!%6TO%5(Kpw*!X}{&<3w4L8~wbHxX}JziI8uf&0bOW zBOMHlde1lK8G91ioC1Gl+06SSR=3VxYf=**QZg~*}zCP zd%UEvvEIjX;xsX6s8vI)#N1P0ic`DY+C1N86-KzjF{%sJJ-^%We zHB>}hN;JSAjblFA=iyG5ezCFom;ggOm~B`bsHI2?`a_(hLwPmf8&$%ZS57Dp{+eZs zNJ$Rw{B%ds?7p@{6owJa1g_=G>;?_Y*7(%~MSJXylwxj5FfosG%jJBGQg;zFnaKH_|)? z8$?m1MEe?5)#AHXG&8$$o|2G37xG9uCLfi! zd^l*ad~mkFGse2P={6m|c)+xZSvgp<5x{=+Z|{SPV5{Ep#f7_Lv*m32-7;C{#i_xf z1r};aOWZraEZO_9XWYpns7pR5 z$@OM5$+P`U_Bj0K6!7!NFSH_3>#j4}B&x>Z{COa^YGoRR_%U6Y z;i=)%yHrL?Fsgk#+U|Ey*TQensJg#^+@YGgnl_;(CMNC^p~G@FH)Yii)%{xTEdpO! z-`3?_Y8aMy%n;a^K=rVZQ7V{3*1d zFk8->tli6=iAyp@>34kQ!yGbNrx-HS3y+`yunenG8YD%;MI;-(MMhMOgpe6=QS#D2 z@7?@RgBXTXlRc1DBQVB3S{Eue*}tv5s(*v8wG|wsi!s*wIjHOwPE8It9DZtji=uA- zvY$PNPoVsiNqo%?p39YJ9Ti&m z{pE62t96GHUUKUp#M&#mtWASSfp{=k(f66e%;YY#I<4N7{G@hZDsNq_)W!!A>O|$K zH?56mDsRf_OPrDyZ=X}n%uc?=uLQ_>Fv7!Ab*h}6Xz3|)JIJ@W&ulT#h9 z(g(ZDr}E#h#W%t-M-^l7L_Z_|?D1UDP+_KgrCpr7tk5p!LUO8cZ&Ul&szTVaK8Yg^ zBfOngf;VGRZv+b>#VnEV3RX$Iz^74f^52S9TKbIvbPQki(r|YDqNyYu;=^UbvN@QR z%Y?nNgQr0Ib@`~Jq`ejUH*a@SBh#;q7TSMQ8N_AeVZ=tqrhe0|?MN`DO$bvhb9&Z?rYmI5@mw;xs9oX}L^`_|yobH4 zzi2jPvLd{6y4*coh?T_b5o9d7y6+}L%*BK zB_Hk=s+H%Oj-ZA^MPeHAM80TD{)~$Gak$^zj%}F5TBC@aZDWv}u8McLG~le^wQ++Q zB*}ODLEr|-$jfyd8~4`0HT}4_mf44?YRG-14woeBHLU7(!F;S4?(;o%kR z?5twl+-PKIHR*!yE{L3u+U8<)Jn8v#`ElK{ziDMPScN?oAy57kq>D)G;xTuhzWQjR z`<$9TL=>d(mD;&9Xe$LLk2rTtr@_qWYuv3dEz?V3c2COV0e0neMdrn>yC^Ix(&9*l*oa(e$ z4>TH=K~FpmuXRf=3f0`<^GiOFP#zV!f^vM<0KeH`q6!aM!2DNrjs|J|QJ8q}l<34rWI~^N<*yy+FdMacNG=-oyIIXm(L>4m zu@k2-E`Khm+5L3hC|-FQRhSWI;~Rm~&!_#9{goXJ0|O8JBM_Av`J0JuxJRppKU*=I zq8Ia%#9Pwd^zZwjMfjZTTXp&0?#sU)%W})=GNz6n`sMO#z*(r2E6Ejc$Oi<6UFjp5 z3#Itw3AyG#&;VwbYn-9ihvjJu>LMMrY8Or#Cfc%VBcF3C(dGJG~p zuUN)S8iP8rl#SIbmphK;{n1n;H<{BLCzbeVVhnWb%0-)jG6@mnD2HGQe*YS=(y+hl zSK)Q0bN&a3WKB0=9qJe8e1Wtfb+uY9@SH#h_XzS)d^8FCE`s$lf(i@S=ehe%C4Se< z;2HU=Oh*8?EtPd&zXYA-ve!^B`iEE25szCu6NM9>H{~N}OvAFiSg@mu9qj=R)l!m~ zl*1cq%hHxq$@=Z$dJGhSOy?i_i>(*AbIt`}gPSJfdThyrSNsgIEN*mMZ0z>}S;^p$ zCa@;DXZKmU_q8n;!#~!pq4vKZgFpE=oe2|Pol6zS4mxr4&C^GYN9|CIzM&jo6ogr5 zVm|AC#L;ej+HL#zzr^&NAj}d66K#kYBwN9X!c(FKp$e!oomYCcuI^rTOe)Fld3E_>y8S>`#en!Q(s(QbyGG( ztyty~c5{nGd$XX3ya%zA`z686_kBcP`00>^%Dozxh%FRMO^~^&8JDDwwMi_#ozd~; zP`6?G+z*W}-y7OlwK}O&S&jZK3{*z-Dg_k&dK0lh_cmkPZBw66)2A7=@&MjZwoVYHeGdyp1i%1{x+ zc8;Pu<;t`7jtV8E_~NH_z5z#Od_cHr!rMedq*I@wRZX_f=V7C7fA&j-)a4vs$S2(E zUS!Vf81FTy4S+{dD=xDjum!&cNYWynwfkj^*FxvI&9)J7yM9NwSvgFgs2Ss;aEAJw z$`PteH0iK6Pj=YUkrmN8ZbPsueIqDY7dm)vTG~?)`3}z;;Uj|5i?1t+hZmJ`Abmhb zG<6nsR_-KDuWrXC5_FJpJ>1fC`W>Yk46hmUXS?<~|JD$u6J*rntNUL27KCzI4lN0v zY_JfyUp1UW46w^dweKd9&YT{R8dqr_X)|opSv97;Z7Q4w0rHw78*JZlUf)TzsH^t} zuQYS-loJ~;mQWs?34g5XmnAPQ&^S7@gCn9kU~`B<_4hJ|lWG81iDWPdd2-`PHBeZ7 zo8vM>!EBS`GDvcM*ODG%0`}MLLD4WLPi)h!(sm4RrGpa>=QybQCeZxhOuDVZb%Ggl zdT#73TvgZ*J83XvzkdYiU`7Z&4)nJ1Ll$^e^OuxqDVJG>2s*=pC*H@ZG9lfP^~TPm z)!(bsE>LXb=Wb*d%dPieP_xry?iCvDxVSs$MGSeo(!7EV{>F$bNl_;daniPg@><-XEo*&@*H1~ zdu9T5@nOj|4naACf_nY=qHtgak-YVzi23)gF1TxKxe)LS7k8O&&r}g&vIK2yWLq|~ zMM3srXV89SSjL*1>F>mfCIZl);DZtverZC2?Cogf39h%uJm*L7EAmztIWpBID_+1V z$8HJK=yIXpZ4~sYsqXfux{9jg5c7Y4XgrJ3BSOQ!1P4FLoeJj?x5nEuqe%y(IDKB_ zF;mcyQwyNTlW-wL3O(3AmhSo2=-MWnKLLMa?(Eq5IR?Bjd=h|$6Qbco-0I50BozOu zZ?%%4MuLrtXSG`POpRR^2L<3^Zem9`T+HawBbbCjOd|!0g}}gz5H?j8zzFH@YZD-r zYHwf48Zzfn;13maY#3r>VNu>& zsso6MmHe2Py- zosg18?3fa2Bg4Zl3F^0T;ciY$i^H0sZ$P%%VE}7Fp#3h8jfoogqa8=L-q*8Kk3cO(+Ig5-0@n2~+^gna-aoIq3$h!8waeb6zL?bZwxPe3R zN@jb#RAT2m<(FT~KQ3Tw734fOAa|9em^|21%P#=(RZ4nmGrfY;9WxZ_ymqL)3DB1=qZ z%7@vus65=(Y0vNuHo@3v0r+Zz%;g&56|O0dxf+Lcfc`RS)Q)dU%I_4{xVtrC$I3+O zdEdO`-K3Qi0}LOp$_t$3N`sJpA+qyE+XyCyBL%LAKLdJQghH0IP?YClX9YHEWMHd0 z13ipnwa5 z6e^~=9tWdQEfFr`GL?i%k$P!l&AfJaV_2O*T7s7Z(CG?CCf*aIJ5tS~4VCEWKz68i zyXsz+e2J4Q(wZW9@q-pQcq+)=B$0x_d3WuCO+HT5L6b`z=Mj;3SQciJgOueyYH{TR zZ_G?|WS*FjMlbCNha^l%#}2G$4j=kn+G37aIml9ugAZ3n3<>knT#Wu?#?vhRvC(qx z7(-jUcOS8j1H9Unj_$O0o#b~qKc@mepktwf=`z}MpC&lNZkI00?LJODQ*V=xme{5$ z+}a+|EspO#od2x#u8}{uFBa?}&06IZ@i&P#v3VdR7as(Mw|^2&a_mrl)XndEzBdR> zW_Ku`;<(;Vmyzk9uKY%{{ZQ(=J0B_1rqMhvxIR&t1GF!ijVn~R?gke~-@l@swVytQ zkG0Po%S&`M4MNUgqz<0!nMt!n*=n*^;^DL5aa-&52O)62n$V^k}aBmWg$j! zIUHj8GL@xH<(s%y$UN{;NQO#DA3FbFn%m%Of{4EpwC|Lqp{uy!h<1x&#^>~uti=iN$ zM656Qg3ieqNAT>ucr)AjUj5Q(lj`jry<+l%Zue%&gO~1{WX{zVN2hQt-0+M{M|5XJM~KcS+hF=gHS>n1{+1byW6Q_Z3~bXGe0K_n=HiW+bd}^a z3lWQ|ipfOzk36U%rMw1~y ziiY-6?a7X03I25F&tOD?H!yC!<297gJ#5C@&$tFL*zNULj-SFvqS!@O3zdQ% z`300sxjFjpfZbn)^%rZgu(C1z3z)M03wHe%#`_mA`xovN_z&DGX{K*vujgoHWBnKT z((v0@8va}E%f!Y&K*Pw&LcqXC&q%;P&&c@yjD5ex{QqFzf4->yAIOgFUsv&;$c~Yo z`QPxm|4!(%Vn?j|2oQoUxj={R5HK^eYN-pPsh_8XoL;}dMJVKB5lO;%zXBvz#kqYt z)jsr6MoJIoRgr5|cuUc~Uq&wA67eGI@ljUftR~MsU#|MqMfoh9@k-GNET{m7%Y3+ zBjUOO9#?>-;%Q1ynaxu)i@IGNpvn<)_l2~QVah+y<2~Xu-S1bPQz#8e5z>_~*=5={ z2&$02Os&kr9mI{#r}y{W325MF)3o=#sY|aXZRecx++fm2I(pm`NrhzvimVf|WzD;1+h4H__nV zNs9enxBb7w^M7E#|3?k|dl=02Uoe=J`3v~6un;gavk)+{vH!DXVfYW=%l1`g{DQ%M z`~EI}A@F}d;lBWxo`4kqfcm@sXYAK@{{{^IeGdL782+oN{{e;>|G%*X82|6F1po}} z{{swfc$(>=EX7`xU1Uix=AGb8l;|0|GwseZ@Dl+6g0X%;0(}QV5CjH`oc1+5<44-Y zUI8=k?;vOC#ML+>iQ22a)-^=q)Yg!;tqo1a_|+rkIUpVpKY@-PmhAMlQhcw}m4z8e z|KQ!W^>}7c(zaEma#^aPR8^`i@!rv<9uf+JkR&RV8OhE2+E?W*3GuAL-@RJjrlZ-u z*oiQg7eN1+*I*)YB=G5Y0LtI2$M4w3$x&$)NQrzXWfhP>V{Tz)sm=Ik0ve!*JHT?- z@MBx~SsnLqtH;w?!{n10>GMaUQly%FPF`Ed%;)GTzAoMx0jnd6_MF1tJwpKXWl#I^ z!t%<^a~`kR;2Xh@!OpCU&JSbzSCAjrYz6H_O$9{{Ie)5jd6E&(>>#$I?NjMXlx|?g z%<4Hhe)O3FOw?U_(v0djGiY5JP12T*(1F=|)=wCXC)2pe=(>K>D>5~)Y07iheE8K; zq0th4@@l5Fg=Ef~q9H?{ z9ID}x*bHddKN_ao*jJd2PamOLJ}rXK@Ma<&f6-WJ&h8%d-YM6w|nFE_BDf zKoYWMSciT98GTtZj*mq;f)n%xy(YPLQ}4;y|vU{Z9u-nb7WTtx{6$b{+IU2dakS< z-$!{WW8o2)!*}mwsco86V}l^RsyTDEB%nCD!5_+~CPm@=P6pMK%c=@7bjmHOl+ZV2 zehW3t%jARC0}~L7^Rlwl477v&PcWX$g}w%MkPI4hJqe1E6oHWK%^}qCtq@_?jEQ{L zD3;nP(I;(`{&EZ-h*DLBX4YU6DGbOEy09FSM)mqi?d~pXJ*5~?h*8*#NubFMhA8{- zdziwKSPZDysORi(bxGf(=<7-=*(MP>)K1V$)EAa!=>O*-Euwp!nPLT1YfHJ4v!ZC?RLG=Gx~IX zHrZx-NOS$BYox>_W9GE*qR3lD+7{4k%z=*r{{h}}0>b-ZOPS9AG$VcV=}$hwR!0qY zb_P6pP$I03&!visQU*T=$C8zXv5bfEyxp@$I@gm$Nz58LZ-87xn#H>xskhl3>cPf93! zd6~*B;mUdf8M%2nB4^pjFLGdSh^Vff||@RlMM zt>S7a1o%^LaK;eI zHPj&!@jn4(VPMaJ@*=(WuyqOwf<(55|zWkm|%H!J{a-ae)WZ~V3CN> zBZA*mGsemLBUFyuW<#-cq;E?sCrAdU;s$p4ylfYO{KfZr1pProItisw(2~#~@JgXk zeBp90P~A|>D5t@rCE^IjtyIV(K~$LVVXTXF1Z(87*N1|& zUt9N();ska-W|AB1Dlo>c>BK9Q7a>IXN4QxPlYy{$&%;&MExCym>4lT>pp%=(Rsuk z8Uv(0D)()IHS;^a-U~5|=p2P`;I+93qp1jzUUh(iL_RS~FntFU_HTN3Tr#MUe3;1m zWSF>62F9$t-#%G5HI_2A=Pl_YDkM6^L6ZV;ls1g>O?;L}c0RF6hw-5wL}%Rj`GG6SN330nwn` z9n=l{PN%YcK&e^Q?KGUb{jHqG#{xgpzZXd36qr0t|6z(7{5d)yF)UY}efXEG4~hUU z|EotmpVq$dNZN^`x^IdUb=gvSg=OQKr}?gfSyqpx0gJhoUyrG2h%vx@oKbku%;;X- zOCaIfa>L?`C0jZy(F(#;P>v<}R8Yko;lWNd!X&aN8;)~g@a=rQF3lKn`8G9j?3<(lgmy^BLSo!f*Y_hykg z2|D}pf!TAqrnxsw^NSc}Wc=Ex>Z;!jy984btk76QGYCZz*_ffHZi8r{0Js^@e$YJH zkmldRpzY9urVr)N!kP#!Ju%Q=TJ+m~cJ7DGp;dlC7@J;xBc%u}|JAr6?eeaMb zz8is9d_mqPGX^wRVu_k#>I%%qK3Oa-t0ao=#G=*6WRaFXWZ}fBM~Oj^6su2?zQuKC zZHLC`Mp?&c{8m@Fl{r}2n5NS4+CyHm-k@T=Y(WlNnOcQ1p?hfq-g|6;hFTwQG}yeR zCMnR<1Rcg_9>(WfNe&H`B+Ha<`JK&^i7Z9RI+W{{79U$jds++KTQ53K_yjuG5A}V< zgw0WtxU>%0gIN5@H+7mGIX~4Wv?4w{*kxHA&3w5L)r4>Kczw1Rmn=SINYaX4gk0_W zfoy4cIjCR3?ayRLXKdOlPuKSxo6ER^^3A?e3aDLV_7ZcnO#Eu2=Pb{{UbRM7k8(WQfYzZuuLe zlPH>bERb16BqLH&`jKlkZ+Ns|-8mX^801V&^|33fvTnwiY)7uSYE~r;gc1xeN-n8B zN)~~fpS_u(xaeFy;J0IHC2SafD6{5yMh%ATDiqL9xv<+nOupFXg~`{04x7xg<3%2* z#P^${+F!a`lM^%A&-(YqPw!jbGJN0BH9>W_j%a-t={`(JZ^?X5M>uVx(3u+YeFO`T zio6S>As7Q?b7XAN8Aaw00@>AAWCZ4o_6GUsvHa?OU_ka@c%cRU{BnyPE6x8*IsHcY zZWLNm7MG3c{9?;~l$eBKULx%R)stE(|F{$RqB}S)AmKlkUD0*R8J=#v`b%MMw}ut( zmz`PledpSR&U(Ge=VsvmezbFY1LA5n>;g__iSgR3UoU9-gEcNkD%t1r@#y68tW@}| z0Cdwj)>i~|#_x{W2hDggW_Vsg}nR%DIT>#!@-;c!jD zd2n3X+wHbJ(7ZRjJal&+IV;d^n;>tex7ut+fpgjz550(Cz5`{mr*A&JP177KP`{WV zhZ;}YWm5xmuF+Sg<>+7vos@P1HN*JYyCdB6=AlhG==TGG=bSNStl{fR%(3#nVJrN#zV&K8N=(qjx@cTUxu7R$5kUYhB$Zvd) zfj7YoP~c-pg(%z#%Aw>B#m^BDXztc|`eDlRs%WhRAI;@<*Y6KCRS~P>+p(__ zK=vFbApv2+1f`txD$Nw{WgpIRTaK!)tjUN3bu?2$OtMzEkeF*bo|0Pq6$-|{Wyoue zib|rO!Qs-?dh!&Mn}vaje1fVi?&iUGJs&P_T$+f%tTWi8@Z=l@Nzvp!Mv^D~D<4;? zvW2kDe5n!F_6ja&vY;8OxEX35h-7W|{;mR6PArFzqlv)D8wt!taYM5L^yt-jqvW)i z6VSuefJ!#+^?uk!Q{uxuD3$bu*U^RzY<46I7#lyLtB*`AM`&@xZAC z=KGjCOu3F@?#f)S`KC;a9BN-Lx0MSDEEtZh%-~NjgAtzym<3zV26!Iwr55t+`Cc!{2uQ>vE@G!@!9E~2S|~ac zGXfQ07Fb)X=HI@zSZqbUdayVP-8`^&7Qf|zMVRP+0~Lw@Gr$Tm5tw}|3&kS9BFCQV z4gnKpwoM}4#lpxv=0>rpBHcKa2{Y(Z)DlEG3vn-G(ycPGwB7Po3<`>EdbBW);Z+s` z<;b1EkP;j^6U4R9b^5Y=nW{?ZBshtY5|Cmr_ryTzlXjmgMosbvw4_2|hNXZlEIRTj zaBz>``8sidsNLx7{1gjlm0pM}=u&twCiSjr19s~Mvmlw#ADdogg5&fz=KqS>mO8;A z5hNV!k^9?#F;aLyf-6!;7!4wM;oL_G&X(=xnGY}LwiWo>Jdh0AHV=6HY_2)@xI;Hg z*z`v#@W-)_4(B#I`1g)YqjC>HO{v2Fcr?gs`zsT{6l;#18hW!9KDDsm7kaWJX{;|BWf`|!OP zDNH*U-T8S%gqFo(e5IgZ1%0VDT4#L_Pi3}Q_{VIm1O^M;aZ6Ja7)c=-;?GLcxQwIDfy+c3vJCErDUnV@Im+Y>;CcdjF z!v&Y*OQ-+nO*y>0hCEc3bWYG`k_+oXQ(J#&h30!7mExB5#^A*9x>kb&S<14ix7uh! z+17N-)t}-KsL@c&qKtea{wAgz1DI6F!oVq}V~i+1K8aRFTTM6QIZ zm@)rI@Tg#Du8gA{9QYzPjKdvrcoEm-p+45_=ns{vu@5>nv5rc7hQzAKFxq57@f(Hj-Hmd+VA{^#kM51#>{w~C{ z$QTQdbVN3yxHx?nEW1+S5X>L?AR`b&!XemtA;xY*2t*Mx)Vl?FQmKW2njnc{dNcHG z962xPTBFCUv5TA^#g)?G6d?QREKz_HVxU?b^`kml<+8cNo$+BvjtUkFV)NUS0nz#M zD|g2%Cpqb%I@8x0Gzth{J_0^+DyUvl1YuJiG!P0JExZgSheQU_U0AWQ#C+EB*G;;LOQU)8=qz60^Wgug?meKQSh{f0 z14xi0f+Ue7N%8=b$RIFeK|m#^A*Vrd9u)}!f=Esxl93!Gg9r$M0+OSWa}JVU51wtbHP!$G=d@D3v?t+ z<=3BMZ0?mtg?iL$z2H|o#MKBaO+03f@K)_qO@h1gu&uQRZnxSQ@{>EnjoZ>lDw$^A=KLMieXw z&>AktSygNGHIFXd0Jc8SSmr*}U~A>$HZ7C&sFt?=(Oh3wSeJ?c)h7{yybJBnR{_Yk|PK%vciWbwNi?QGcz3yXz zx+XK5OR*(eb;9Ixyds)-qyjCIQqMWc8~Vwtl<3mV?(%$@?a@*bf(ywfRaSH7J@aJR z2$>cQIX5gEF2m0cl(VENDf(!@(C#6pf$dIdl-pLi^5TBu`;u-AQ!rKv?^sw%vUvLq zyrvbBL3k!}-`kZHovS5VG+ zDWL1x1|#i5X6cV6A%Np~NtY~0w@ zJ$JF40|k?j9+k@nT+qQ4hn*=KelGGlklf;Fx8svTGi+SK>WgWt7GSu9GoH=(} zrI`_-Qe?173s9T6^^wu`#S}d&J1;pH5!CkGWr;U3NAZiOUB10Rv@01kkD_G2_4Ea` zFN5wTD-0v0l=>eInWDX>8>;8R&QTUh?GI zdU)yh$mURE*zp|yD}oODg;ylEkbB>>r{t2xq}OAv2M=^T#CzMk)MqAKs?JJJ75+V8 z@2=1Wh#8f%Dg!PScqs4qLDwoB~Kxm#^kZsibpQ+&5eg@CD%>h>!q zFJhu8f(XnslC3lj2%DR>*)3#K}J zQJ)qp@{Q;75k=g}AoDj36_&ceq-<33`fx%2NMY8nutc$juhQ@FO^}TO6D61S3Qj1$YoJ>P^XTWv-OUqp>%xgwXk;{XwruM9G-0+% zUS)pr2Zx4B^KTt;<$a~ucgi3YX^+r;il-rm+cE+)5;xIqSM0|4(B9VhMun9P*PZ!B zPyZT|@f~!SXK1yoe>Yd_&wWqAlwG2~F4)J6<(%(O5KNWSX5pUmu+%J?xWF%k?J8R> zgqF>@U- zB)&zHIStC67WFzilJsWWWZyWvPukn(sWmk;Uxp9Hn-5_Vg=oGSWiR+#sx?cvy?J|I zLu@mp{)ubfF@avLp&;uFV_s4U!^ga!q$-&;zC-N(s!nfM$M#{^hZls4UEHq# zv$`a03)+15eDS&?Hx_RY9$o8sw~$JLht z%N*cqfm$)X9bDR6)oC9|-q6{V2b2<(U#7gW!{T5(?Vy0bZft9=?FS`_QAoK83>35! zc)tt|v44^$0g?>k^w_T7ienUQ^V4VEPxhuGJ*4K}7fNcERMx$_t&Fk=Z9 z-n>TN*4caEtPwhB1xW&r=s;l$Tkik{Lqt!)bK0+UhPfrxfjgshDuq=a^p@=R*LN89 zUhTiyd3A98ng<^?We*7Zi#NZAP$&E;rqjU??)fwh9Zljfhzx z)+|rP8kX!xa`4f_ytlv+-HDvo?0^2{RXy#X`^QunYb-&A{Md*wB0>+3zZwb%a!)un zLmqXibp(W@YCNu-5K!fP7!3nD@*TArMB6q`_{Yqfghf?+D+|ZbN-xOag zJI{H1Ow6RwdyzhxC#Ja-WaPIQc(S!{?s(kydRPFx82|n8#tk&(tHbHUB!`AQ-Tg&= zKaSMspxNxXAm=mto@s0t0Uf$^crN|QqyeGHrY7B$!&%B`i1<+>^Yi;eB2?Nkfo-h< zUWi6fFYRaiGyLf>f{)Catni4JwnLFpW!KZ>T~ zd}RV$?82wRhShP0jX&b~LurboBS>ySU)ZUe;q>Cwksvtx*a&Rx9di@om#t1yM~IfT z(|v*iUiq0UNB1hxDhWHJWBZ5RVGAVrb`$?wSltQMkHgT-ea#t3#z{#Dx4%eFuln7~ z%Zd8Z*w1Z)>kxyQ9c^>ZooW>eKWh?S{j_)muBcx#C>wn5t!wpKY*5v(=KusAm!+Vo zt937}dWmb-CDHIKj}T%1Y109$PZ=OS8z>FiRkx>4d!Bi#_eG(8wmR2Zm&bOw_*^c* zlHn)udnT>6oP~vaqz@j%Jbg<(sZ8liXb=yw2=;1wA8nm?S=ot|o9KG@cLl26rZ>!9 zS~bqu(^jz@pP?zz1Ta_&s&WjRRD#%E9eaF~@nZD_m6s)vbabuCV9H*p3NA$zm<|}%Ot~X_%?!5ga}C({>D)VILMGn=l%-Ecv8t{TT>HWu1QJdC zK55Wnu@e*@HABt(b~S6&@uNXgVCfGWqptcNf$jStCr?a=RKq$_olibM_3dlTjKNJ< zo)UzYsPV04c%YrmZ%#aIxnnW|D5xQ|>KoV9V{Pv4j0TTbxK*d@2j)bD%BAq2Y=gIJ zw4_#d9B8A@!oZ?(hjpD;*vPOb=*B+fp^m3^_$M{TJk`iB85`1Xez#s;wJuUk zvcIWI{_(1~A@ED>m3x&^;5zu=2$^}A+k%uWsn$YM*o_}N_-FE@O$wyM3r)Q@;4g8G zotR$Y#0aau#Hki;nvS8rc*7Xs{F(#bRG4Y*QG9ymnVE;U!7|;; z_1VAe2*w2f%-XDJwyT@-NE-g{BsW_4Q z2D#Z$Fd(GFg!gH4vPOZy*VG~RB=JP^Q1!4v=j*q&RnML1vSqQ1A(may9q$b7*p5ty z^~A`15^1^|=1y&GfBNSGJbZMWNo8q#bX;X=taMIg&9NjcBaUFYaI=;MyG6D4hjvn{ zL?fU?lCF_i_XY70GDRP+$<3J8EtLh-pxf-Wsa|gLS z#n*Yxe6ITJi}crzwChMOn)6Ac_Ol~Cz1v?=pAM46q#Na5+9p7E%`XY63SO0AxBQl` zWASE-6=L#|rGPZMo-DqPocnY+1WRqtR}_6@=smV^HdoVZzFFdP*KcpUuV()ocSYim zX3)>?p26POwrKPLS8;?w=@pz_vzIEi_wktHb|dfAT9-0e(Chj=rIVW{`5f%GH{!Gg6nJ_z=TD2m3w%vsL^VqY>UU8-IFc;-}vf0kV z_EcpOGE-y&kt(qif*RqZA}w=yj5ieV@(^E7zD0+MbnMVffs>VDmc*_L_`@?G%3BeHjO*M z%)C1OCCo}LFFKZ8@UEYgkrFv-Jz~LLrFd=h=sp(ovN~@QG1d)iE8KTXO^mp3jwUr+ zIA;?D_G*@ut75qkk)!UTT{jJa80>55IGlu!{8+E{oREDJvnRfqgnLVo3WUTCBXqp~ z=qi@ir5BfOkw<&^To>bOBIA9o{94$C7bJYBaJ^J&Wh*9Uyyr zAuPLW`C??}`r?$8VQK%-9DYs(we{|ZQRPSz=Z5N%4dPi|;pMKC(s{UO^~QZ)i+^!%PYx)h|ff7KRSHvqN(_k`UX44ihQk zp<>bIdFQPcMm5M+>@^s|p1s|T*17dG>Kb{fYxbnptv-4vTZ$X-QwJ6_K6AXe4>XBo z9_|seChZ0_ZXVlih1lE98s$3}Ior*K@Hc6VRT3)Mj@d-K;)$w~u}(PQLfXW@S|~av z2*1-iHjWpLi_Qv>-CqO|ErIfKS!r3L^5bq>+_^HUVoV!evgxJDo>a}Pq)inj!uyVu zf#7u7EZ9%%<`yUSTm6b0j)ggu!^Oq1Xf8cbSI1%D_O?`0(u0&}#(|GFef|=fgPF|x z?LQ8!4;q=?DzG`R6FnU)j_qQuQeLsp$yRe0De$|Wl<@2r*Z?t~$2PWt|9a<>{Cp;5 zpSmmJmZ|(SvbCTbuNc(){NOAZK0hu;G5Ya6F21F%{PH>a>?~A`mYdLm!Eig}7kv`n)@O59@T_G8LtVgP^)`;ItH5(PwU|WWc=zH^A z>kLcSr6Xow`O)-`qW3$&iTzSMX6+C+KOB8eJZ~^z=~GN1Xx+(V^qURx^#dKHQ3#>8TDT;6c4b~Mid{P@W+XlQ?j>oLCdYPd z!CrR_|5`YlDCne#IO7y6I)4Abo!mzI;B02?6U8J^)nwsNUdpn2Ba|7H zKIMfFj%uAy;5elaNUC6`;E&f)W{)3Mxv$|nWb}0n_aMr%LlrTB_DdOe>#v`q8dp(2 zZ(pQRS3HQ&uaUpy{Yl#iMXNaW9Pg=YK#dvhok#r^QKMCfoY)RrDmG(^Yrqx)+hUd9 zoyHVuj>lfCALbanWJ)-v?9e}htb^z*{2kdnJr3HdV(pX}zCDzz(@tOJ%Sbxu;GS4!x^|$${sBAxx zwJTFOJ`Zh9D*tn zx`-LoXupzmpKz5hW*_EBSC0jgq@=Avh1rzhtiHg$b)LE^=c<=b+_q@dx+fl}uLNN zCR{O-Kvh3xB zx-zBJn7)6!YgEf{oy9)TxLLqa2Ie5Q#!1NX6pj3BJlT7~8wq`hdt}7c$L^Hb9Iuen zaWBx!C?Vs+rkD9~`2N}cif&@-eA^kKB)4{9baJ2G{&YG&YsB{7a^F}^QRa(8vZ-p*mkZna)_)geWMw4};h-rESR z%#S@*`{8*29bu~i60Q88ad>!uXE2ki(B9r2Ws}wfbaaN0U0+AFL>gASt*S4ou2)kWfe*RnCTPmGTB4Gm6K$gFB+CFk(&S3&lAG}g4N>}@eODpI}xwTwk$Xbec{Y32&4bf4em!57- zaar4Z+u9oa+Uc;a9ukG5&>-#@oa~q9eDajc`+6;5p4*<=LHRd@#)>*O@~ikc8f8Vb zNZ5Y9v3o^1m|J|h*uBcdm~Hi4dhM}|xkSN4J-lcBtnx{DWR;uy9&*5;q@P|G!|~dQ?D`3}?Syw#%}+G*eAE?kp7(wh19;nMAf_}Q-N0A~sVCfYIYqhrG3 zQBlHLZ}+Ez_lI68_1yv9I*vGS%?JQfT-`u)!A$d>xkNEI@h)X*+Y?asnpoW|+cHoI z`KVtfS9+tQrlbyMCDe>I%ey3Y+b(0xEgc~H!$*#wM|B0V200LSWo#FaHn@YR_f$3| zlWsh!s0XZcw=(Dl@->|CM*?Q7WIt;31y$&hWha;hXZ*Esp8xzj--kkVFH5kea_c+Bn<96WUULD3auU8}-`%DnRWs{&BegK{Oyd|zjDS4${YV7)OarqJF>%5ZhP^)?s1Cs_}e>%Er<60PfJ$B&8^iVB@$xzCRR629Z@0C8j-#&<_PLC|KS2is;ULtszwM)T?Tk-}EW2$OO*7<4}^2Bn-$ImG{AsR<+9Lsy^1^uZs z${aBf(9Xx=vxHzC8Mw$?_KR(kntm{wSr$lOz6V|VO0bYYsoCXlQT2HyMZ0#=i?hP$ z{xzkjsaYjEDS9pCJvp@}=sb#O3Vv(p$V6q=dHp=0?9aF7+T6MhzHaT_)urkaUTxa0 z7?$Bx9G*5al_Xsf9C|2Yw&Z5T{Fi;PzggM=J&Wz@$97LM%>)#F#1`jcPkjOv)e)Hp z03h&I0;4B~as)=fH5B#U8sP`JbysG(zZaNZV@426rO7t@wR5OF1M$JGr?e8j9dn@6 zHT2EfbK2nfCYR3xwry@u1d1FdWn2Dm_mJGN?=lU2&`_K7ji7p?+q23vKU_97=ZlbK zr)m-P;I{nJjPFs|k|v=NSf4mvb1-f(%1MOy_V4ue$d3|#3NpTl#`=ERi+grJ)mXdb z9y&FmFxi?=uea+kJMq|kX2WI@*KI~LzvW9rFpC_EI1BI>CwYW?8)6rSpS0oQ$qo^7 z;~efeQP}y1Q3`Lh;u4PL?Tm9p_HD;i6N}BO#bVQF)?I?*9{+$d{J7(jgDKcoNw2A4 z->_|yPrepuN4VNV6^kN=Cf%3a-kQi#`P`QoAJ)20Ic9UT+t@RMCfB z`P~pSxmGQ@vA(h);Zl{gQ2BTa4~4|vzp`%mYVx$tA&XydY-%EAVMAA z!RwapbEnMocvokj1g~T2k%AtS`VhvSy7q-o4`$=|{>DvRZArb)h32&*Evw4;cN!(8 zcZyoP!GcsK8Ntn3_Bty@bh@8_cjRMq@8cF%#E5g_-!J9Pvplwq<=@ncJ&p^CZLB=0 zpG)N#g7O5lZ&n>GEyv~Q0a8XYDrGy8^X< zms-LdEB+E%cYVvrXE_OM7&a5KqnV|0@wL7681FJDnE+c!w30--vZo z*K_tCpjQ{bBMh2PKu8D*`5$mTq5oC(*4ux;`OKZHE&d~v4+0hfpnMn<9|lq-3>Wxs zk$gat{|w~2095@OV)Z9~D;WMi1@c9G3Lgbs3q0^72KH$g&5 zf%v)B%a2cSQAXzr?s~aIJ(kDGGhf{9REw{Y&J;&aP50Bcy!qTR-0qmPUP82djju)9 zD*Y%;Z(HH4)>f3-yi;7lLHQj++fKPI<=jEJo8GjHxc$-6H3`bOq2VBS81>#R(pzO_ z#`hIEz?O#k9_32Ka*Oc5;rM5xQQKQ=D~CPVb0(f*+0ke$#t7kCEJ)QDhvgP~hg!0+ zE%K0i_X-AV8jYw;R?qcpxd0-hi7(JB^_1IhJJ$xEJ$Ed_*V`rGB z+6;BHZ!QY6ZlZG{@k5?a)lpXB)v+k2xR-v|ppEc#ZT0+Nbu`3~d^**$(A-e~T zpu@ANrd@YprcB4myG! z&*;aV;kojhlKAkP(l2Wt4GF5DgQ|*mVehz;PD|o48)FVvBfQIY-AhpoXt>@{_S+Bm zsf~6%M~mH(yqPuLVYw+8k252Bq+4jt_J4?Ve|$NG+IBqn_@5%+za*gjfAskO2t0%W zl(c`d(82((#{dj5jI)>m2I2uD!<-8Opu~Sbg&6t8=fCS=t^=S%Ld;PZxQ01iwE3s) zFGmb`@dDKNv(3dlF6u%+KY@#Y8~`!?>;nUG{JSsA5hMQx@QC@08OJ|z4Db{slr&_B3jF|iA@F_X|wcrU-UnyHOB(ghGJ+52OQf?vzr!v(l(Vree(^Pu?iaNFS5+hG8kn7j#edjVNh2kP^yn>b-;rv-iv zQ^VXD; zA_zC&mv=(BIs!M)1bC1El(ZwJccdr3j3z*E?PiTM*O0%>ugK&Aa3o7e@XG+~$iU5k zmtrvb{lY{1J2LzKkC93{IG|jd^#}zp4?zRq=>B=QfWBg!;QyT_7tMdsMBtaK{=b>g zFE(ud)#^gOm|X_tit!2nM-C8G1M!J5&IM8R-{-&j)y37n9qVU15WkkSi=DX`LJold zfxto_5D;M?s0>hqfg%XF4^S{N82E1)P!B2x0w~h~8Kz*aV`P}NKuE)YBc=#R1HKP{ z^j-8Wo)^EijxG}f$_HScp-?`!5a7iI|G4ypI=||7;p4vt0Knb;yVDc?-(C->{lDP$ z7lw zN(0CTdVr=-VPG`^2lEL7x`JUsd{7V!2wpfJOi0*(U;3ZWmPTTD3Vd72@2waVxa6GKqUx_2?pi^!~ef)WNL>p z{Vz1)cLdUriILggoc|b`018`JTk>0)I{@Slb{PGEk9?jc_I4~PV4>elfQge|J?y`F ztUq;Tf(XGcOaKQ+aQ@FT0VV|hWda!!V9NuPB@mUCz_jvno+0E{11$a1N%ell%ta(S zxZ2q=msTyzmo7@~X!%Uk9Sy!SLYe|0=CCP@FuKThT*z+Mf1XC4S< zqQYbnAnROY8cZe;{5gA?xgyQ~sR#Z&GXeF$nCt`4@Lv>6*7`dWVKNkE0u%(Ym5>n7 zmkj2XfUC#?0dh-LL=Xh5gakkWf`Sl$te+bszyShrVEp8tjT$_h%q<9kwTb{C(9_>v zOi%~}nEWl6e#(G(6$&f`Fkeg#f6IV#jPd?06A-|xG=7&ses3!X2D<;Po*)EJ=r@taH#Ed2YJ;a~{n8UMSjAOzUg z;CC4u_PY(>5a5yiRu2xWMgF)41oP9}zx#uOg)vLH-|h=M?B8Ti(4Y5(f`mbU>;9`P zFrx|oDFc-IqaGCYM?E+M{JS1dI0X8;9#A;!51T@T1^%!fFi`*;H2)qSToCy8rwsD@ zSl~jyr2Tt6A&BrFZGqYQkG5bCOYI2;TINrU7Na<_$ULu6qv oxGY#23`|`RSzx^)guo;yXBQJEmy2+R1KuJ?$i^n8h9LaE02+fFm;e9( literal 0 HcmV?d00001 From 0e146a9acdda6550243fa10b3e1c8e5a997b6440 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 26 Jan 2025 13:31:21 +0100 Subject: [PATCH 25/39] add cmd_vel_mux --- .../launch/penta_sim_full_rviz.launch.py | 8 +++++ scorpion_cmd_vel_mux/CMakeLists.txt | 35 +++++++++++++++++++ scorpion_cmd_vel_mux/README.md | 18 ++++++++++ .../config/cmd_vel_mux_params.yaml | 28 +++++++++++++++ .../launch/cmd_vel_mux.launch.py | 25 +++++++++++++ scorpion_cmd_vel_mux/package.xml | 30 ++++++++++++++++ 6 files changed, 144 insertions(+) create mode 100644 scorpion_cmd_vel_mux/CMakeLists.txt create mode 100644 scorpion_cmd_vel_mux/README.md create mode 100644 scorpion_cmd_vel_mux/config/cmd_vel_mux_params.yaml create mode 100644 scorpion_cmd_vel_mux/launch/cmd_vel_mux.launch.py create mode 100644 scorpion_cmd_vel_mux/package.xml diff --git a/penta_pod/launch/penta_sim_full_rviz.launch.py b/penta_pod/launch/penta_sim_full_rviz.launch.py index 2373075..b5a6667 100644 --- a/penta_pod/launch/penta_sim_full_rviz.launch.py +++ b/penta_pod/launch/penta_sim_full_rviz.launch.py @@ -6,6 +6,13 @@ import os def generate_launch_description(): + # Include scorption_cmd_vel_mux launcer + scorption_cmd_vel_mux_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource( + os.path.join(FindPackageShare('scorpion_cmd_vel_mux').find('scorpion_cmd_vel_mux'), 'launch', 'cmd_vel_mux.launch.py') + ) + ) + # Include RVIZ launch file rviz_penta_pod_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource( @@ -49,6 +56,7 @@ def generate_launch_description(): ) return LaunchDescription([ + scorption_cmd_vel_mux_launch, rviz_penta_pod_launch, penta_pod_launch, gait_generator_launch, diff --git a/scorpion_cmd_vel_mux/CMakeLists.txt b/scorpion_cmd_vel_mux/CMakeLists.txt new file mode 100644 index 0000000..d36babf --- /dev/null +++ b/scorpion_cmd_vel_mux/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 3.12) +project(scorpion_cmd_vel_mux) + +# Default to C++20 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 20) + set(CMAKE_CXX_STANDARD_REQUIRED ON) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Werror -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) + +############# +## Install ## +############# + +install(DIRECTORY + config + launch + DESTINATION share/${PROJECT_NAME} +) + +##############. +## Testing ## +############## + +if(BUILD_TESTING) +endif() + +ament_package() diff --git a/scorpion_cmd_vel_mux/README.md b/scorpion_cmd_vel_mux/README.md new file mode 100644 index 0000000..6b3b745 --- /dev/null +++ b/scorpion_cmd_vel_mux/README.md @@ -0,0 +1,18 @@ +# scorpion_cmd_vel_mux + +requires cmd_vel_mux + + +``` +git clone https://github.com/kobuki-base/cmd_vel_mux.git +``` + +Then, colcon build, + +Finally, launch the `scorpion_cmd_vel_mux` + +``` +ros2 launch scorpion_cmd_vel_mux cmd_vel_mux.launch.py +``` + + diff --git a/scorpion_cmd_vel_mux/config/cmd_vel_mux_params.yaml b/scorpion_cmd_vel_mux/config/cmd_vel_mux_params.yaml new file mode 100644 index 0000000..a41986b --- /dev/null +++ b/scorpion_cmd_vel_mux/config/cmd_vel_mux_params.yaml @@ -0,0 +1,28 @@ +scorpion_cmd_vel_mux: + ros__parameters: + subscribers: + joystick_teleop: + topic: "input/cmd_vel_teleop_joy" + timeout: 0.1 + priority: 9 + short_desc: "Remote control joystick" + keyboard_teleop: + topic: "input/cmd_vel_teleop_keyboard" + timeout: 0.1 + priority: 8 + short_desc: "Keyboard operation" + navigation_stack: + topic: "input/cmd_vel_nav2" + timeout: 0.5 + priority: 1 + short_desc: "Navigation stack controller" + web_application: + topic: "input/cmd_vel_teleop_web" + timeout: 0.3 + priority: 7 + short_desc: "Web application" + handheld_device: + topic: "cmd_vel_mux_input/cmd_vel_teleop_handheld_joy" + timeout: 0.3 + priority: 6 + short_desc: "handheld device teleoperation" diff --git a/scorpion_cmd_vel_mux/launch/cmd_vel_mux.launch.py b/scorpion_cmd_vel_mux/launch/cmd_vel_mux.launch.py new file mode 100644 index 0000000..03805c5 --- /dev/null +++ b/scorpion_cmd_vel_mux/launch/cmd_vel_mux.launch.py @@ -0,0 +1,25 @@ +import os + +import ament_index_python.packages +import launch +import launch_ros.actions + +import yaml + + +def generate_launch_description(): + share_dir = ament_index_python.packages.get_package_share_directory('scorpion_cmd_vel_mux') + params_file = os.path.join(share_dir, 'config', 'cmd_vel_mux_params.yaml') + with open(params_file, 'r') as f: + params = yaml.safe_load(f)['scorpion_cmd_vel_mux']['ros__parameters'] + + cmd_vel_mux_node = launch_ros.actions.Node( + package='cmd_vel_mux', + executable='cmd_vel_mux_node', + output='both', + parameters=[params], + # remappings={("/cmd_vel", "output/cmd_vel_ref"), # this is for the output topic + # ("input/cmd_vel_nav2", "/cmd_vel")} # this is for the input from nav2 + ) + + return launch.LaunchDescription([cmd_vel_mux_node]) diff --git a/scorpion_cmd_vel_mux/package.xml b/scorpion_cmd_vel_mux/package.xml new file mode 100644 index 0000000..390bb23 --- /dev/null +++ b/scorpion_cmd_vel_mux/package.xml @@ -0,0 +1,30 @@ + + + + scorpion_cmd_vel_mux + 0.0.0 + TODO: Package description + mohammad.safeea + TODO: License declaration + + ament_cmake + + rclcpp + std_msgs + geometry_msgs + + launch_testing + + cmd_vel_mux + slam_toolbox + nav2_bringup + nav2_simple_commander + + ament_lint_auto + ament_lint_common + ament_cmake_gtest + + + ament_cmake + + From 5174a2dff39f83fd663bf293d1a66618ee958e91 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Tue, 18 Mar 2025 12:58:34 +0100 Subject: [PATCH 26/39] publish only when necessary --- .../joints_aggregator/joints_aggregator.hpp | 3 + .../joints_aggregator/joints_aggregator.cpp | 59 ++++++++++++++++++- penta_description/config/general_config.yaml | 1 + 3 files changed, 60 insertions(+), 3 deletions(-) diff --git a/joints_aggregator/include/joints_aggregator/joints_aggregator.hpp b/joints_aggregator/include/joints_aggregator/joints_aggregator.hpp index f094cab..6cba46c 100644 --- a/joints_aggregator/include/joints_aggregator/joints_aggregator.hpp +++ b/joints_aggregator/include/joints_aggregator/joints_aggregator.hpp @@ -30,9 +30,12 @@ class JointsAggregator { std::mutex q_mutex_; std::vector q_; + std::vector previous_q_; int limbs_num_; std::vector joints_per_limb_; int update_interval_millis_; + int publish_on_startup_counter_ {0}; + bool publish_joints_only_on_value_change_{false}; auto get_parameters() -> bool; diff --git a/joints_aggregator/src/joints_aggregator/joints_aggregator.cpp b/joints_aggregator/src/joints_aggregator/joints_aggregator.cpp index 03fc18d..415fc75 100644 --- a/joints_aggregator/src/joints_aggregator/joints_aggregator.cpp +++ b/joints_aggregator/src/joints_aggregator/joints_aggregator.cpp @@ -33,6 +33,7 @@ JointsAggregator::JointsAggregator() RCLCPP_INFO(node_->get_logger(), "total joints count is %d", joints_count); this->q_ = std::vector(joints_count, 0.); + this->previous_q_ = std::vector(joints_count, 0.); joint_state_publisher_ = node_->create_publisher("joint_states", 10); @@ -61,7 +62,38 @@ JointsAggregator::JointsAggregator() msg.name = joints_states_names; msg.position = q_; } - joint_state_publisher_->publish(msg); + + // publish logic + auto force_publish_on_startup = [this]() -> bool { + constexpr long times_to_publish_on_startup = 1000; + if (publish_on_startup_counter_ < times_to_publish_on_startup) { + publish_on_startup_counter_++; + return true; + } + return false; + }; + + bool force_publish = !publish_joints_only_on_value_change_; + + auto check_joints_value_change = [this]() -> bool { + constexpr auto epsilon = 1e-10; + auto total_angular_change_squared = 0.0; + for (size_t i = 0; i < q_.size(); i++) { + auto value = q_[i] - previous_q_[i]; + total_angular_change_squared += (value * value); + } + return (total_angular_change_squared > epsilon); + }; + + if (force_publish_on_startup()) { + joint_state_publisher_->publish(msg); + } else if (force_publish || check_joints_value_change()) { + joint_state_publisher_->publish(msg); + } + + for (size_t i = 0; i < q_.size(); i++) { + previous_q_[i] = q_[i]; + } }); } @@ -73,9 +105,13 @@ void JointsAggregator::declare_parameters() { // joint_states publish rate (time interval) node_->declare_parameter( "joints_aggregator.joints_update_interval_millis"); + // publish only on value change + node_->declare_parameter( + "joints_aggregator.publish_joints_only_on_value_change"); } auto JointsAggregator::get_parameters() -> bool { + // load limbs_num if (node_->get_parameter("limbs_num", limbs_num_)) { RCLCPP_INFO_STREAM( node_->get_logger(), @@ -85,7 +121,7 @@ auto JointsAggregator::get_parameters() -> bool { "ERROR, can not load (limbs_num) parameter"); return false; } - + // load joints_per_limb vector if (node_->get_parameter("joints_per_limb", joints_per_limb_)) { std::string formatted_values = "["; for (auto &value : joints_per_limb_) @@ -99,6 +135,7 @@ auto JointsAggregator::get_parameters() -> bool { "ERROR, can not load (joints_per_limb) parameter"); return false; } + // sanity check if (joints_per_limb_.size() != static_cast(limbs_num_)) { RCLCPP_ERROR(node_->get_logger(), "ERROR, value of parameter (limbs_num) is not equal to the " @@ -110,7 +147,7 @@ auto JointsAggregator::get_parameters() -> bool { "comply with a value %d", limbs_num_); } - + // load joints_update_interval_millis if (!node_->get_parameter("joints_aggregator.joints_update_interval_millis", update_interval_millis_)) { RCLCPP_ERROR( @@ -132,6 +169,22 @@ auto JointsAggregator::get_parameters() -> bool { auto rate = 1000.0 / update_interval_millis_; RCLCPP_INFO_STREAM(node_->get_logger(), "/joints_states: publish rate is: " << rate << " Hz"); + // load publish_joints_only_on_value_change + if (node_->get_parameter( + "joints_aggregator.publish_joints_only_on_value_change", + publish_joints_only_on_value_change_)) { + RCLCPP_INFO_STREAM( + node_->get_logger(), + "loaded joints_aggregator.publish_joints_only_on_value_change) is: " + << publish_joints_only_on_value_change_); + } else { + RCLCPP_ERROR( + node_->get_logger(), + "ERROR, can not load " + "joints_aggregator.publish_joints_only_on_value_change parameter"); + rclcpp::shutdown(); + return false; + } return true; } diff --git a/penta_description/config/general_config.yaml b/penta_description/config/general_config.yaml index 5357ee6..0194afe 100644 --- a/penta_description/config/general_config.yaml +++ b/penta_description/config/general_config.yaml @@ -40,6 +40,7 @@ ] joints_aggregator: joints_update_interval_millis: 10 + publish_joints_only_on_value_change: true base_twerk: base_frame_transform_update_interval_millis: 20 action_server_service_call_interval_millis: 100 From 8a19f5027cc5503968ae4d5ed14341b67307c10c Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 23 Mar 2025 16:50:03 +0100 Subject: [PATCH 27/39] service difinition to retrieve base in base footprint transform --- interfaces/base_twerk_msgs/CMakeLists.txt | 1 + interfaces/base_twerk_msgs/srv/GetCurrentBasePose.srv | 3 +++ 2 files changed, 4 insertions(+) create mode 100644 interfaces/base_twerk_msgs/srv/GetCurrentBasePose.srv diff --git a/interfaces/base_twerk_msgs/CMakeLists.txt b/interfaces/base_twerk_msgs/CMakeLists.txt index 95d799b..5f712e6 100644 --- a/interfaces/base_twerk_msgs/CMakeLists.txt +++ b/interfaces/base_twerk_msgs/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(geometry_msgs REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "srv/BasePoseSetpoint.srv" + "srv/GetCurrentBasePose.srv" "action/BaseTwerkAction.action" DEPENDENCIES builtin_interfaces diff --git a/interfaces/base_twerk_msgs/srv/GetCurrentBasePose.srv b/interfaces/base_twerk_msgs/srv/GetCurrentBasePose.srv new file mode 100644 index 0000000..c589d39 --- /dev/null +++ b/interfaces/base_twerk_msgs/srv/GetCurrentBasePose.srv @@ -0,0 +1,3 @@ +# returns the current pose of the base +--- +geometry_msgs/PoseStamped pose From b0c42ab767f6d03d41e9094b3039b303619e0f44 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 23 Mar 2025 17:15:39 +0100 Subject: [PATCH 28/39] service to quiry for base pose rather than a subscriber --- .../base_twerk/base_twerk_action_server.hpp | 7 +- .../base_twerk/base_twerk_cmd_publisher.hpp | 6 ++ .../launch/base_twerk_action_server.launch.py | 15 +-- .../launch/null_pose_publisher.launch.py | 15 +-- .../base_twerk/base_twerk_action_server.cpp | 93 +++++++++++++------ .../base_twerk/base_twerk_cmd_publisher.cpp | 23 ++++- 6 files changed, 115 insertions(+), 44 deletions(-) diff --git a/base_twerk/include/base_twerk/base_twerk_action_server.hpp b/base_twerk/include/base_twerk/base_twerk_action_server.hpp index bfa8300..98c486c 100644 --- a/base_twerk/include/base_twerk/base_twerk_action_server.hpp +++ b/base_twerk/include/base_twerk/base_twerk_action_server.hpp @@ -9,6 +9,7 @@ #include "base_twerk_msgs/action/base_twerk_action.hpp" #include "base_twerk_msgs/srv/base_pose_setpoint.hpp" +#include "base_twerk_msgs/srv/get_current_base_pose.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" namespace penta_pod::kin::base_twerk { @@ -16,6 +17,7 @@ namespace penta_pod::kin::base_twerk { using BaseTwerkAction = base_twerk_msgs::action::BaseTwerkAction; using GoalHandle = rclcpp_action::ServerGoalHandle; using BasePoseSetpointSrv = base_twerk_msgs::srv::BasePoseSetpoint; +using GetCurrentBasePose = base_twerk_msgs::srv::GetCurrentBasePose; using geometry_msgs::msg::PoseStamped; using penta_pod::kin::commons::service_call_template; @@ -27,7 +29,7 @@ class BaseTwerkActionServer { rclcpp::Client::SharedPtr setpoint_client_; - rclcpp::Subscription::SharedPtr base_pose_subscriber_; + rclcpp::Client::SharedPtr get_currnet_pose_client_; rclcpp::CallbackGroup::SharedPtr callback_group_; @@ -46,9 +48,12 @@ class BaseTwerkActionServer { auto get_parameters() -> void; auto call_setpoint_client(const PoseStamped &base_to_basefootprint) -> bool; + auto calculate_twerk_pose_from_goal( rclcpp::Time start_time, PoseStamped start_pose, const std::shared_ptr goal_handle) -> PoseStamped; + + auto quiry_current_base_pose() -> std::optional; double update_interval_millis_double_; double max_permissible_displacement_meter_; diff --git a/base_twerk/include/base_twerk/base_twerk_cmd_publisher.hpp b/base_twerk/include/base_twerk/base_twerk_cmd_publisher.hpp index 2f4adb2..7b036c8 100644 --- a/base_twerk/include/base_twerk/base_twerk_cmd_publisher.hpp +++ b/base_twerk/include/base_twerk/base_twerk_cmd_publisher.hpp @@ -6,18 +6,23 @@ // include messages #include "base_twerk_msgs/srv/base_pose_setpoint.hpp" +#include "base_twerk_msgs/srv/get_current_base_pose.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" namespace penta_pod::kin::base_twerk { using PoseStamped = geometry_msgs::msg::PoseStamped; using BasePoseSetpoint = base_twerk_msgs::srv::BasePoseSetpoint; +using GetCurrentBasePose = base_twerk_msgs::srv::GetCurrentBasePose; + +const auto base_footprint = "base_footprint"; class BaseTwerkCmdPuplisher { private: rclcpp::Node::SharedPtr node_; rclcpp::Publisher::SharedPtr base_pose_publisher_; rclcpp::Service::SharedPtr setpoint_service_; + rclcpp::Service::SharedPtr get_current_base_pose_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::TimerBase::SharedPtr timer_; @@ -31,6 +36,7 @@ class BaseTwerkCmdPuplisher { void load_parameters(); void timer_callback(); void create_setpoint_service(); + void create_get_current_base_pose_service(); public: explicit BaseTwerkCmdPuplisher(); diff --git a/base_twerk/launch/base_twerk_action_server.launch.py b/base_twerk/launch/base_twerk_action_server.launch.py index 732e5c2..90081e3 100644 --- a/base_twerk/launch/base_twerk_action_server.launch.py +++ b/base_twerk/launch/base_twerk_action_server.launch.py @@ -3,6 +3,7 @@ from launch import LaunchDescription from launch_ros.actions import Node + def generate_launch_description(): config = os.path.join( get_package_share_directory("penta_description"), @@ -10,10 +11,12 @@ def generate_launch_description(): "general_config.yaml", ) ld = LaunchDescription() - ld.add_action(Node( - package="base_twerk", - executable="base_twerk_action_server_node", - output="screen", - parameters=[config], - )) + ld.add_action( + Node( + package="base_twerk", + executable="base_twerk_action_server_node", + output="screen", + parameters=[config], + ) + ) return ld diff --git a/base_twerk/launch/null_pose_publisher.launch.py b/base_twerk/launch/null_pose_publisher.launch.py index 457c8be..8de29ef 100644 --- a/base_twerk/launch/null_pose_publisher.launch.py +++ b/base_twerk/launch/null_pose_publisher.launch.py @@ -3,6 +3,7 @@ from launch import LaunchDescription from launch_ros.actions import Node + def generate_launch_description(): config = os.path.join( get_package_share_directory("penta_description"), @@ -10,10 +11,12 @@ def generate_launch_description(): "general_config.yaml", ) ld = LaunchDescription() - ld.add_action(Node( - package="base_twerk", - executable="base_twerk_publisher_node", - output="screen", - parameters=[config], - )) + ld.add_action( + Node( + package="base_twerk", + executable="base_twerk_publisher_node", + output="screen", + parameters=[config], + ) + ) return ld diff --git a/base_twerk/src/base_twerk/base_twerk_action_server.cpp b/base_twerk/src/base_twerk/base_twerk_action_server.cpp index bd475fb..49a958d 100644 --- a/base_twerk/src/base_twerk/base_twerk_action_server.cpp +++ b/base_twerk/src/base_twerk/base_twerk_action_server.cpp @@ -17,14 +17,9 @@ BaseTwerkActionServer::BaseTwerkActionServer() this->setpoint_client_ = node_->create_client( "cmd_null_setpoint", rmw_qos_profile_services_default, callback_group_); - this->base_pose_subscriber_ = node_->create_subscription( - "null_space_pose", 10, [this](const PoseStamped &msg) -> void { - { - std::lock_guard lock(received_base_pose_mutex_); - received_base_pose_.timestamp = node_->now(); - received_base_pose_.value = msg; - } - }); + this->get_currnet_pose_client_ = node_->create_client( + "get_current_null_pose", rmw_qos_profile_services_default, + callback_group_); this->base_twerk_action_server_ = rclcpp_action::create_server( @@ -66,8 +61,9 @@ auto BaseTwerkActionServer::execute( const auto goal = goal_handle->get_goal(); auto result = std::make_shared(); - double mag_displacement = std::sqrt( - goal->r[0] * goal->r[0] + goal->r[1] * goal->r[1] + goal->r[2] * goal->r[2]); + double mag_displacement = + std::sqrt(goal->r[0] * goal->r[0] + goal->r[1] * goal->r[1] + + goal->r[2] * goal->r[2]); if (mag_displacement > max_permissible_displacement_meter_) { auto message = "Action aborted for the specified displacement is: " + std::to_string(mag_displacement) + @@ -97,26 +93,19 @@ auto BaseTwerkActionServer::execute( return false; }; - // get current null pose - auto start_time = node_->now(); - while (rclcpp::ok()) { - rate.sleep(); - - if (received_base_pose_.timestamp > start_time) { - break; - } - - if (is_timed_out(start_time, 1s)) { - result->result_message = "Timed out, did not receive transform message"; - goal_handle->abort(result); - RCLCPP_WARN(node_->get_logger(), "Time out, breaking out from action"); - return; - } + // get current null space pose + auto get_currnet_pose_response = quiry_current_base_pose(); + if (!get_currnet_pose_response.has_value()) { + result->result_message = "Failed to get current base pose"; + goal_handle->abort(result); + return; } PoseStamped start_pose{}; { std::lock_guard lock(received_base_pose_mutex_); + received_base_pose_ = {node_->now(), + get_currnet_pose_response.value().pose}; start_pose = received_base_pose_.value; RCLCPP_INFO(node_->get_logger(), "Current base pose is: x:%f y:%f z:%f", start_pose.pose.position.x, start_pose.pose.position.y, @@ -127,7 +116,7 @@ auto BaseTwerkActionServer::execute( std::chrono::milliseconds(static_cast(goal->dance_time_millis)); // start control loop for base pose motion - start_time = node_->now(); + auto start_time = node_->now(); while (rclcpp::ok()) { rate.sleep(); @@ -160,6 +149,54 @@ auto BaseTwerkActionServer::execute( } } +auto BaseTwerkActionServer::quiry_current_base_pose() + -> std::optional { + + // check if service is available + auto service_name = get_currnet_pose_client_->get_service_name(); + if (!get_currnet_pose_client_->wait_for_service(1s)) { + RCLCPP_ERROR(node_->get_logger(), "Service %s not online!", service_name); + return std::nullopt; + } + + // send request + auto get_current_pose_request = + std::make_shared(); + + auto start_time = node_->now(); + + auto future = + get_currnet_pose_client_->async_send_request(get_current_pose_request); + + using namespace std::chrono_literals; + const auto timeout_millis = std::chrono::milliseconds(500); + + auto status = future.wait_for(timeout_millis); + + if (status != std::future_status::ready) { + RCLCPP_ERROR(node_->get_logger(), "Service %s response timed out!", + service_name); + return std::nullopt; + } + + if (!future.valid()) { + RCLCPP_ERROR(node_->get_logger(), "Future from service %s is not valid!", + service_name); + return std::nullopt; + } + + auto result = future.get(); + if (!result) { + RCLCPP_ERROR(node_->get_logger(), "Returned null Service %s response!", + service_name); + return std::nullopt; + } + + RCLCPP_INFO(node_->get_logger(), "Service %s response is ready!", + service_name); + return *result; +} + auto BaseTwerkActionServer::calculate_twerk_pose_from_goal( rclcpp::Time start_time, PoseStamped start_pose, const std::shared_ptr goal_handle) -> PoseStamped { @@ -177,10 +214,10 @@ auto BaseTwerkActionServer::calculate_twerk_pose_from_goal( pose.pose.position.z = start_pose.pose.position.z + goal->r[2] * sin(goal->w * delta_t_seconds + goal->phi[2]); - + std::vector rpy = {0., 0., 0.}; for (int i = 3; i < 6; i++) { - rpy[i-3] = goal->r[i] * sin(goal->w * delta_t_seconds + goal->phi[i]); + rpy[i - 3] = goal->r[i] * sin(goal->w * delta_t_seconds + goal->phi[i]); } auto roll = rpy[0]; diff --git a/base_twerk/src/base_twerk/base_twerk_cmd_publisher.cpp b/base_twerk/src/base_twerk/base_twerk_cmd_publisher.cpp index 3c70302..f9b3833 100644 --- a/base_twerk/src/base_twerk/base_twerk_cmd_publisher.cpp +++ b/base_twerk/src/base_twerk/base_twerk_cmd_publisher.cpp @@ -20,17 +20,18 @@ BaseTwerkCmdPuplisher::BaseTwerkCmdPuplisher() std::chrono::milliseconds(static_cast(update_interval_millis_)), [this]() { timer_callback(); }); + callback_group_ = node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive); + create_setpoint_service(); + create_get_current_base_pose_service(); } void BaseTwerkCmdPuplisher::create_setpoint_service() { - callback_group_ = node_->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive); auto lambda = [this](const BasePoseSetpoint::Request::SharedPtr &request, const BasePoseSetpoint::Response::SharedPtr &response) -> bool { auto frame_id = request->pose.header.frame_id; - const auto base_footprint = "base_footprint"; if (frame_id == "") { frame_id = base_footprint; } @@ -54,6 +55,22 @@ void BaseTwerkCmdPuplisher::create_setpoint_service() { callback_group_); } +void BaseTwerkCmdPuplisher::create_get_current_base_pose_service() { + auto lambda = + [this](const GetCurrentBasePose::Request::SharedPtr & /*request*/, + const GetCurrentBasePose::Response::SharedPtr &response) -> bool { + auto pose = base_pose_; + pose.header.stamp = node_->now(); + pose.header.frame_id = base_footprint; + response->pose = pose; + return true; + }; + + get_current_base_pose_ = node_->create_service( + "get_current_null_pose", lambda, rmw_qos_profile_services_default, + callback_group_); +} + void BaseTwerkCmdPuplisher::timer_callback() { double deta_t_sec = update_interval_millis_ / 1000.0; using namespace penta_pod::kin::commons; From 2f7f57499a1ea0a8db53a6ec18077fb7512ebb71 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 23 Mar 2025 17:16:46 +0100 Subject: [PATCH 29/39] remove base pose tf broadcaster into another node --- gait_generator/CMakeLists.txt | 7 ++++ .../gait_generator/base_tf_broadcaster.hpp | 30 +++++++++++++++ .../include/gait_generator/gait_generator.hpp | 1 - .../launch/gait_generator.launch.py | 23 +++++++++--- .../src/base_tf_broadcaster_node.cpp | 8 ++++ .../gait_generator/base_tf_broadcaster.cpp | 37 +++++++++++++++++++ .../gait_generator/gait_generator_core.cpp | 13 ------- 7 files changed, 99 insertions(+), 20 deletions(-) create mode 100644 gait_generator/include/gait_generator/base_tf_broadcaster.hpp create mode 100644 gait_generator/src/base_tf_broadcaster_node.cpp create mode 100644 gait_generator/src/gait_generator/base_tf_broadcaster.cpp diff --git a/gait_generator/CMakeLists.txt b/gait_generator/CMakeLists.txt index 31576dd..c4c797b 100644 --- a/gait_generator/CMakeLists.txt +++ b/gait_generator/CMakeLists.txt @@ -24,6 +24,7 @@ find_package(tf2_geometry_msgs REQUIRED) add_library(${PROJECT_NAME} src/${PROJECT_NAME}/${PROJECT_NAME}_parameters.cpp src/${PROJECT_NAME}/${PROJECT_NAME}_core.cpp + src/${PROJECT_NAME}/base_tf_broadcaster.cpp ) target_include_directories(${PROJECT_NAME} @@ -46,6 +47,11 @@ target_link_libraries(${PROJECT_NAME}_node ${PROJECT_NAME} ) + +add_executable(base_tf_broadcaster_node src/base_tf_broadcaster_node.cpp) +target_link_libraries(base_tf_broadcaster_node + ${PROJECT_NAME} + ) ############# ## Install ## ############# @@ -57,6 +63,7 @@ install( install(TARGETS ${PROJECT_NAME}_node + base_tf_broadcaster_node DESTINATION lib/${PROJECT_NAME} ) diff --git a/gait_generator/include/gait_generator/base_tf_broadcaster.hpp b/gait_generator/include/gait_generator/base_tf_broadcaster.hpp new file mode 100644 index 0000000..7015fcd --- /dev/null +++ b/gait_generator/include/gait_generator/base_tf_broadcaster.hpp @@ -0,0 +1,30 @@ +#ifndef BASE_TF_BROADCASTER_HPP_ +#define BASE_TF_BROADCASTER_HPP_ + +#include "rclcpp/rclcpp.hpp" +#include + +// include messages +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "tf2_ros/transform_broadcaster.h" +#include + +namespace penta_pod::kin { + +using PoseStamped = geometry_msgs::msg::PoseStamped; +const auto base_footprint = "base_footprint"; + +class BaseTfBroadcaster { +private: + rclcpp::Node::SharedPtr node_; + rclcpp::Subscription::SharedPtr base_pose_subscriber_; + auto base_pose_sub_callback(const PoseStamped::SharedPtr msg) -> void; + +public: + explicit BaseTfBroadcaster(); + void spin() { rclcpp::spin(node_); }; +}; + +} // namespace penta_pod::kin + +#endif // BASE_TF_BROADCASTER_HPP_ \ No newline at end of file diff --git a/gait_generator/include/gait_generator/gait_generator.hpp b/gait_generator/include/gait_generator/gait_generator.hpp index 5f2aa3d..a3638c0 100644 --- a/gait_generator/include/gait_generator/gait_generator.hpp +++ b/gait_generator/include/gait_generator/gait_generator.hpp @@ -15,7 +15,6 @@ #include #include #include -#include #include #include diff --git a/gait_generator/launch/gait_generator.launch.py b/gait_generator/launch/gait_generator.launch.py index db2252a..dfece2e 100644 --- a/gait_generator/launch/gait_generator.launch.py +++ b/gait_generator/launch/gait_generator.launch.py @@ -3,6 +3,7 @@ from launch import LaunchDescription from launch_ros.actions import Node + def generate_launch_description(): config = os.path.join( get_package_share_directory("penta_description"), @@ -10,10 +11,20 @@ def generate_launch_description(): "general_config.yaml", ) ld = LaunchDescription() - ld.add_action(Node( - package="gait_generator", - executable="gait_generator_node", - output="screen", - parameters=[config], - )) + ld.add_action( + Node( + package="gait_generator", + executable="gait_generator_node", + output="screen", + parameters=[config], + ) + ) + ld.add_action( + Node( + package="gait_generator", + executable="base_tf_broadcaster_node", + output="screen", + parameters=[config], + ) + ) return ld diff --git a/gait_generator/src/base_tf_broadcaster_node.cpp b/gait_generator/src/base_tf_broadcaster_node.cpp new file mode 100644 index 0000000..00a535f --- /dev/null +++ b/gait_generator/src/base_tf_broadcaster_node.cpp @@ -0,0 +1,8 @@ +#include "gait_generator/base_tf_broadcaster.hpp" + +int main(int argc, char **argv) { + rclcpp::init(argc, argv); + penta_pod::kin::BaseTfBroadcaster().spin(); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file diff --git a/gait_generator/src/gait_generator/base_tf_broadcaster.cpp b/gait_generator/src/gait_generator/base_tf_broadcaster.cpp new file mode 100644 index 0000000..819ee20 --- /dev/null +++ b/gait_generator/src/gait_generator/base_tf_broadcaster.cpp @@ -0,0 +1,37 @@ +#include "gait_generator/base_tf_broadcaster.hpp" + +namespace penta_pod::kin { + +BaseTfBroadcaster::BaseTfBroadcaster() + : node_{rclcpp::Node::make_shared("base_tf_broadcaster")} { + RCLCPP_INFO(node_->get_logger(), + "Starting base_tf_broadcaster, subscriping to null_space_pose " + "topic and broadcasting tf"); + base_pose_subscriber_ = node_->create_subscription( + "null_space_pose", 10, [this](const PoseStamped::SharedPtr msg) { + this->base_pose_sub_callback(msg); + }); +} + +auto BaseTfBroadcaster::base_pose_sub_callback(const PoseStamped::SharedPtr msg) + -> void { + geometry_msgs::msg::TransformStamped transformStamped; + // header + transformStamped.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now(); + transformStamped.header.frame_id = "base_footprint"; + transformStamped.child_frame_id = "base_link"; + // translation + transformStamped.transform.translation.x = msg->pose.position.x; + transformStamped.transform.translation.y = msg->pose.position.y; + transformStamped.transform.translation.z = msg->pose.position.z; + // rotation + transformStamped.transform.rotation.x = msg->pose.orientation.x; + transformStamped.transform.rotation.y = msg->pose.orientation.y; + transformStamped.transform.rotation.z = msg->pose.orientation.z; + transformStamped.transform.rotation.w = msg->pose.orientation.w; + // broadcast + static auto br = std::make_shared(node_); + br->sendTransform(transformStamped); +} + +} // namespace penta_pod::kin \ No newline at end of file diff --git a/gait_generator/src/gait_generator/gait_generator_core.cpp b/gait_generator/src/gait_generator/gait_generator_core.cpp index e342384..1e0fd8c 100644 --- a/gait_generator/src/gait_generator/gait_generator_core.cpp +++ b/gait_generator/src/gait_generator/gait_generator_core.cpp @@ -13,8 +13,6 @@ #include #include -#include "tf2_ros/transform_broadcaster.h" - #include #define pi 3.141592 @@ -56,16 +54,6 @@ GaitGenerator::GaitGenerator() create_set_gait_pattern_service(); } -void GaitGenerator::publish_base_to_basefootprint_transform() { - geometry_msgs::msg::TransformStamped transformStamped; - transformStamped.header.stamp = rclcpp::Clock(RCL_ROS_TIME).now(); - transformStamped.header.frame_id = "base_footprint"; - transformStamped.child_frame_id = "base_link"; - transformStamped.transform = body_basefootprint_; - static auto br = std::make_shared(node_); - br->sendTransform(transformStamped); -} - void GaitGenerator::create_set_gait_pattern_service() { auto lambda = [this](const SetGaitPattern::Request::SharedPtr &request, @@ -233,7 +221,6 @@ void GaitGenerator::update_feet_positions(double delta_t_milli) { void GaitGenerator::timer_callback(double delta_t_milli) { update_phase(delta_t_milli); update_feet_positions(delta_t_milli); - publish_base_to_basefootprint_transform(); } } // namespace penta_pod::kin::gait_generator From a6406b16448a7824aa7b31653ed01ebd9d9d2bfe Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 23 Mar 2025 21:14:04 +0100 Subject: [PATCH 30/39] control with D-Pad --- penta_teleop/CMakeLists.txt | 46 ++++++--- .../penta_teleop/joystick_extra_controls.hpp | 45 +++++++++ penta_teleop/launch/teleop_joystick.launch.py | 8 ++ .../src/joystick_extra_controls_node.cpp | 20 ++++ .../penta_teleop/joystick_extra_controls.cpp | 98 +++++++++++++++++++ 5 files changed, 205 insertions(+), 12 deletions(-) create mode 100644 penta_teleop/include/penta_teleop/joystick_extra_controls.hpp create mode 100644 penta_teleop/src/joystick_extra_controls_node.cpp create mode 100644 penta_teleop/src/penta_teleop/joystick_extra_controls.cpp diff --git a/penta_teleop/CMakeLists.txt b/penta_teleop/CMakeLists.txt index c79f036..d5cceea 100644 --- a/penta_teleop/CMakeLists.txt +++ b/penta_teleop/CMakeLists.txt @@ -8,9 +8,40 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -# uncomment the following section in order to fill in -# further dependencies manually. -# find_package( REQUIRED) +find_package(base_twerk_msgs REQUIRED) +find_package(sensor_msgs REQUIRED) + +# Declare library +add_library(${PROJECT_NAME} + src/${PROJECT_NAME}/joystick_extra_controls.cpp + ) + +target_include_directories(${PROJECT_NAME} + PUBLIC + $ + $) + +ament_target_dependencies(${PROJECT_NAME} + rclcpp + base_twerk_msgs + sensor_msgs + ) + +add_executable(joystick_extra_controls_node src/joystick_extra_controls_node.cpp) +target_link_libraries(joystick_extra_controls_node + ${PROJECT_NAME} + ) + +# Install +install( + DIRECTORY include/ + DESTINATION include +) + +install(TARGETS + joystick_extra_controls_node + DESTINATION lib/${PROJECT_NAME} +) install(DIRECTORY config @@ -19,15 +50,6 @@ install(DIRECTORY ) if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # comment the line when a copyright and license is added to all source files - set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # comment the line when this package is in a git repo and when - # a copyright and license is added to all source files - set(ament_cmake_cpplint_FOUND TRUE) - ament_lint_auto_find_test_dependencies() endif() ament_package() diff --git a/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp b/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp new file mode 100644 index 0000000..a24aa7d --- /dev/null +++ b/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp @@ -0,0 +1,45 @@ +#ifndef JOYSTICK_EXTRA_CONTROLS_HPP_ +#define JOYSTICK_EXTRA_CONTROLS_HPP_ + +#include "rclcpp/rclcpp.hpp" +#include + +// include messages +#include "base_twerk_msgs/srv/base_pose_setpoint.hpp" +#include "base_twerk_msgs/srv/get_current_base_pose.hpp" +#include "geometry_msgs/msg/pose_stamped.hpp" +#include "sensor_msgs/msg/joy.hpp" + +namespace penta_pod::teleop::joystick_extra_controls { + +using PoseStamped = geometry_msgs::msg::PoseStamped; +using BasePoseSetpoint = base_twerk_msgs::srv::BasePoseSetpoint; +using GetCurrentBasePose = base_twerk_msgs::srv::GetCurrentBasePose; + +class JoystickExtraControls { +private: + rclcpp::Node::SharedPtr node_; + rclcpp::Subscription::SharedPtr joy_subscriber_; + + rclcpp::Client::SharedPtr get_current_base_pose_client_; + rclcpp::Client::SharedPtr set_base_pose_client_; + rclcpp::CallbackGroup::SharedPtr callback_group_; + + rclcpp::TimerBase::SharedPtr timer_; + + void joy_sub_callback(const sensor_msgs::msg::Joy::SharedPtr msg); + + void handle_get_base_pose_response( + rclcpp::Client::SharedFuture response, + double z_disp_base_command); + void handle_set_base_pose_response( + rclcpp::Client::SharedFuture response); + +public: + explicit JoystickExtraControls(); + auto get_node() { return node_; }; +}; + +} // namespace penta_pod::teleop::joystick_extra_controls + +#endif // JOYSTICK_EXTRA_CONTROLS_HPP_ \ No newline at end of file diff --git a/penta_teleop/launch/teleop_joystick.launch.py b/penta_teleop/launch/teleop_joystick.launch.py index db77f29..f064ec8 100644 --- a/penta_teleop/launch/teleop_joystick.launch.py +++ b/penta_teleop/launch/teleop_joystick.launch.py @@ -25,9 +25,17 @@ def generate_launch_description(): # remappings=[("/cmd_vel", "/input/cmd_vel_teleop_joy")], ) + joystick_extra_controls_node = Node( + package="penta_teleop", + executable="joystick_extra_controls_node", + name="joystick_extra_controls_node", + parameters=[joy_params], + ) + return LaunchDescription( [ joy_node, teleop_twist_joy_node, + joystick_extra_controls_node ] ) diff --git a/penta_teleop/src/joystick_extra_controls_node.cpp b/penta_teleop/src/joystick_extra_controls_node.cpp new file mode 100644 index 0000000..df94a30 --- /dev/null +++ b/penta_teleop/src/joystick_extra_controls_node.cpp @@ -0,0 +1,20 @@ +#include "penta_teleop/joystick_extra_controls.hpp" +#include + +int main(int argc, char **argv) { + rclcpp::init(argc, argv); + + // Create a shared node instance + auto joystick_extra_controls = penta_pod::teleop::joystick_extra_controls::JoystickExtraControls(); + + // Multi-threaded executor + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(joystick_extra_controls.get_node()); + + // Spin the executor + executor.spin(); + + // Cleanup + rclcpp::shutdown(); + return 0; +} diff --git a/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp new file mode 100644 index 0000000..8460785 --- /dev/null +++ b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp @@ -0,0 +1,98 @@ +#include "penta_teleop/joystick_extra_controls.hpp" + +namespace penta_pod::teleop::joystick_extra_controls { + +JoystickExtraControls::JoystickExtraControls() + : node_{rclcpp::Node::make_shared("joystick_extra_controls")} { + RCLCPP_INFO(node_->get_logger(), + "Starting joystick_extra_controls, subscribing to joy topic and " + "calling base_pose_setpoint service"); + + callback_group_ = node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive); + + // Joystick subscriber + joy_subscriber_ = node_->create_subscription( + "joy", 10, [this](const sensor_msgs::msg::Joy::SharedPtr msg) { + this->joy_sub_callback(msg); + }); + + // Create service clients + get_current_base_pose_client_ = node_->create_client( + "get_current_null_pose", rmw_qos_profile_services_default, + callback_group_); + set_base_pose_client_ = node_->create_client( + "cmd_null_setpoint", rmw_qos_profile_services_default, callback_group_); +} + +void JoystickExtraControls::joy_sub_callback( + const sensor_msgs::msg::Joy::SharedPtr msg) { + + if (msg->axes[7] != 0) { + double delta_z = 0.001; + double z_disp_base_command = msg->axes[7] * delta_z; + + // Check if the service is available before calling + if (!get_current_base_pose_client_->wait_for_service( + std::chrono::seconds(100))) { + RCLCPP_ERROR(node_->get_logger(), + "Service get_current_base_pose is unavailable."); + return; + } + + // Prepare the request + auto request = std::make_shared(); + + // Call the service asynchronously with a callback + auto future = get_current_base_pose_client_->async_send_request( + request, + [this, z_disp_base_command]( + rclcpp::Client::SharedFuture response) { + this->handle_get_base_pose_response(response, z_disp_base_command); + }); + } +} + +void JoystickExtraControls::handle_get_base_pose_response( + rclcpp::Client::SharedFuture response, + double z_disp_base_command) { + + auto result = response.get(); + + if (!result) { + RCLCPP_ERROR(node_->get_logger(), "Failed to get base pose."); + return; + } + + RCLCPP_INFO(node_->get_logger(), "Current base pose: %f %f %f %f %f %f %f", + result->pose.pose.position.x, result->pose.pose.position.y, + result->pose.pose.position.z, result->pose.pose.orientation.x, + result->pose.pose.orientation.y, result->pose.pose.orientation.z, + result->pose.pose.orientation.w); + + // Prepare new base pose setpoint request + auto setpoint_request = std::make_shared(); + setpoint_request->pose = result->pose; + setpoint_request->pose.pose.position.z += z_disp_base_command; + + // Call the set_base_pose service asynchronously + auto future = set_base_pose_client_->async_send_request( + setpoint_request, + [this](rclcpp::Client::SharedFuture setpoint_response) { + this->handle_set_base_pose_response(setpoint_response); + }); +} + +void JoystickExtraControls::handle_set_base_pose_response( + rclcpp::Client::SharedFuture response) { + + auto result = response.get(); + + if (!result) { + RCLCPP_ERROR(node_->get_logger(), "Failed to set base pose."); + } else { + RCLCPP_INFO(node_->get_logger(), "Base pose set successfully."); + } +} + +} // namespace penta_pod::teleop::joystick_extra_controls From 0718ff183ad71974476abba7a19047471295fcd8 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 11:32:51 +0200 Subject: [PATCH 31/39] joystick params --- penta_teleop/config/joy_extra_controls.yaml | 6 ++ .../penta_teleop/joystick_extra_controls.hpp | 8 ++- penta_teleop/launch/teleop_joystick.launch.py | 12 ++-- .../penta_teleop/joystick_extra_controls.cpp | 60 ++++++++++++++++++- 4 files changed, 78 insertions(+), 8 deletions(-) create mode 100644 penta_teleop/config/joy_extra_controls.yaml diff --git a/penta_teleop/config/joy_extra_controls.yaml b/penta_teleop/config/joy_extra_controls.yaml new file mode 100644 index 0000000..43af239 --- /dev/null +++ b/penta_teleop/config/joy_extra_controls.yaml @@ -0,0 +1,6 @@ +/**: + ros__parameters: + base_height_ctl: # parameters to change the ehight of the robot base using joystick DPad + d_pad_up_down_axis_index: 7 + z_base_min_value: 0.01 + z_base_max_value: 0.15 \ No newline at end of file diff --git a/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp b/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp index a24aa7d..6eda6d8 100644 --- a/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp +++ b/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp @@ -34,7 +34,13 @@ class JoystickExtraControls { double z_disp_base_command); void handle_set_base_pose_response( rclcpp::Client::SharedFuture response); - + void declare_parameters(); + bool get_parameters(); + + int d_pad_up_down_axis_index_{7}; + double z_base_max_value_{0.01}; + double z_base_min_value_{0.15}; + public: explicit JoystickExtraControls(); auto get_node() { return node_; }; diff --git a/penta_teleop/launch/teleop_joystick.launch.py b/penta_teleop/launch/teleop_joystick.launch.py index f064ec8..94a8a51 100644 --- a/penta_teleop/launch/teleop_joystick.launch.py +++ b/penta_teleop/launch/teleop_joystick.launch.py @@ -25,17 +25,17 @@ def generate_launch_description(): # remappings=[("/cmd_vel", "/input/cmd_vel_teleop_joy")], ) + joystick_extra_controls_configs = os.path.join( + get_package_share_directory("penta_teleop"), "config", "joy_extra_controls.yaml" + ) + joystick_extra_controls_node = Node( package="penta_teleop", executable="joystick_extra_controls_node", name="joystick_extra_controls_node", - parameters=[joy_params], + parameters=[joystick_extra_controls_configs], ) return LaunchDescription( - [ - joy_node, - teleop_twist_joy_node, - joystick_extra_controls_node - ] + [joy_node, teleop_twist_joy_node, joystick_extra_controls_node] ) diff --git a/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp index 8460785..3e9fec6 100644 --- a/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp +++ b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp @@ -7,6 +7,9 @@ JoystickExtraControls::JoystickExtraControls() RCLCPP_INFO(node_->get_logger(), "Starting joystick_extra_controls, subscribing to joy topic and " "calling base_pose_setpoint service"); + // load parameters + this->declare_parameters(); + this->get_parameters(); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive); @@ -28,7 +31,7 @@ JoystickExtraControls::JoystickExtraControls() void JoystickExtraControls::joy_sub_callback( const sensor_msgs::msg::Joy::SharedPtr msg) { - if (msg->axes[7] != 0) { + if (msg->axes[this->d_pad_up_down_axis_index_] != 0) { double delta_z = 0.001; double z_disp_base_command = msg->axes[7] * delta_z; @@ -64,6 +67,22 @@ void JoystickExtraControls::handle_get_base_pose_response( return; } + // Sanity checks + if ((result->pose.pose.position.z > this->z_base_max_value_) && + z_disp_base_command > 0.) { + RCLCPP_ERROR(node_->get_logger(), + "Already above the max Z limit, can not move up any further."); + return; + } + + if ((result->pose.pose.position.z < this->z_base_min_value_) && + z_disp_base_command < 0.) { + RCLCPP_ERROR( + node_->get_logger(), + "Already below the min Z limit, can not move down any further."); + return; + } + RCLCPP_INFO(node_->get_logger(), "Current base pose: %f %f %f %f %f %f %f", result->pose.pose.position.x, result->pose.pose.position.y, result->pose.pose.position.z, result->pose.pose.orientation.x, @@ -95,4 +114,43 @@ void JoystickExtraControls::handle_set_base_pose_response( } } +void JoystickExtraControls::declare_parameters() { + node_->declare_parameter("base_height_ctl.d_pad_up_down_axis_index"); + node_->declare_parameter("base_height_ctl.z_base_min_value"); + node_->declare_parameter("base_height_ctl.z_base_max_value"); +} + +bool JoystickExtraControls::get_parameters() { + std::string param_name; + + param_name = "base_height_ctl.d_pad_up_down_axis_index"; + if (!node_->get_parameter(param_name, this->d_pad_up_down_axis_index_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %d", + param_name.c_str(), this->d_pad_up_down_axis_index_); + + param_name = "base_height_ctl.z_base_max_value"; + if (!node_->get_parameter(param_name, this->z_base_max_value_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %f", + param_name.c_str(), this->z_base_max_value_); + + param_name = "base_height_ctl.z_base_min_value"; + if (!node_->get_parameter(param_name, this->z_base_min_value_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %f", + param_name.c_str(), this->z_base_min_value_); + + return true; +} + } // namespace penta_pod::teleop::joystick_extra_controls From bc72ccb3e43f6ba9c95a0ab7b3ed9cccbf1ecc93 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 16:48:28 +0200 Subject: [PATCH 32/39] base motion is omindirectional --- penta_teleop/config/teleop_joystick.yaml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/penta_teleop/config/teleop_joystick.yaml b/penta_teleop/config/teleop_joystick.yaml index bb92128..2cd4a80 100644 --- a/penta_teleop/config/teleop_joystick.yaml +++ b/penta_teleop/config/teleop_joystick.yaml @@ -7,10 +7,13 @@ axis_linear: x: 1 # left stick up/down + y: 0 # left stick left/right scale_linear: x: 0.01 + y: 0.01 scale_linear_turbo: x: 0.035 + y: 0.035 axis_angular: yaw: 3 # right stick left/right From 3442873e876b8ac129c095dc0adeeb5f6565f9a9 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 16:52:54 +0200 Subject: [PATCH 33/39] readme 4 joystick --- penta_teleop/README.md | 15 +++++++++++++++ 1 file changed, 15 insertions(+) create mode 100644 penta_teleop/README.md diff --git a/penta_teleop/README.md b/penta_teleop/README.md new file mode 100644 index 0000000..cf8bb17 --- /dev/null +++ b/penta_teleop/README.md @@ -0,0 +1,15 @@ +# Pentapod control with Xbox joystick controller + + +You can control the Pentapod from Xbox joystick controller + +Tested with wirless Xbox contorller provided with a dongle + +Connect the dongle to Raspberry PI, to control the robot as follows: + + +1- Left joystick for x and y motion + +2- Right joystick for rotations + +3- D-Pad up and down buttons, to move the robot up and down From bd2d0d50fe5828a8ef3a0a8b2648a180fafd05c0 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 17:01:02 +0200 Subject: [PATCH 34/39] motion in plane --- penta_teleop/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/penta_teleop/README.md b/penta_teleop/README.md index cf8bb17..c8a30c8 100644 --- a/penta_teleop/README.md +++ b/penta_teleop/README.md @@ -8,7 +8,7 @@ Tested with wirless Xbox contorller provided with a dongle Connect the dongle to Raspberry PI, to control the robot as follows: -1- Left joystick for x and y motion +1- Left joystick for linear motion in the plane (x and y) 2- Right joystick for rotations From 6ddc9590a9dac30ff2cd9a4bc3cdb91aa6aa474a Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 17:16:00 +0200 Subject: [PATCH 35/39] enable buttons --- penta_teleop/README.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/penta_teleop/README.md b/penta_teleop/README.md index c8a30c8..86c11db 100644 --- a/penta_teleop/README.md +++ b/penta_teleop/README.md @@ -13,3 +13,9 @@ Connect the dongle to Raspberry PI, to control the robot as follows: 2- Right joystick for rotations 3- D-Pad up and down buttons, to move the robot up and down + +Note, make sure to enable the motion using: + +1- Use Right Trigger button (RT) to enable the turbo mode + +2- Use Left Trigger button (LT) to enable slow motion mode From 492822ca6a7400fa3bd7c32692106edd2dcc05e7 Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 18:05:59 +0200 Subject: [PATCH 36/39] base_twerk_msgs as dep --- penta_teleop/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/penta_teleop/CMakeLists.txt b/penta_teleop/CMakeLists.txt index d5cceea..8656ccb 100644 --- a/penta_teleop/CMakeLists.txt +++ b/penta_teleop/CMakeLists.txt @@ -14,6 +14,7 @@ find_package(sensor_msgs REQUIRED) # Declare library add_library(${PROJECT_NAME} src/${PROJECT_NAME}/joystick_extra_controls.cpp + src/${PROJECT_NAME}/declare_load_parameters.cpp ) target_include_directories(${PROJECT_NAME} From 0e96aeb52ede5b1fc916638cee2c9adb7bdeee3a Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 18:06:21 +0200 Subject: [PATCH 37/39] base_twerk_msgs as dep --- penta_teleop/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/penta_teleop/package.xml b/penta_teleop/package.xml index 71939f5..0742518 100644 --- a/penta_teleop/package.xml +++ b/penta_teleop/package.xml @@ -12,6 +12,7 @@ sensor_msgs joy teleop_twist_joy + base_twerk_msgs ament_cmake From 5bd1570e5647ce3455fecef2f69a2cbbde56400d Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 18:06:46 +0200 Subject: [PATCH 38/39] move parameters into separate cpp --- .../penta_teleop/declare_load_parameters.cpp | 44 +++++++++++++++++++ .../penta_teleop/joystick_extra_controls.cpp | 39 ---------------- 2 files changed, 44 insertions(+), 39 deletions(-) create mode 100644 penta_teleop/src/penta_teleop/declare_load_parameters.cpp diff --git a/penta_teleop/src/penta_teleop/declare_load_parameters.cpp b/penta_teleop/src/penta_teleop/declare_load_parameters.cpp new file mode 100644 index 0000000..579cb9f --- /dev/null +++ b/penta_teleop/src/penta_teleop/declare_load_parameters.cpp @@ -0,0 +1,44 @@ +#include "penta_teleop/joystick_extra_controls.hpp" + +namespace penta_pod::teleop::joystick_extra_controls { + +void JoystickExtraControls::declare_parameters() { + node_->declare_parameter("base_height_ctl.d_pad_up_down_axis_index"); + node_->declare_parameter("base_height_ctl.z_base_min_value"); + node_->declare_parameter("base_height_ctl.z_base_max_value"); +} + +bool JoystickExtraControls::get_parameters() { + std::string param_name; + + param_name = "base_height_ctl.d_pad_up_down_axis_index"; + if (!node_->get_parameter(param_name, this->d_pad_up_down_axis_index_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %d", + param_name.c_str(), this->d_pad_up_down_axis_index_); + + param_name = "base_height_ctl.z_base_max_value"; + if (!node_->get_parameter(param_name, this->z_base_max_value_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %f", + param_name.c_str(), this->z_base_max_value_); + + param_name = "base_height_ctl.z_base_min_value"; + if (!node_->get_parameter(param_name, this->z_base_min_value_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %f", + param_name.c_str(), this->z_base_min_value_); + + return true; +} + +} // namespace penta_pod::teleop::joystick_extra_controls diff --git a/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp index 3e9fec6..035bb22 100644 --- a/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp +++ b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp @@ -114,43 +114,4 @@ void JoystickExtraControls::handle_set_base_pose_response( } } -void JoystickExtraControls::declare_parameters() { - node_->declare_parameter("base_height_ctl.d_pad_up_down_axis_index"); - node_->declare_parameter("base_height_ctl.z_base_min_value"); - node_->declare_parameter("base_height_ctl.z_base_max_value"); -} - -bool JoystickExtraControls::get_parameters() { - std::string param_name; - - param_name = "base_height_ctl.d_pad_up_down_axis_index"; - if (!node_->get_parameter(param_name, this->d_pad_up_down_axis_index_)) { - RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", - param_name.c_str()); - return false; - } - RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %d", - param_name.c_str(), this->d_pad_up_down_axis_index_); - - param_name = "base_height_ctl.z_base_max_value"; - if (!node_->get_parameter(param_name, this->z_base_max_value_)) { - RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", - param_name.c_str()); - return false; - } - RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %f", - param_name.c_str(), this->z_base_max_value_); - - param_name = "base_height_ctl.z_base_min_value"; - if (!node_->get_parameter(param_name, this->z_base_min_value_)) { - RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", - param_name.c_str()); - return false; - } - RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %f", - param_name.c_str(), this->z_base_min_value_); - - return true; -} - } // namespace penta_pod::teleop::joystick_extra_controls From d013edf631eefb4fa0a1391232648ac6a6fcf36e Mon Sep 17 00:00:00 2001 From: "Safeea, Mohammad" Date: Sun, 6 Apr 2025 19:51:04 +0200 Subject: [PATCH 39/39] add change walking patterns from joystick button press, button X on xbox controller --- penta_teleop/CMakeLists.txt | 6 +- penta_teleop/README.md | 4 ++ penta_teleop/config/joy_extra_controls.yaml | 4 +- .../penta_teleop/joystick_extra_controls.hpp | 13 +++- penta_teleop/launch/teleop_joystick.launch.py | 6 +- penta_teleop/package.xml | 1 + .../penta_teleop/declare_load_parameters.cpp | 21 +++++++ .../penta_teleop/joystick_extra_controls.cpp | 60 +++++++++++++++++++ 8 files changed, 109 insertions(+), 6 deletions(-) diff --git a/penta_teleop/CMakeLists.txt b/penta_teleop/CMakeLists.txt index 8656ccb..5c06980 100644 --- a/penta_teleop/CMakeLists.txt +++ b/penta_teleop/CMakeLists.txt @@ -8,8 +8,9 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(base_twerk_msgs REQUIRED) find_package(sensor_msgs REQUIRED) +find_package(base_twerk_msgs REQUIRED) +find_package(gait_generator_msgs REQUIRED) # Declare library add_library(${PROJECT_NAME} @@ -24,8 +25,9 @@ target_include_directories(${PROJECT_NAME} ament_target_dependencies(${PROJECT_NAME} rclcpp - base_twerk_msgs sensor_msgs + base_twerk_msgs + gait_generator_msgs ) add_executable(joystick_extra_controls_node src/joystick_extra_controls_node.cpp) diff --git a/penta_teleop/README.md b/penta_teleop/README.md index 86c11db..861429b 100644 --- a/penta_teleop/README.md +++ b/penta_teleop/README.md @@ -14,8 +14,12 @@ Connect the dongle to Raspberry PI, to control the robot as follows: 3- D-Pad up and down buttons, to move the robot up and down +4- X button to change walking pattern + Note, make sure to enable the motion using: 1- Use Right Trigger button (RT) to enable the turbo mode 2- Use Left Trigger button (LT) to enable slow motion mode + +3- Walking pattern changes only when the robot is in stand-still \ No newline at end of file diff --git a/penta_teleop/config/joy_extra_controls.yaml b/penta_teleop/config/joy_extra_controls.yaml index 43af239..5862a81 100644 --- a/penta_teleop/config/joy_extra_controls.yaml +++ b/penta_teleop/config/joy_extra_controls.yaml @@ -3,4 +3,6 @@ base_height_ctl: # parameters to change the ehight of the robot base using joystick DPad d_pad_up_down_axis_index: 7 z_base_min_value: 0.01 - z_base_max_value: 0.15 \ No newline at end of file + z_base_max_value: 0.15 + gait_patterns_ctl: + button_index: 2 diff --git a/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp b/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp index 6eda6d8..34eaec5 100644 --- a/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp +++ b/penta_teleop/include/penta_teleop/joystick_extra_controls.hpp @@ -7,6 +7,7 @@ // include messages #include "base_twerk_msgs/srv/base_pose_setpoint.hpp" #include "base_twerk_msgs/srv/get_current_base_pose.hpp" +#include "gait_generator_msgs/srv/set_gait_pattern.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "sensor_msgs/msg/joy.hpp" @@ -15,6 +16,7 @@ namespace penta_pod::teleop::joystick_extra_controls { using PoseStamped = geometry_msgs::msg::PoseStamped; using BasePoseSetpoint = base_twerk_msgs::srv::BasePoseSetpoint; using GetCurrentBasePose = base_twerk_msgs::srv::GetCurrentBasePose; +using SetGaitPattern = gait_generator_msgs::srv::SetGaitPattern; class JoystickExtraControls { private: @@ -23,24 +25,31 @@ class JoystickExtraControls { rclcpp::Client::SharedPtr get_current_base_pose_client_; rclcpp::Client::SharedPtr set_base_pose_client_; + rclcpp::Client::SharedPtr set_gait_pattern_client_; + rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::TimerBase::SharedPtr timer_; void joy_sub_callback(const sensor_msgs::msg::Joy::SharedPtr msg); + void dpad_up_down(const sensor_msgs::msg::Joy::SharedPtr msg); + void set_gait_pattern(const sensor_msgs::msg::Joy::SharedPtr msg); void handle_get_base_pose_response( rclcpp::Client::SharedFuture response, double z_disp_base_command); void handle_set_base_pose_response( rclcpp::Client::SharedFuture response); + void declare_parameters(); bool get_parameters(); - + int d_pad_up_down_axis_index_{7}; + int gait_patterns_ctl_button_index_{2}; + int num_of_gait_patterns_{3}; double z_base_max_value_{0.01}; double z_base_min_value_{0.15}; - + public: explicit JoystickExtraControls(); auto get_node() { return node_; }; diff --git a/penta_teleop/launch/teleop_joystick.launch.py b/penta_teleop/launch/teleop_joystick.launch.py index 94a8a51..24d6f2a 100644 --- a/penta_teleop/launch/teleop_joystick.launch.py +++ b/penta_teleop/launch/teleop_joystick.launch.py @@ -29,11 +29,15 @@ def generate_launch_description(): get_package_share_directory("penta_teleop"), "config", "joy_extra_controls.yaml" ) + general_config_params = os.path.join( + get_package_share_directory("penta_description"), "config", "general_config.yaml" + ) + joystick_extra_controls_node = Node( package="penta_teleop", executable="joystick_extra_controls_node", name="joystick_extra_controls_node", - parameters=[joystick_extra_controls_configs], + parameters=[joystick_extra_controls_configs, general_config_params], ) return LaunchDescription( diff --git a/penta_teleop/package.xml b/penta_teleop/package.xml index 0742518..b4040a8 100644 --- a/penta_teleop/package.xml +++ b/penta_teleop/package.xml @@ -13,6 +13,7 @@ joy teleop_twist_joy base_twerk_msgs + gait_generator_msgs ament_cmake diff --git a/penta_teleop/src/penta_teleop/declare_load_parameters.cpp b/penta_teleop/src/penta_teleop/declare_load_parameters.cpp index 579cb9f..e83e78f 100644 --- a/penta_teleop/src/penta_teleop/declare_load_parameters.cpp +++ b/penta_teleop/src/penta_teleop/declare_load_parameters.cpp @@ -4,6 +4,8 @@ namespace penta_pod::teleop::joystick_extra_controls { void JoystickExtraControls::declare_parameters() { node_->declare_parameter("base_height_ctl.d_pad_up_down_axis_index"); + node_->declare_parameter("gait_patterns_ctl.button_index"); + node_->declare_parameter("gait_parameters.gait_patterns.num"); node_->declare_parameter("base_height_ctl.z_base_min_value"); node_->declare_parameter("base_height_ctl.z_base_max_value"); } @@ -20,6 +22,25 @@ bool JoystickExtraControls::get_parameters() { RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %d", param_name.c_str(), this->d_pad_up_down_axis_index_); + param_name = "gait_patterns_ctl.button_index"; + if (!node_->get_parameter(param_name, + this->gait_patterns_ctl_button_index_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %d", + param_name.c_str(), this->gait_patterns_ctl_button_index_); + + param_name = "gait_parameters.gait_patterns.num"; + if (!node_->get_parameter(param_name, this->num_of_gait_patterns_)) { + RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", + param_name.c_str()); + return false; + } + RCLCPP_INFO(node_->get_logger(), "Loaded parameter %s with value %d", + param_name.c_str(), this->num_of_gait_patterns_); + param_name = "base_height_ctl.z_base_max_value"; if (!node_->get_parameter(param_name, this->z_base_max_value_)) { RCLCPP_ERROR(node_->get_logger(), "Can not load parameters %s", diff --git a/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp index 035bb22..4dfdd5b 100644 --- a/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp +++ b/penta_teleop/src/penta_teleop/joystick_extra_controls.cpp @@ -26,11 +26,71 @@ JoystickExtraControls::JoystickExtraControls() callback_group_); set_base_pose_client_ = node_->create_client( "cmd_null_setpoint", rmw_qos_profile_services_default, callback_group_); + // Service cleint to change walking pattern + set_gait_pattern_client_ = node_->create_client( + "/gait_generator/set_gait_pattern", rmw_qos_profile_services_default, + callback_group_); } void JoystickExtraControls::joy_sub_callback( const sensor_msgs::msg::Joy::SharedPtr msg) { + // move base up and down + dpad_up_down(msg); + // change walking pattern + set_gait_pattern(msg); +} + +void JoystickExtraControls::set_gait_pattern( + const sensor_msgs::msg::Joy::SharedPtr msg) { + + static int last_button_state = 0; + static int walking_pattern = 0; + int current_button_state = + msg->buttons[this->gait_patterns_ctl_button_index_]; + if (current_button_state == 1 && last_button_state == 0) { + walking_pattern++; + if (walking_pattern > num_of_gait_patterns_) { + walking_pattern = 0; + } + // Button was pressed + RCLCPP_INFO(node_->get_logger(), + "Button index %d pressed, changing walking pattern", + this->gait_patterns_ctl_button_index_); + // Check if the service is available before calling + if (!set_gait_pattern_client_->wait_for_service( + std::chrono::seconds(100))) { + RCLCPP_ERROR(node_->get_logger(), + "Service set_gait_pattern_client_ is unavailable."); + return; + } + // Add your logic to change the walking pattern here + auto request = std::make_shared(); + request->pattern = walking_pattern; + // Call the service asynchronously + auto future = set_gait_pattern_client_->async_send_request( + request, [this](rclcpp::Client::SharedFuture response) { + auto result = response.get(); + + if (!result) { + RCLCPP_ERROR(node_->get_logger(), + "Failed change walking pattern (null return)."); + return; + } + if (result->success) { + RCLCPP_INFO(node_->get_logger(), + "Walking pattern changed successfully."); + } else { + RCLCPP_ERROR(node_->get_logger(), + "Failed to change walking pattern."); + } + }); + } + last_button_state = current_button_state; +} + +void JoystickExtraControls::dpad_up_down( + const sensor_msgs::msg::Joy::SharedPtr msg) { if (msg->axes[this->d_pad_up_down_axis_index_] != 0) { double delta_z = 0.001; double z_disp_base_command = msg->axes[7] * delta_z;