diff --git a/Go2Py/control/neuro_diff.py b/Go2Py/control/neuro_diff.py new file mode 100644 index 0000000..4b4cc22 --- /dev/null +++ b/Go2Py/control/neuro_diff.py @@ -0,0 +1,354 @@ +import os +import time + +import numpy as np +import torch +import torch.nn as nn +import torch.nn.functional as F + +import onnxruntime +from models import model_utils + +class ActorStochasticMLP(nn.Module): + def __init__(self): + super(ActorStochasticMLP, self).__init__() + + self.hidden_size = 256 + obs_dim = 49 + action_dim = 12 + self.gru = nn.GRU(obs_dim, self.hidden_size, batch_first=True) + self.layer_dims = [obs_dim + self.hidden_size] + [256, 128, 64] + [action_dim] + + init_ = lambda m: model_utils.init(m, nn.init.orthogonal_, lambda x: nn.init. + constant_(x, 0), np.sqrt(2)) + + modules = [] + for i in range(len(self.layer_dims) - 1): + modules.append(nn.Linear(self.layer_dims[i], self.layer_dims[i + 1])) + if i < len(self.layer_dims) - 2: + modules.append(model_utils.get_activation_func('elu')) + modules.append(torch.nn.LayerNorm(self.layer_dims[i+1])) + else: + modules.append(model_utils.get_activation_func('identity')) + + self.mu_net = nn.Sequential(*modules) + + logstd = -1.0 + + self.logstd = torch.nn.Parameter(torch.ones(action_dim, dtype=torch.float32) * logstd) + + self.action_dim = action_dim + self.obs_dim = obs_dim + + self.min_logstd = -1.427 + + print(self.mu_net) + print(self.logstd) + + def forward(self, obs, l): + out, time_latent = self.gru(obs, l) + x = torch.cat([obs, out], dim=-1) + + mu = self.mu_net(x) + + return mu, time_latent + +class Policy: + def __init__(self, checkpoint_path): + self.agent = ActorStochasticMLP() + agent_init, _, _, self.obs_rms, _, _ = torch.load(checkpoint_path, map_location="cpu") + self.agent.load_state_dict(agent_init.state_dict()) + onnx_file_name = checkpoint_path.replace(".pt", ".onnx") + self.actor_hidden_in = np.zeros((1, 256), dtype=np.float32) + + dummy_input = torch.randn(1, 49) + with torch.no_grad(): + torch_out, torch_hidden_out = self.agent(dummy_input, l = torch.tensor(self.actor_hidden_in)) + + torch.onnx.export( + self.agent, # The model being converted + (dummy_input, torch.tensor(self.actor_hidden_in)), # An example input for the model + onnx_file_name, # Output file name + export_params=True, # Store trained parameter weights inside the model file + opset_version=11, # ONNX version (opset) to export to, adjust as needed + do_constant_folding=True, # Whether to perform constant folding optimization + input_names=['input', 'hidden_in'], # Name of the input in the ONNX graph (can be customized) + output_names=['action', 'hidden_out'], # Name of the output (assuming get_action and get_value are key outputs) + ) + + self.ort_session = onnxruntime.InferenceSession(onnx_file_name, providers=["CPUExecutionProvider"]) + ort_inputs = {'input': dummy_input.numpy(), 'hidden_in': self.actor_hidden_in} + ort_outs = self.ort_session.run(None, ort_inputs) + action, hidden_out = ort_outs[0], ort_outs[1] + np.testing.assert_allclose(torch_out.numpy(), action, rtol=1e-03, atol=1e-05) + np.testing.assert_allclose(torch_hidden_out.numpy(), hidden_out, rtol=1e-03, atol=1e-05) + print("Exported model has been tested with ONNXRuntime, and the result looks good!") + + def __call__(self, obs, info): + obs = torch.cat( + [torch.zeros((1, 3)), torch.tensor(obs[np.newaxis]), torch.zeros((1, 9))], + dim = -1 + ) + obs = self.obs_rms.normalize(obs)[:, 3:-9].numpy().astype(np.float32) + ort_inputs = {'input': obs, 'hidden_in': self.actor_hidden_in} + ort_outs = self.ort_session.run(None, ort_inputs) + self.actor_hidden_in = ort_outs[1] + return ort_outs[0] + +class CommandInterface: + def __init__(self, limits=None): + self.limits = limits + self.x_vel_cmd, self.y_vel_cmd, self.yaw_vel_cmd = 0.0, 0.0, 0.0 + + def get_command(self): + command = np.zeros((3,)) + command[0] = self.x_vel_cmd + command[1] = self.y_vel_cmd + command[2] = self.yaw_vel_cmd + return command, False + + +class NeuroDiffAgent: + def __init__(self, command_profile, robot): + self.robot = robot + self.command_profile = command_profile + # self.lcm_bridge = LCMBridgeClient(robot_name=self.robot_name) + self.sim_dt = 0.001 + self.decimation = 20 + self.dt = self.sim_dt * self.decimation + self.timestep = 0 + + self.device = "cpu" + + joint_names = [ + "FL_hip_joint", + "FL_thigh_joint", + "FL_calf_joint", + "FR_hip_joint", + "FR_thigh_joint", + "FR_calf_joint", + "RL_hip_joint", + "RL_thigh_joint", + "RL_calf_joint", + "RR_hip_joint", + "RR_thigh_joint", + "RR_calf_joint", + ] + + policy_joint_names = joint_names + + unitree_joint_names = [ + "FR_hip_joint", + "FR_thigh_joint", + "FR_calf_joint", + "FL_hip_joint", + "FL_thigh_joint", + "FL_calf_joint", + "RR_hip_joint", + "RR_thigh_joint", + "RR_calf_joint", + "RL_hip_joint", + "RL_thigh_joint", + "RL_calf_joint", + ] + + policy_to_unitree_map = [] + unitree_to_policy_map = [] + for i, policy_joint_name in enumerate(policy_joint_names): + id = np.where([name == policy_joint_name for name in unitree_joint_names])[0][0] + policy_to_unitree_map.append((i, id)) + self.policy_to_unitree_map = np.array(policy_to_unitree_map).astype(np.uint32) + + for i, unitree_joint_name in enumerate(unitree_joint_names): + id = np.where([name == unitree_joint_name for name in policy_joint_names])[0][0] + unitree_to_policy_map.append((i, id)) + self.unitree_to_policy_map = np.array(unitree_to_policy_map).astype(np.uint32) + + default_joint_angles = { + "FL_hip_joint": 0.1, + "RL_hip_joint": 0.1, + "FR_hip_joint": -0.1, + "RR_hip_joint": -0.1, + "FL_thigh_joint": 0.8, + "RL_thigh_joint": 1.0, + "FR_thigh_joint": 0.8, + "RR_thigh_joint": 1.0, + "FL_calf_joint": -1.5, + "RL_calf_joint": -1.5, + "FR_calf_joint": -1.5, + "RR_calf_joint": -1.5 + } + self.default_dof_pos = np.array( + [ + default_joint_angles[name] + for name in joint_names + ] + ) + + self.default_dof_pos = self.default_dof_pos + + self.p_gains = np.zeros(12) + self.d_gains = np.zeros(12) + for i in range(12): + self.p_gains[i] = 20.0 + self.d_gains[i] = 0.5 + + print(f"p_gains: {self.p_gains}") + + self.commands = np.zeros(3) + self.actions = np.zeros((1, 12)) + self.last_actions = np.zeros((1,12)) + self.gravity_vector = np.zeros(3) + self.dof_pos = np.zeros(12) + self.dof_vel = np.zeros(12) + self.pos = np.zeros(3) + self.body_linear_vel = np.zeros(3) + self.body_angular_vel = np.zeros(3) + self.joint_pos_target = np.zeros(12) + self.joint_vel_target = np.zeros(12) + self.prev_joint_acc = None + self.torques = np.zeros(12) + self.contact_state = np.ones(4) + self.foot_contact_forces_mag = np.zeros(4) + self.prev_foot_contact_forces_mag = np.zeros(4) + self.test = 0 + + self.gait_indices = np.zeros(1, dtype=np.float32) + self.clock_inputs = np.zeros(4, dtype=np.float32) + + def wait_for_state(self): + # return self.lcm_bridge.getStates(timeout=2) + pass + + def get_obs(self): + cmds, reset_timer = self.command_profile.get_command() + self.commands[:] = cmds + + # self.state = self.wait_for_state() + joint_state = self.robot.getJointStates() + if joint_state is not None: + self.gravity_vector = self.robot.getGravityInBody() + self.prev_dof_pos = self.dof_pos.copy() + self.dof_pos = np.array(joint_state['q'])[self.unitree_to_policy_map[:, 1]] + self.prev_dof_vel = self.dof_vel.copy() + self.dof_vel = np.array(joint_state['dq'])[self.unitree_to_policy_map[:, 1]] + self.body_angular_vel = self.robot.getIMU()["gyro"] + + try: + self.foot_contact_forces_mag = self.robot.getFootContact() + self.body_linear_vel = self.robot.getLinVel() + self.pos, _ = self.robot.getPose() + except: + pass + + ob = np.concatenate( + ( + self.body_angular_vel * 0.25, + self.commands * np.array([2.0, 2.0, 0.25]), + self.gravity_vector[:, 0], + self.dof_pos * 1.0, + #((self.dof_pos - self.prev_dof_pos) / self.dt) * 0.05, + self.dof_vel * 0.05, + self.last_actions[0], + self.clock_inputs + ), + axis=0, + ) + + #return torch.tensor(ob, device=self.device).float() + return ob + + def publish_action(self, action, hard_reset=False): + # command_for_robot = UnitreeLowCommand() + #self.joint_pos_target = ( + # action[0, :12].detach().cpu().numpy() * 0.25 + #).flatten() + self.joint_pos_target = ( + action[0, :12] * 0.25 + ).flatten() + self.joint_pos_target += self.default_dof_pos + self.joint_vel_target = np.zeros(12) + # command_for_robot.q_des = self.joint_pos_target + # command_for_robot.dq_des = self.joint_vel_target + # command_for_robot.kp = self.p_gains + # command_for_robot.kd = self.d_gains + # command_for_robot.tau_ff = np.zeros(12) + if hard_reset: + command_for_robot.id = -1 + + self.torques = (self.joint_pos_target - self.dof_pos) * self.p_gains + ( + self.joint_vel_target - self.dof_vel + ) * self.d_gains + # self.lcm_bridge.sendCommands(command_for_robot) + self.robot.setCommands(self.joint_pos_target[self.policy_to_unitree_map[:, 1]], + self.joint_vel_target[self.policy_to_unitree_map[:, 1]], + self.p_gains[self.policy_to_unitree_map[:, 1]], + self.d_gains[self.policy_to_unitree_map[:, 1]], + np.zeros(12)) + + def reset(self): + self.actions = torch.zeros((1, 12)) + self.time = time.time() + self.timestep = 0 + return self.get_obs() + + def step(self, actions, hard_reset=False): + self.last_actions = self.actions[:] + self.actions = actions + self.publish_action(self.actions, hard_reset=hard_reset) + # time.sleep(max(self.dt - (time.time() - self.time), 0)) + # if self.timestep % 100 == 0: + # print(f"frq: {1 / (time.time() - self.time)} Hz") + self.time = time.time() + #obs = self.get_obs() + + joint_acc = np.abs(self.prev_dof_vel - self.dof_vel) / self.dt + if self.prev_joint_acc is None: + self.prev_joint_acc = np.zeros_like(joint_acc) + joint_jerk = np.abs(self.prev_joint_acc - joint_acc) / self.dt + self.prev_joint_acc = joint_acc.copy() + + # clock accounting + frequencies = 3. + phases = 0.5 + offsets = 0. + bounds = 0 + self.gait_indices = np.remainder( + self.gait_indices + self.dt * frequencies, 1.0 + ) + + self.foot_indices = [ + self.gait_indices + phases + offsets + bounds, + self.gait_indices + offsets, + self.gait_indices + bounds, + self.gait_indices + phases, + ] + + self.clock_inputs[0] = np.sin(2 * np.pi * self.foot_indices[0]) + self.clock_inputs[1] = np.sin(2 * np.pi * self.foot_indices[1]) + self.clock_inputs[2] = np.sin(2 * np.pi * self.foot_indices[2]) + self.clock_inputs[3] = np.sin(2 * np.pi * self.foot_indices[3]) + + foot_contact_rate = np.abs(self.foot_contact_forces_mag - self.prev_foot_contact_forces_mag) + self.prev_foot_contact_forces_mag = self.foot_contact_forces_mag.copy() + + infos = { + "joint_pos": self.dof_pos[np.newaxis, :], + "joint_vel": self.dof_vel[np.newaxis, :], + "joint_pos_target": self.joint_pos_target[np.newaxis, :], + "joint_vel_target": self.joint_vel_target[np.newaxis, :], + "body_linear_vel": self.body_linear_vel[np.newaxis, :], + "body_angular_vel": self.body_angular_vel[np.newaxis, :], + "body_pos": self.pos[np.newaxis, :].copy(), + "contact_state": self.contact_state[np.newaxis, :], + "body_linear_vel_cmd": self.commands[np.newaxis, 0:2], + "body_angular_vel_cmd": self.commands[np.newaxis, 2:], + "torques": self.torques, + "foot_contact_forces_mag": self.foot_contact_forces_mag.copy(), + "joint_acc": joint_acc[np.newaxis, :], + "joint_jerk": joint_jerk[np.newaxis, :], + "foot_contact_rate": foot_contact_rate[np.newaxis, :], + } + + self.timestep += 1 + return None, None, None, infos diff --git a/Go2Py/utils/point_cloud2.py b/Go2Py/utils/point_cloud2.py new file mode 100644 index 0000000..36126f5 --- /dev/null +++ b/Go2Py/utils/point_cloud2.py @@ -0,0 +1,329 @@ +# Copyright 2008 Willow Garage, Inc. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the name of the Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived from +# this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + + +""" +Serialization of sensor_msgs.PointCloud2 messages. + +Author: Tim Field +ROS 2 port by Sebastian Grans +File originally ported from: +https://github.com/ros/common_msgs/blob/f48b00d43cdb82ed9367e0956db332484f676598/ +sensor_msgs/src/sensor_msgs/point_cloud2.py +""" + +import array +from collections import namedtuple +import sys +from typing import Iterable, List, NamedTuple, Optional + +import numpy as np +try: + from numpy.lib.recfunctions import (structured_to_unstructured, unstructured_to_structured) +except ImportError: + from sensor_msgs_py.numpy_compat import (structured_to_unstructured, + unstructured_to_structured) + +from sensor_msgs.msg import PointCloud2, PointField +from std_msgs.msg import Header + + +_DATATYPES = {} +_DATATYPES[PointField.INT8] = np.dtype(np.int8) +_DATATYPES[PointField.UINT8] = np.dtype(np.uint8) +_DATATYPES[PointField.INT16] = np.dtype(np.int16) +_DATATYPES[PointField.UINT16] = np.dtype(np.uint16) +_DATATYPES[PointField.INT32] = np.dtype(np.int32) +_DATATYPES[PointField.UINT32] = np.dtype(np.uint32) +_DATATYPES[PointField.FLOAT32] = np.dtype(np.float32) +_DATATYPES[PointField.FLOAT64] = np.dtype(np.float64) + +DUMMY_FIELD_PREFIX = 'unnamed_field' + + +def read_points( + cloud: PointCloud2, + field_names: Optional[List[str]] = None, + skip_nans: bool = False, + uvs: Optional[Iterable] = None, + reshape_organized_cloud: bool = False) -> np.ndarray: + """ + Read points from a sensor_msgs.PointCloud2 message. + + :param cloud: The point cloud to read from sensor_msgs.PointCloud2. + :param field_names: The names of fields to read. If None, read all fields. + (Type: Iterable, Default: None) + :param skip_nans: If True, then don't return any point with a NaN value. + (Type: Bool, Default: False) + :param uvs: If specified, then only return the points at the given + coordinates. (Type: Iterable, Default: None) + :param reshape_organized_cloud: Returns the array as an 2D organized point cloud if set. + :return: Structured NumPy array containing all points. + """ + assert isinstance(cloud, PointCloud2), \ + 'Cloud is not a sensor_msgs.msg.PointCloud2' + + # Cast bytes to numpy array + points = np.ndarray( + shape=(cloud.width * cloud.height, ), + dtype=dtype_from_fields(cloud.fields, point_step=cloud.point_step), + buffer=cloud.data) + + # Keep only the requested fields + if field_names is not None: + assert all(field_name in points.dtype.names for field_name in field_names), \ + 'Requests field is not in the fields of the PointCloud!' + # Mask fields + points = points[list(field_names)] + + # Swap array if byte order does not match + if bool(sys.byteorder != 'little') != bool(cloud.is_bigendian): + points = points.byteswap(inplace=True) + + # Check if we want to drop points with nan values + if skip_nans and not cloud.is_dense: + # Init mask which selects all points + not_nan_mask = np.ones(len(points), dtype=bool) + for field_name in points.dtype.names: + # Only keep points without any non values in the mask + not_nan_mask = np.logical_and( + not_nan_mask, ~np.isnan(points[field_name])) + # Select these points + points = points[not_nan_mask] + + # Select points indexed by the uvs field + if uvs is not None: + # Don't convert to numpy array if it is already one + if not isinstance(uvs, np.ndarray): + uvs = np.fromiter(uvs, int) + # Index requested points + points = points[uvs] + + # Cast into 2d array if cloud is 'organized' + if reshape_organized_cloud and cloud.height > 1: + points = points.reshape(cloud.width, cloud.height) + + return points + + +def read_points_numpy( + cloud: PointCloud2, + field_names: Optional[List[str]] = None, + skip_nans: bool = False, + uvs: Optional[Iterable] = None, + reshape_organized_cloud: bool = False) -> np.ndarray: + """ + Read equally typed fields from sensor_msgs.PointCloud2 message as a unstructured numpy array. + + This method is better suited if one wants to perform math operations + on e.g. all x,y,z fields. + But it is limited to fields with the same dtype as unstructured numpy arrays + only contain one dtype. + + :param cloud: The point cloud to read from sensor_msgs.PointCloud2. + :param field_names: The names of fields to read. If None, read all fields. + (Type: Iterable, Default: None) + :param skip_nans: If True, then don't return any point with a NaN value. + (Type: Bool, Default: False) + :param uvs: If specified, then only return the points at the given + coordinates. (Type: Iterable, Default: None) + :param reshape_organized_cloud: Returns the array as an 2D organized point cloud if set. + :return: Numpy array containing all points. + """ + assert all(cloud.fields[0].datatype == field.datatype for field in cloud.fields[1:]), \ + 'All fields need to have the same datatype. Use `read_points()` otherwise.' + structured_numpy_array = read_points( + cloud, field_names, skip_nans, uvs, reshape_organized_cloud) + return structured_to_unstructured(structured_numpy_array) + + +def read_points_list( + cloud: PointCloud2, + field_names: Optional[List[str]] = None, + skip_nans: bool = False, + uvs: Optional[Iterable] = None) -> List[NamedTuple]: + """ + Read points from a sensor_msgs.PointCloud2 message. + + This function returns a list of namedtuples. It operates on top of the + read_points method. For more efficient access use read_points directly. + + :param cloud: The point cloud to read from. (Type: sensor_msgs.PointCloud2) + :param field_names: The names of fields to read. If None, read all fields. + (Type: Iterable, Default: None) + :param skip_nans: If True, then don't return any point with a NaN value. + (Type: Bool, Default: False) + :param uvs: If specified, then only return the points at the given + coordinates. (Type: Iterable, Default: None] + :return: List of namedtuples containing the values for each point + """ + assert isinstance(cloud, PointCloud2), \ + 'cloud is not a sensor_msgs.msg.PointCloud2' + + if field_names is None: + field_names = [f.name for f in cloud.fields] + + Point = namedtuple('Point', field_names) + + return [Point._make(p) for p in read_points(cloud, field_names, + skip_nans, uvs)] + + +def dtype_from_fields(fields: Iterable[PointField], point_step: Optional[int] = None) -> np.dtype: + """ + Convert a Iterable of sensor_msgs.msg.PointField messages to a np.dtype. + + :param fields: The point cloud fields. + (Type: iterable of sensor_msgs.msg.PointField) + :param point_step: Point step size in bytes. Calculated from the given fields by default. + (Type: optional of integer) + :returns: NumPy datatype + """ + # Create a lists containing the names, offsets and datatypes of all fields + field_names = [] + field_offsets = [] + field_datatypes = [] + for i, field in enumerate(fields): + # Datatype as numpy datatype + datatype = _DATATYPES[field.datatype] + # Name field + if field.name == '': + name = f'{DUMMY_FIELD_PREFIX}_{i}' + else: + name = field.name + # Handle fields with count > 1 by creating subfields with a suffix consiting + # of "_" followed by the subfield counter [0 -> (count - 1)] + assert field.count > 0, "Can't process fields with count = 0." + for a in range(field.count): + # Add suffix if we have multiple subfields + if field.count > 1: + subfield_name = f'{name}_{a}' + else: + subfield_name = name + assert subfield_name not in field_names, 'Duplicate field names are not allowed!' + field_names.append(subfield_name) + # Create new offset that includes subfields + field_offsets.append(field.offset + a * datatype.itemsize) + field_datatypes.append(datatype.str) + + # Create dtype + dtype_dict = { + 'names': field_names, + 'formats': field_datatypes, + 'offsets': field_offsets + } + if point_step is not None: + dtype_dict['itemsize'] = point_step + return np.dtype(dtype_dict) + + +def create_cloud( + header: Header, + fields: Iterable[PointField], + points: Iterable) -> PointCloud2: + """ + Create a sensor_msgs.msg.PointCloud2 message. + + :param header: The point cloud header. (Type: std_msgs.msg.Header) + :param fields: The point cloud fields. + (Type: iterable of sensor_msgs.msg.PointField) + :param points: The point cloud points. List of iterables, i.e. one iterable + for each point, with the elements of each iterable being the + values of the fields for that point (in the same order as + the fields parameter) + :return: The point cloud as sensor_msgs.msg.PointCloud2 + """ + # Check if input is numpy array + if isinstance(points, np.ndarray): + # Check if this is an unstructured array + if points.dtype.names is None: + assert all(fields[0].datatype == field.datatype for field in fields[1:]), \ + 'All fields need to have the same datatype. Pass a structured NumPy array \ + with multiple dtypes otherwise.' + # Convert unstructured to structured array + points = unstructured_to_structured( + points, + dtype=dtype_from_fields(fields)) + else: + assert points.dtype == dtype_from_fields(fields), \ + 'PointFields and structured NumPy array dtype do not match for all fields! \ + Check their field order, names and types.' + else: + # Cast python objects to structured NumPy array (slow) + points = np.array( + # Points need to be tuples in the structured array + list(map(tuple, points)), + dtype=dtype_from_fields(fields)) + + # Handle organized clouds + assert len(points.shape) <= 2, \ + 'Too many dimensions for organized cloud! \ + Points can only be organized in max. two dimensional space' + height = 1 + width = points.shape[0] + # Check if input points are an organized cloud (2D array of points) + if len(points.shape) == 2: + height = points.shape[1] + + # Convert numpy points to array.array + memory_view = memoryview(points) + casted = memory_view.cast('B') + array_array = array.array('B') + array_array.frombytes(casted) + + # Put everything together + cloud = PointCloud2( + header=header, + height=height, + width=width, + is_dense=False, + is_bigendian=sys.byteorder != 'little', + fields=fields, + point_step=points.dtype.itemsize, + row_step=(points.dtype.itemsize * width)) + # Set cloud via property instead of the constructor because of the bug described in + # https://github.com/ros2/common_interfaces/issues/176 + cloud.data = array_array + return cloud + + +def create_cloud_xyz32(header: Header, points: Iterable) -> PointCloud2: + """ + Create a sensor_msgs.msg.PointCloud2 message with (x, y, z) fields. + + :param header: The point cloud header. (Type: std_msgs.msg.Header) + :param points: The point cloud points. (Type: Iterable) + :return: The point cloud as sensor_msgs.msg.PointCloud2. + """ + fields = [PointField(name='x', offset=0, + datatype=PointField.FLOAT32, count=1), + PointField(name='y', offset=4, + datatype=PointField.FLOAT32, count=1), + PointField(name='z', offset=8, + datatype=PointField.FLOAT32, count=1)] + return create_cloud(header, fields, points) \ No newline at end of file diff --git a/Go2Py/utils/ros2.py b/Go2Py/utils/ros2.py index 4d25f91..ca31767 100644 --- a/Go2Py/utils/ros2.py +++ b/Go2Py/utils/ros2.py @@ -9,6 +9,85 @@ from rclpy.qos import QoSProfile from rclpy.executors import MultiThreadedExecutor from geometry_msgs.msg import TransformStamped from scipy.spatial.transform import Rotation as R +from sensor_msgs.msg import PointCloud2 +from sensor_msgs_py import point_cloud2 +from sensor_msgs.msg import Image, CameraInfo +from cv_bridge import CvBridge +import cv2 +from Go2Py.utils.point_cloud2 import read_points_numpy +import rclpy +from rclpy.node import Node +from nav_msgs.msg import Odometry + +import rclpy +from rclpy.node import Node +from nav_msgs.msg import Odometry + +import numpy as np +from scipy.spatial.transform import Rotation as R + +class ROS2OdometryReader(Node): + """ + A class for subscribing to and retrieving Odometry messages. + + Args: + odom_topic (str): The topic name for the odometry data. + node_name (str): A unique name for this node. + + Attributes: + odom (Odometry): The latest odometry message received from the topic. + """ + + def __init__(self, odom_topic, node_name): + super().__init__(f'{node_name}_odom_reader') + self.odom = None # Stores the latest odometry message + + # Create a subscription to the specified odometry topic + self.odom_subscriber = self.create_subscription( + Odometry, + odom_topic, + self.odom_callback, + 10 + ) + + def odom_callback(self, msg): + """ + Callback function that stores the latest odometry message. + + Args: + msg (Odometry): The odometry message received. + """ + self.odom = msg + + def get_odometry(self): + """ + Returns the latest odometry message received from the topic. + + Returns: + Odometry: The latest odometry message. + """ + return self.odom + + def get_pose(self): + if self.odom is not None: + position = self.odom.pose.pose.position + orientation = self.odom.pose.pose.orientation + t = np.array([position.x, position.y, position.z]) + q = np.array([orientation.x, orientation.y, orientation.z, orientation.w]) + Rot = R.from_quat(q).as_matrix() + T = np.eye(4) + T[:3, :3] = Rot + T[:3, -1] = t + return T + else: + return None + + def close(self): + """ + Destroys the node, cleaning up resources. + """ + self.destroy_node() + def ros2_init(args=None): rclpy.init(args=args) @@ -49,10 +128,50 @@ class ROS2ExecutorManager: if self.executor_thread: self.executor_thread.join() -class ROS2TFInterface(Node): +# class ROS2TFInterface(Node): +# def __init__(self, parent_name, child_name, node_name): +# super().__init__(f'{node_name}_tf2_listener') +# self.parent_name = parent_name +# self.child_name = child_name +# self.tfBuffer = tf2_ros.Buffer() +# self.listener = tf2_ros.TransformListener(self.tfBuffer, self) +# self.T = None +# self.stamp = None +# self.running = True +# self.thread = threading.Thread(target=self.update_loop) +# self.thread.start() +# self.trans = None + +# def update_loop(self): +# while self.running: +# try: +# self.trans = self.tfBuffer.lookup_transform(self.parent_name, self.child_name, rclpy.time.Time(), rclpy.time.Duration(seconds=0.1)) +# except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException) as e: +# print(e) +# time.sleep(0.01) + +# def get_pose(self): +# if self.trans is None: +# return None +# else: +# translation = [self.trans.transform.translation.x, self.trans.transform.translation.y, self.trans.transform.translation.z] +# rotation = [self.trans.transform.rotation.x, self.trans.transform.rotation.y, self.trans.transform.rotation.z, self.trans.transform.rotation.w] +# self.T = np.eye(4) +# self.T[0:3, 0:3] = R.from_quat(rotation).as_matrix() +# self.T[:3, 3] = translation +# self.stamp = self.trans.header.stamp.nanosec * 1e-9 + self.trans.header.stamp.sec +# return self.T + +# def close(self): +# self.running = False +# self.thread.join() +# self.destroy_node() + + +class ROS2TFInterface(Node): def __init__(self, parent_name, child_name, node_name): - super().__init__(f'{node_name}_tf2_listener') + super().__init__(f"{node_name}_tf2_listener") self.parent_name = parent_name self.child_name = child_name self.tfBuffer = tf2_ros.Buffer() @@ -60,31 +179,137 @@ class ROS2TFInterface(Node): self.T = None self.stamp = None self.running = True - self.thread = threading.Thread(target=self.update_loop) - self.thread.start() self.trans = None - def update_loop(self): - while self.running: - try: - self.trans = self.tfBuffer.lookup_transform(self.parent_name, self.child_name, rclpy.time.Time(), rclpy.time.Duration(seconds=0.1)) - except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException) as e: - print(e) - time.sleep(0.01) - def get_pose(self): - if self.trans is None: + try: + self.trans = self.tfBuffer.lookup_transform( + self.parent_name, + self.child_name, + rclpy.time.Time(), + rclpy.time.Duration(seconds=0.1), + ) + except ( + tf2_ros.LookupException, + tf2_ros.ConnectivityException, + tf2_ros.ExtrapolationException, + ) as e: return None - else: - translation = [self.trans.transform.translation.x, self.trans.transform.translation.y, self.trans.transform.translation.z] - rotation = [self.trans.transform.rotation.x, self.trans.transform.rotation.y, self.trans.transform.rotation.z, self.trans.transform.rotation.w] - self.T = np.eye(4) - self.T[0:3, 0:3] = R.from_quat(rotation).as_matrix() - self.T[:3, 3] = translation - self.stamp = self.trans.header.stamp.nanosec * 1e-9 + self.trans.header.stamp.sec - return self.T + + translation = [ + self.trans.transform.translation.x, + self.trans.transform.translation.y, + self.trans.transform.translation.z, + ] + rotation = [ + self.trans.transform.rotation.x, + self.trans.transform.rotation.y, + self.trans.transform.rotation.z, + self.trans.transform.rotation.w, + ] + self.T = np.eye(4) + self.T[0:3, 0:3] = R.from_quat(rotation).as_matrix() + self.T[:3, 3] = translation + self.stamp = ( + self.trans.header.stamp.nanosec * 1e-9 + self.trans.header.stamp.sec + ) + + return self.T def close(self): self.running = False - self.thread.join() + self.destroy_node() + + +class PoindCloud2Bridge(Node): + def __init__(self, topic_name): + super().__init__("point_cloud_listener") + self.subscription = self.create_subscription( + PointCloud2, topic_name, self.listener_callback, 1 + ) + self.data = None + self.new_frame_flag = False + self.points = None + + self._points = None + self.points = None + self.ready = False + self.running = True + + def listener_callback(self, msg): + # Read the x, y, z fields from the PointCloud2 message + self._points = read_points_numpy( + msg, + field_names=("x", "y", "z"), + skip_nans=True, + reshape_organized_cloud=True, + ) + # self._points = point_cloud2.read_points( + # msg, + # field_names=("x", "y", "z"), + # skip_nans=True, + # ) + # _points = np.reshape(_points, (-1, 16, 3)) + # self._points = np.reshape(_points, (-1, 16, 3)) + self.new_frame_flag = True + + @property + def state(self): + return self._points + +class ROS2CameraReader(Node): + """ + A class for interacting with a ROS2 camera topics. + + Args: + image_topic (str): The topic name for the image stream. + camera_info_topic (str, optional): The topic name for the camera information. + K (numpy.ndarray, optional): The intrinsic camera matrix for the raw (distorted) images. + D (numpy.ndarray, optional): The distortion coefficients. + + Attributes: + color_frame (numpy.ndarray): The latest image frame received from the topic. + camera_info (CameraInfo): The latest camera information received from the topic. + K (numpy.ndarray): The intrinsic camera matrix. + D (numpy.ndarray): The distortion coefficients. + """ + def __init__(self, image_topic, node_name, camera_info_topic=None, K=None, D=None): + super().__init__(f'{node_name}_camera_reader') + self.bridge = CvBridge() + self.color_frame = None + self.camera_info = None + self.K = K + self.D = D + self.node_name = node_name + + self.image_subscriber = self.create_subscription(Image, image_topic, self.image_callback, 10) + if camera_info_topic: + self.camera_info_subscriber = self.create_subscription(CameraInfo, camera_info_topic, self.camera_info_callback, 10) + + def image_callback(self, msg): + self.color_frame = self.bridge.imgmsg_to_cv2(msg, desired_encoding='passthrough') + + def camera_info_callback(self, msg): + self.camera_info = msg + self.K = np.array(msg.k).reshape((3, 3)) + self.D = np.array(msg.d) + + def get_image(self): + """ + Returns the latest image frame received from the topic. + + Returns: + numpy.ndarray: The latest image frame received from the topic. + """ + return self.color_frame + + def get_intrinsics(self): + """ + Returns the intrinsic camera matrix. + + Returns: + numpy.ndarray: The intrinsic camera matrix. + """ + return {'K': self.K, 'D': self.D} + def close(self): self.destroy_node() \ No newline at end of file diff --git a/dds_bridge/09-NeuroDiffSim-RL-controller.ipynb b/dds_bridge/09-NeuroDiffSim-RL-controller.ipynb new file mode 100644 index 0000000..430e432 --- /dev/null +++ b/dds_bridge/09-NeuroDiffSim-RL-controller.ipynb @@ -0,0 +1,1077 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "RL policy based on the [SoloParkour: Constrained Reinforcement Learning for Visual Locomotion from Privileged Experience](https://arxiv.org/abs/2409.13678). " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Flat Ground" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Test In Simulation" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from Go2Py.robot.fsm import FSM\n", + "from Go2Py.robot.remote import KeyboardRemote, XBoxRemote\n", + "from Go2Py.robot.safety import SafetyHypervisor\n", + "from Go2Py.sim.mujoco import Go2Sim\n", + "from Go2Py.control.neuro_diff_sim import *\n", + "import torch" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "from Go2Py.robot.model import FrictionModel\n", + "friction_model = None\n", + "Fs = np.zeros(12)\n", + "mu_v = np.zeros(12)\n", + "#mu_v[[2,5,8,11]] = np.array([0.2167, -0.0647, -0.0420, -0.0834])\n", + "#Fs[[2,5,8,11]] = np.array([1.5259, 1.2380, 0.8917, 2.2461])\n", + "\n", + "#mu_v[[0,3,6,9]] = np.array([0., 0., 0., 0.])\n", + "#Fs[[0,3,6,9]] = np.array([1.5, 1.5, 1.5, 1.5])\n", + "#mu_v[[2,5,8,11]] = np.array([0., 0., 0., 0.])\n", + "#Fs[[2,5,8,11]] = np.array([1.5, 1.5, 1.5, 1.5])\n", + "\n", + "friction_model = FrictionModel(Fs=1.5, mu_v=0.3)\n", + "#friction_model = FrictionModel(Fs=0., mu_v=0.)\n", + "#friction_model = FrictionModel(Fs=Fs, mu_v=mu_v)\n", + "robot = Go2Sim(dt = 0.001, friction_model=friction_model)" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "remote = KeyboardRemote() # XBoxRemote() # KeyboardRemote()\n", + "robot.sitDownReset()\n", + "safety_hypervisor = SafetyHypervisor(robot)" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "def getRemote(remote):\n", + " commands = remote.getCommands()\n", + " commands[0] *= 0.6\n", + " commands[1] *= 0.6\n", + " zero_commands_xy = np.linalg.norm(commands[:2]) <= 0.2\n", + " zero_commands_yaw = np.abs(commands[2]) <= 0.2\n", + " if zero_commands_xy:\n", + " commands[:2] = np.zeros_like(commands[:2])\n", + " if zero_commands_yaw:\n", + " commands[2] = 0\n", + " return commands" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "class NeuroDiffSimController:\n", + " def __init__(self, robot, remote, checkpoint):\n", + " self.remote = remote\n", + " self.robot = robot\n", + " self.policy = Policy(checkpoint)\n", + " self.command_profile = CommandInterface()\n", + " self.agent = NeuroDiffSimAgent(self.command_profile, self.robot)\n", + " self.hist_data = {}\n", + "\n", + " def init(self):\n", + " self.obs = self.agent.reset()\n", + " self.policy_info = {}\n", + " self.command_profile.yaw_vel_cmd = 0.0\n", + " self.command_profile.x_vel_cmd = 0.0\n", + " self.command_profile.y_vel_cmd = 0.0\n", + "\n", + " def update(self, robot, remote):\n", + " if not hasattr(self, \"obs\"):\n", + " self.init()\n", + " commands = getRemote(remote)\n", + " self.command_profile.yaw_vel_cmd = -commands[2]\n", + " self.command_profile.x_vel_cmd = commands[1]\n", + " self.command_profile.y_vel_cmd = -commands[0]\n", + "\n", + " self.obs = self.agent.get_obs()\n", + " action = self.policy(self.obs, self.policy_info)\n", + " _, self.ret, self.done, self.info = self.agent.step(action)\n", + " for key, value in self.info.items():\n", + " if key in self.hist_data:\n", + " self.hist_data[key].append(value)\n", + " else:\n", + " self.hist_data[key] = [value]" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "robot.getJointStates()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from Go2Py import ASSETS_PATH\n", + "import os\n", + "checkpoint_path = os.path.join(ASSETS_PATH, 'checkpoints/neuro_diff_sim/neuro_diff_sim.pt')\n", + "\n", + "controller = NeuroDiffSimController(robot, remote, checkpoint_path)\n", + "decimation = 20\n", + "fsm = FSM(robot, remote, safety_hypervisor, control_dT=decimation * robot.dt, user_controller_callback=controller.update)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Slippage Analysis" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "contacts = []\n", + "feet_vels = []\n", + "\n", + "while True:\n", + " if remote.xbox_controller.digital_cmd[1]:\n", + " break\n", + " contact_state = robot.getFootContact()>15\n", + " sites = ['FR_foot', 'FL_foot', 'RR_foot', 'RL_foot']\n", + " feet_vel = [np.linalg.norm(robot.getFootVelInWorld(s)) for s in sites]\n", + " contacts.append(contact_state)\n", + " feet_vels.append(feet_vel)\n", + " time.sleep(0.01)\n", + "\n", + "feet_vels = np.stack(feet_vels)\n", + "contacts = np.stack(contacts)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import matplotlib.pyplot as plt\n", + "start = 300\n", + "end = 1200\n", + "plt.plot(contacts[start:end,0])\n", + "plt.plot(feet_vels[start:end,0])\n", + "plt.legend(['contact state', 'foot velocity'])\n", + "plt.grid(True)\n", + "plt.tight_layout()\n", + "plt.savefig('foot_slipping_fric0.2.png')" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "**To Do**\n", + "- Train a policy without any actuator friction and check the plots for friction 0.2 and 0.6 \n", + "- Do the same experiment for the walk-these-ways policy\n", + "- While testing the walk these ways, check the output of the adaptation module for various friction numbers, any correlation?" + ] + }, + { + "cell_type": "code", + "execution_count": 8, + "metadata": {}, + "outputs": [], + "source": [ + "fsm.close()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Foot Contanct Analysis" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "np.array(controller.hist_data[\"body_pos\"])[0, 0, -1]" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "plt.plot(np.array(controller.hist_data[\"body_pos\"])[:, 0, -1])" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import matplotlib.pyplot as plt\n", + "# Assuming 'controller.hist_data[\"torques\"]' is a dictionary with torque profiles\n", + "torques = np.array(controller.hist_data[\"body_linear_vel\"])[:, 0, :, 0]\n", + "\n", + "# Number of torque profiles\n", + "torque_nb = torques.shape[1]\n", + "\n", + "# Number of rows needed for the grid, with 3 columns per row\n", + "n_cols = 3\n", + "n_rows = int(np.ceil(torque_nb / n_cols))\n", + "\n", + "# Create the figure and axes for subplots\n", + "fig, axes = plt.subplots(n_rows, n_cols, figsize=(15, 5 * n_rows))\n", + "\n", + "# Flatten the axes array for easy indexing (in case of multiple rows)\n", + "axes = axes.flatten()\n", + "\n", + "# Plot each torque profile\n", + "for i in range(torque_nb):\n", + " axes[i].plot(np.arange(torques.shape[0]) * robot.dt * decimation, torques[:, i])\n", + " axes[i].set_title(f'Torque {i+1}')\n", + " axes[i].set_xlabel('Time')\n", + " axes[i].set_ylabel('Torque Value')\n", + " axes[i].grid(True)\n", + "\n", + "# Remove any empty subplots if torque_nb is not a multiple of 3\n", + "for j in range(torque_nb, len(axes)):\n", + " fig.delaxes(axes[j])\n", + "\n", + "# Adjust layout\n", + "plt.tight_layout()\n", + "plt.savefig(\"torque_profile.png\")\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import matplotlib.pyplot as plt\n", + "# Assuming 'controller.hist_data[\"torques\"]' is a dictionary with torque profiles\n", + "torques = np.array(controller.hist_data[\"torques\"])\n", + "\n", + "# Number of torque profiles\n", + "torque_nb = torques.shape[1]\n", + "\n", + "# Number of rows needed for the grid, with 3 columns per row\n", + "n_cols = 3\n", + "n_rows = int(np.ceil(torque_nb / n_cols))\n", + "\n", + "# Create the figure and axes for subplots\n", + "fig, axes = plt.subplots(n_rows, n_cols, figsize=(15, 5 * n_rows))\n", + "\n", + "# Flatten the axes array for easy indexing (in case of multiple rows)\n", + "axes = axes.flatten()\n", + "\n", + "# Plot each torque profile\n", + "for i in range(torque_nb):\n", + " axes[i].plot(np.arange(torques.shape[0]) * robot.dt * decimation, torques[:, i])\n", + " axes[i].set_title(f'Torque {i+1}')\n", + " axes[i].set_xlabel('Time')\n", + " axes[i].set_ylabel('Torque Value')\n", + " axes[i].grid(True)\n", + "\n", + "# Remove any empty subplots if torque_nb is not a multiple of 3\n", + "for j in range(torque_nb, len(axes)):\n", + " fig.delaxes(axes[j])\n", + "\n", + "# Adjust layout\n", + "plt.tight_layout()\n", + "plt.savefig(\"torque_profile.png\")\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Extract the joint position data for the first joint over time\n", + "joint_pos = np.array(controller.hist_data[\"joint_vel\"])[:, 0]\n", + "\n", + "# Number of data points in joint_pos\n", + "n_data_points = len(joint_pos)\n", + "\n", + "# Since you're plotting only one joint, no need for multiple subplots in this case.\n", + "# But to follow the grid requirement, we'll replicate the data across multiple subplots.\n", + "# For example, let's assume you want to visualize this data 9 times in a 3x3 grid.\n", + "\n", + "n_cols = 3\n", + "n_rows = int(np.ceil(torque_nb / n_cols))\n", + "\n", + "# Create the figure and axes for subplots\n", + "fig, axes = plt.subplots(n_rows, n_cols, figsize=(15, 5 * n_rows))\n", + "\n", + "# Flatten the axes array for easy indexing (in case of multiple rows)\n", + "axes = axes.flatten()\n", + "\n", + "# Plot the same joint position data in every subplot (as per grid requirement)\n", + "for i in range(n_rows * n_cols):\n", + " axes[i].plot(joint_pos[:, i])\n", + " axes[i].set_title(f'Joint Position {i+1}')\n", + " axes[i].set_xlabel('Time')\n", + " axes[i].set_ylabel('Position Value')\n", + "\n", + "# Adjust layout\n", + "plt.tight_layout()\n", + "plt.savefig(\"joint_position_profile.png\")\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import matplotlib.pyplot as plt\n", + "# Assuming 'controller.hist_data[\"foot_contact_forces_mag\"]' is a dictionary with foot contact force magnitudes\n", + "foot_contact_forces_mag = np.array(controller.hist_data[\"foot_contact_forces_mag\"])\n", + "\n", + "# Number of feet (foot_nb)\n", + "foot_nb = foot_contact_forces_mag.shape[1]\n", + "\n", + "# Number of rows needed for the grid, with 3 columns per row\n", + "n_cols = 3\n", + "n_rows = int(np.ceil(foot_nb / n_cols))\n", + "\n", + "# Create the figure and axes for subplots\n", + "fig, axes = plt.subplots(n_rows, n_cols, figsize=(15, 5 * n_rows))\n", + "\n", + "# Flatten the axes array for easy indexing (in case of multiple rows)\n", + "axes = axes.flatten()\n", + "\n", + "# Plot each foot's contact force magnitude\n", + "for i in range(foot_nb):\n", + " axes[i].plot(foot_contact_forces_mag[:, i])\n", + " axes[i].set_title(f'Foot {i+1} Contact Force Magnitude')\n", + " axes[i].set_xlabel('Time')\n", + " axes[i].set_ylabel('Force Magnitude')\n", + "\n", + "# Remove any empty subplots if foot_nb is not a multiple of 3\n", + "for j in range(foot_nb, len(axes)):\n", + " fig.delaxes(axes[j])\n", + "\n", + "# Adjust layout\n", + "plt.tight_layout()\n", + "plt.savefig(\"foot_contact_profile.png\")\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Extract the joint acceleration data for the first joint over time\n", + "joint_acc = np.array(controller.hist_data[\"joint_acc\"])[:, 0]\n", + "\n", + "# Number of data points in joint_acc\n", + "n_data_points = len(joint_acc)\n", + "\n", + "# Number of feet (foot_nb)\n", + "foot_nb = joint_acc.shape[1]\n", + "\n", + "# Number of rows needed for the grid, with 3 columns per row\n", + "n_cols = 3\n", + "n_rows = int(np.ceil(foot_nb / n_cols))\n", + "\n", + "# Create the figure and axes for subplots\n", + "fig, axes = plt.subplots(n_rows, n_cols, figsize=(15, 5 * n_rows))\n", + "\n", + "# Flatten the axes array for easy indexing\n", + "axes = axes.flatten()\n", + "\n", + "# Plot the same joint acceleration data in every subplot (as per grid requirement)\n", + "for i in range(n_rows * n_cols):\n", + " axes[i].plot(joint_acc[:, i])\n", + " axes[i].set_title(f'Joint Acceleration {i+1}')\n", + " axes[i].set_xlabel('Time')\n", + " axes[i].set_ylabel('Acceleration Value')\n", + "\n", + "# Adjust layout to prevent overlap\n", + "plt.tight_layout()\n", + "plt.show()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Extract the joint jerk data over time\n", + "joint_jerk = np.array(controller.hist_data[\"joint_jerk\"])[:, 0]\n", + "\n", + "# Number of data points in joint_jerk\n", + "n_data_points = len(joint_jerk)\n", + "\n", + "# Number of joints (assuming the second dimension corresponds to joints)\n", + "num_joints = joint_jerk.shape[1]\n", + "\n", + "# Number of columns per row in the subplot grid\n", + "n_cols = 3\n", + "# Number of rows needed for the grid\n", + "n_rows = int(np.ceil(num_joints / n_cols))\n", + "\n", + "# Create the figure and axes for subplots\n", + "fig, axes = plt.subplots(n_rows, n_cols, figsize=(15, 5 * n_rows))\n", + "\n", + "# Flatten the axes array for easy indexing\n", + "axes = axes.flatten()\n", + "\n", + "# Plot the joint jerk data for each joint\n", + "for i in range(num_joints):\n", + " axes[i].plot(joint_jerk[:, i])\n", + " axes[i].set_title(f'Joint Jerk {i+1}')\n", + " axes[i].set_xlabel('Time')\n", + " axes[i].set_ylabel('Jerk Value')\n", + "\n", + "# Hide any unused subplots\n", + "for i in range(num_joints, len(axes)):\n", + " fig.delaxes(axes[i])\n", + "\n", + "# Adjust layout to prevent overlap\n", + "plt.tight_layout()\n", + "plt.show()\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "# Extract the foot contact rate data over time\n", + "foot_contact_rate = np.array(controller.hist_data[\"foot_contact_rate\"])[:, 0]\n", + "\n", + "# Number of data points in foot_contact_rate\n", + "n_data_points = foot_contact_rate.shape[0]\n", + "\n", + "# Number of feet (assuming the second dimension corresponds to feet)\n", + "num_feet = foot_contact_rate.shape[1]\n", + "\n", + "# Number of columns per row in the subplot grid\n", + "n_cols = 3\n", + "# Number of rows needed for the grid\n", + "n_rows = int(np.ceil(num_feet / n_cols))\n", + "\n", + "# Create the figure and axes for subplots\n", + "fig, axes = plt.subplots(n_rows, n_cols, figsize=(15, 5 * n_rows))\n", + "\n", + "# Flatten the axes array for easy indexing\n", + "axes = axes.flatten()\n", + "\n", + "# Plot the foot contact rate data for each foot\n", + "for i in range(num_feet):\n", + " axes[i].plot(foot_contact_rate[:, i])\n", + " axes[i].set_title(f'Foot Contact Rate {i+1}')\n", + " axes[i].set_xlabel('Time')\n", + " axes[i].set_ylabel('Contact Rate')\n", + "\n", + "# Hide any unused subplots\n", + "for i in range(num_feet, len(axes)):\n", + " fig.delaxes(axes[i])\n", + "\n", + "# Adjust layout to prevent overlap\n", + "plt.tight_layout()\n", + "plt.show()\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Test on Real Robot (ToDo)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from Go2Py.robot.fsm import FSM\n", + "from Go2Py.robot.remote import XBoxRemote\n", + "from Go2Py.robot.safety import SafetyHypervisor\n", + "from Go2Py.control.neuro_diff_sim import *" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "from Go2Py.robot.interface import GO2Real\n", + "import numpy as np\n", + "robot = GO2Real(mode='lowlevel')" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "remote = XBoxRemote() # KeyboardRemote()\n", + "safety_hypervisor = SafetyHypervisor(robot)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "robot.getJointStates()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Make sure the robot can take commands from python. The next cell should make the joints free to move (no damping)." + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "import time\n", + "start_time = time.time()\n", + "\n", + "while time.time()-start_time < 30:\n", + " q = np.zeros(12) \n", + " dq = np.zeros(12)\n", + " kp = np.ones(12)*0.0\n", + " kd = np.ones(12)*0.0\n", + " tau = np.zeros(12)\n", + " tau[0] = 0.0\n", + " robot.setCommands(q, dq, kp, kd, tau)\n", + " time.sleep(0.02)" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "def getRemote(remote):\n", + " commands = remote.getCommands()\n", + " commands[0] *= 0.6\n", + " commands[1] *= 0.6\n", + " zero_commands = np.logical_and(\n", + " np.linalg.norm(commands[:2]) <= 0.2,\n", + " np.abs(commands[2]) <= 0.2\n", + " )\n", + " if zero_commands:\n", + " commands = np.zeros_like(commands)\n", + " return commands" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [], + "source": [ + "class NeuroDiffSimController:\n", + " def __init__(self, robot, remote, checkpoint):\n", + " self.remote = remote\n", + " self.robot = robot\n", + " self.policy = Policy(checkpoint)\n", + " self.command_profile = CommandInterface()\n", + " self.agent = NeuroDiffSimAgent(self.command_profile, self.robot)\n", + " self.hist_data = {}\n", + "\n", + " def init(self):\n", + " self.obs = self.agent.reset()\n", + " self.policy_info = {}\n", + " self.command_profile.yaw_vel_cmd = 0.0\n", + " self.command_profile.x_vel_cmd = 0.0\n", + " self.command_profile.y_vel_cmd = 0.0\n", + "\n", + " def update(self, robot, remote):\n", + " if not hasattr(self, \"obs\"):\n", + " self.init()\n", + " commands = getRemote(remote)\n", + " self.command_profile.yaw_vel_cmd = -commands[2]\n", + " self.command_profile.x_vel_cmd = commands[1]\n", + " self.command_profile.y_vel_cmd = -commands[0]\n", + "\n", + " self.obs = self.agent.get_obs()\n", + " action = self.policy(self.obs, self.policy_info)\n", + " _, self.ret, self.done, self.info = self.agent.step(action)\n", + " for key, value in self.info.items():\n", + " if key in self.hist_data:\n", + " self.hist_data[key].append(value)\n", + " else:\n", + " self.hist_data[key] = [value]" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "from Go2Py import ASSETS_PATH \n", + "import os\n", + "checkpoint_path = os.path.join(ASSETS_PATH, 'checkpoints/neuro_diff_sim/neuro_diff_sim.pt')\n", + "\n", + "controller = NeuroDiffSimController(robot, remote, checkpoint_path)" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [], + "source": [ + "fsm = FSM(robot, remote, safety_hypervisor, control_dT=1./50., user_controller_callback=controller.update)" + ] + }, + { + "cell_type": "code", + "execution_count": 10, + "metadata": {}, + "outputs": [], + "source": [ + "fsm.close()" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [ + { + "ename": "ModuleNotFoundError", + "evalue": "No module named 'rclpy'", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mModuleNotFoundError\u001b[0m Traceback (most recent call last)", + "Cell \u001b[0;32mIn[1], line 1\u001b[0m\n\u001b[0;32m----> 1\u001b[0m \u001b[38;5;28;01mfrom\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mGo2Py\u001b[39;00m\u001b[38;5;21;01m.\u001b[39;00m\u001b[38;5;21;01mutils\u001b[39;00m\u001b[38;5;21;01m.\u001b[39;00m\u001b[38;5;21;01mros2\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;28;01mimport\u001b[39;00m PoindCloud2Bridge, ros2_init, ros2_close, ROS2ExecutorManager, ROS2CameraReader\n\u001b[1;32m 2\u001b[0m \u001b[38;5;28;01mfrom\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mGo2Py\u001b[39;00m\u001b[38;5;21;01m.\u001b[39;00m\u001b[38;5;21;01mutils\u001b[39;00m\u001b[38;5;21;01m.\u001b[39;00m\u001b[38;5;21;01mros2\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;28;01mimport\u001b[39;00m ROS2OdometryReader\n\u001b[1;32m 3\u001b[0m ros2_init()\n", + "File \u001b[0;32m/home/Go2py/Go2Py/utils/ros2.py:5\u001b[0m\n\u001b[1;32m 3\u001b[0m \u001b[38;5;28;01mimport\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mtime\u001b[39;00m\n\u001b[1;32m 4\u001b[0m \u001b[38;5;28;01mimport\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mnumpy\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;28;01mas\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mnp\u001b[39;00m\n\u001b[0;32m----> 5\u001b[0m \u001b[38;5;28;01mimport\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mrclpy\u001b[39;00m\n\u001b[1;32m 6\u001b[0m \u001b[38;5;28;01mimport\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mtf2_ros\u001b[39;00m\n\u001b[1;32m 7\u001b[0m \u001b[38;5;28;01mfrom\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;21;01mrclpy\u001b[39;00m\u001b[38;5;21;01m.\u001b[39;00m\u001b[38;5;21;01mnode\u001b[39;00m\u001b[38;5;250m \u001b[39m\u001b[38;5;28;01mimport\u001b[39;00m Node\n", + "\u001b[0;31mModuleNotFoundError\u001b[0m: No module named 'rclpy'" + ] + } + ], + "source": [ + "from Go2Py.utils.ros2 import PoindCloud2Bridge, ros2_init, ros2_close, ROS2ExecutorManager, ROS2CameraReader\n", + "from Go2Py.utils.ros2 import ROS2OdometryReader\n", + "ros2_init()\n", + "map_bridge = PoindCloud2Bridge('/Laser_map')\n", + "fast_lio_odom = ROS2OdometryReader('/Odometry', 'odometry_subscriber')\n", + "rgb_camera_bridge = ROS2CameraReader('/camera/color/image_raw', 'rgb_reader')\n", + "depth_camera_bridge = ROS2CameraReader('/camera/depth/image_rect_raw', 'depth_reader')\n", + "\n", + "ros2_exec_manager = ROS2ExecutorManager()\n", + "ros2_exec_manager.add_node(map_bridge)\n", + "ros2_exec_manager.add_node(fast_lio_odom)\n", + "ros2_exec_manager.add_node(rgb_camera_bridge)\n", + "ros2_exec_manager.add_node(depth_camera_bridge)\n", + "ros2_exec_manager.start()" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "body_T_lidar = np.array([\n", + " [ 0.9743701, 0.0, 0.2249511, 0.1870 ],\n", + " [ 0.0, 1.0, 0.0, 0.0 ],\n", + " [-0.2249511, 0.0, 0.9743701, 0.0803 ],\n", + " [ 0.0, 0.0, 0.0, 1.0 ]\n", + "])" + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "array([[ 0.97319254, 0.00978982, -0.22978327, -0.29256741],\n", + " [-0.01415969, 0.99974875, -0.01737615, -0.05825406],\n", + " [ 0.22955543, 0.02016401, 0.97308665, -0.03344418],\n", + " [ 0. , 0. , 0. , 1. ]])" + ] + }, + "execution_count": 4, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "lio_T_lidar = fast_lio_odom.get_pose()\n", + "lio_T_body = lio_T_lidar @ np.linalg.inv(body_T_lidar)\n", + "lio_T_body" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [], + "source": [ + "import matplotlib.pyplot as plt\n", + "import cv2\n", + "depth = depth_camera_bridge.get_image()\n", + "depth = cv2.resize(depth, (320, 240))\n" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "15124" + ] + }, + "execution_count": 6, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "depth.max()" + ] + }, + { + "cell_type": "code", + "execution_count": 7, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "" + ] + }, + "execution_count": 7, + "metadata": {}, + "output_type": "execute_result" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAAiQAAAGiCAYAAADX8t0oAAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjcuNSwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy/xnp5ZAAAACXBIWXMAAA9hAAAPYQGoP6dpAAEAAElEQVR4nOz9SaxtW3YdiI051z7n3vuKXxdR1yUZjAgyggxKIpVOmEoZRtowkDbknqC2qQ5bYsMS1JIbNiADkttuGVDDRmbHlgEzBaTEpMQqyBCjrn4wyl8X77177zl7rTndGGOufV7QivhpJPLrI+/+8eK9e++55+y9ijnHHHPMuSwzEzfXzXVz3Vw31811c91cb+Hlb/UN3Fw31811c91cN9fNdXPdAJKb6+a6uW6um+vmurne8usGkNxcN9fNdXPdXDfXzfWWXzeA5Oa6uW6um+vmurlurrf8ugEkN9fNdXPdXDfXzXVzveXXDSC5uW6um+vmurlurpvrLb9uAMnNdXPdXDfXzXVz3Vxv+XUDSG6um+vmurlurpvr5nrLrxtAcnPdXDfXzXVz3Vw311t+3QCSm+vmurlurpvr5rq53vLrLQUk//yf/3N84AMfwPn5Ob7whS/gD//wD9/K27m5bq6b6+a6uW6um+stut4yQPIv/sW/wO/8zu/gH/2jf4Q//dM/xWc+8xn87b/9t/HCCy+8Vbd0c91cN9fNdXPdXDfXW3TZW3W43he+8AX86q/+Kv7ZP/tnAICIwHvf+178/b//9/EP/sE/eCtu6ea6uW6um+vmurlurrfoWt6KDz0ej/iTP/kT/O7v/u78nrvjt37rt/AHf/AHf+X1h8MBh8Nhfh0ReOWVV/Dkk0/CzP4Hueeb6+a6uW6um+vmurn+u1+ZiXv37uFd73oX3P/DiZm3BJC89NJLGGPg2Weffej7zz77LL72ta/9ldf/k3/yT/CP//E//h/q9m6um+vmurlurpvr5vrv+fr+97+P97znPf/Bn78lgOS/6/W7v/u7+J3f+Z359euvv473ve99+N//7/5XODtbAHPESCQoislMRCaaA5mBGB0A/22WE6FFOEU0CUQGzI0/MwfgyBHISGQERgz0fgSQ8Naw+IJlaYhcARjcDWYGM8cYgTTAzNDaAjOAibFERMLMEMH7szS0Br1mIEKv8YaMQETAYcg0wACzRPMGc0PkQASQkTj2FYvxPhCJZdkhAWBpcDMEEsiEuyFGwM35OQCsOTATd3WziczEGB2GAXeHtwa4I8GXGBrvCUCOgLcGd0dk8DPaDglD6rPNyWZl1/uZ87lRH8//N0tE1GuADM5LRGoMDCMCbqaxDJg7zB18Is2n8ff66Lpfg6U9xKrVvy0SqWc2S0QGxuhaK/ydzNSDu9aSIxPICCChOeH7AIAbgAxEdpjxG94aog/9zh7D9njmw7+CdutR/PjFF7Dsz/gMBvRw3L+8wp/86Rdxee8+nnj0Ubz/fe/F2a1z3Ln7CC7OL9DcNMKBe/fuI8bAyy+9jL987jm8/33vR2sNv/ipT+GRxx5Bz9AQc8QN/N1IPndGzLUZIxFaDiMGxziBERyXiNAy4XqGaSEAGJFo7oAZHMZvO5BmABLNGvdMMxgcZo7WFDW5w83QzBGZGBG4vrqGI/HCT36M53/8Ezz19NOw5nhwdYndsuCJp57E6B0ZQB/rXMruQPMGb440aH1yPzR3cEqc9kJrBTBkDlhyJTmM72eGEVt22zSKIwLNG9emvtePR9TgmfM5bI5PcO4RGn8AkXpN/Y7ePQPBH2tNcw9peyIT8MZ1WWs7a47N0Br3V0TophvM29zr7iZbB+wWx+HyEv/n/+P/BS+99hKGD5itaK1hDM5/2+/hvmB9YPgv/ov/Nf7GX/8s1pXMNW2kPtptjlBmYre7wLe+/h38/h/8Pv7O//Z/g7YDRnRkBvdU8GEyEhFAjMSy7PEXf/E1/D//X/9v2diAt9Ta7IgYSHO0tuCzv/p5/PW/9nlkDOyXM7z0wmv4f/zf/yukDSBX3Ll7C4/cuYNP/uKn8ed/8Rd47fIK/XDAen2N49UVnnnmaTz6+GN47dVX8bd+67fw5//uj3F7d4YvfekvkBe3sOyAYz/imaefxJNPP4UPfPD9+O73foCPfPgj+MhHPgKPlAEPpNEGWCvblbCSamatpbmMpi8yxNwvQMq2xLSNZk5/ovmj/YF8jiHN4HDZY60JM9m0k33IWeE9GX2Imet1UY6KtlWvRQaaJabhBxBpOB4D/7f/63+JH3z/L4HdNfdCc/zn/8v/BT792U9jxOC82Q6vvvwa/un/6f+Au3fv4mddbwkgeeqpp9Baw/PPP//Q959//nm84x3v+CuvPzs7w9nZ2V/5/p3zHc7P9+iBuSmRMvbGgWttQcQOEUEnBU2uG8YKIBKeADyx2y/oMWQAHNgtwAi4OwYS15eOGIFl19Dc0ZrBm8upcREBjjEGMGIzCs3nAjF3jCTQAQLL0mCQMcoFlkFAA8CtcQ2U8deSygy0xWnM4Vh7x26h8WmNxnFZNLULDXyWwYwEGo3tiEGnbQ53R6YJyDkSA5mBPgAzAo2lNRoQXxCBzcgmx9+d74NMrV0aGPc2HbqZwfY7WIJOS6+D0WEJs6CvBzkpOU8DzBbOixt6lAHfNvUYg/dqBiNugLmhr4Yxgs4IbQNGD8mnCP7GGLxfd8QYMH/4dQYurUwaeROwS04YQuPawGdyb1i1z5el8b4awWYfO4Sf4e7FBdqtC7y6O8Pu4lyg1THgOByOaG5oAnv7/R5n+wucnZ3j7OIMS4HMTKwrwfEb995Aaw1n52fITFzcusDZ2Rl22OZpetTkOowxNCZ0eKMPDAuC/eTP++iwEWhYeI95Ylu5sU7G1ZAwtALJKdDIQYNbm8/EOWwaT5PhdURBO28wBPbnZ2j7HZb9DvvzPa4O1zi/uMD+7Ax9WYBMLH3RHDqWxYACqub6PMNSawQF8k3AvCHk0DO39ZUCYntz4fWcQQxXgSMjCXwi0FrDelz5nM2xoICv6T21pgWSEQIboAOo8UoEsgIHOReDYSBwMvJzTC1OnVnZm3wo2DBvfBcFT5mB9MTF/hz/7t/+IV5+4x6wNCCPsLbMgGJ3toO3huNhxbvf80H8+q9/AWcXiWXXMEYgEti7b+tL6yAz0XyHizsXODs/w/mtc8A7liwwDzQYAc0YiFF2e4+1dwUbNteFWZfNMqQ74I6zW7dxdnELOToWb3jqiSewd8dwYGTg2FesMZBuGEiMbojQnrIFx2NHRmC/W7Bzx+N3H8XzL74MO79ANMB2O0Q/Yh0Bb9wPt+/cgcFw6+ycY+1Ok+98Fm9GvwLMeePPuGkia64FjBvXYGQgo0C85khjwMBXdl+mt/a+LOGcVyT9j2ls3Qg+x4gJWjCBI4E3MhHZ59xpZRP8OCPHCtL3bYfvPfdNvPDyi7B9Q8dAz8Rjjz+Fj3/ql7C/uEDGADKx8z3+zZ//m7m/f9b1llTZ7Pd7fO5zn8Pv/d7vze9FBH7v934Pf+2v/bU3/T5ujgaHJ+AJLDDsvOFst8O+LVjcIQ+xRRFtkeExAEEAg85oJBLmC9x3ZFwikEl2JFPLqjHi4qJKZNCAZwIxtEgUMZoWhMMZmScntRnZAUeDJe/R4VjctfBCcVkicwBGNsUtYIifiu4AlGNwRoL1Z3p3nLACzu+n01iPjPknLQAHeg6MTIxMtNbQlkWAAoyw4EA2ZDoQrq9zoud6djpkGuWBgZ4rwgafy0HjYImoW7PNdralwEic/JEpD+ghXX/4/M0dDMwD7gFgIGOgNQJDyMkYNqdiiloBPtuy7AFFI4yoF7gvMFvg3jY2Rw4m5mPbZJzcxNRU5GIL3BpimNaLw9DIdBnBbg1dimEZmQgEdmcLzs72DMDMsI5AXwehqDnQZGQLBIwBjIFmwFiPfFaj0zE3sUiYA52gcQzOCiLJTiWIonJ07QPdYzlvA9KSfwQc8uT+DdyTbtoPEJMEGj8zrm0CuwQsNHcJs5j+loxNgSUFE41OdbffYdkJeEfO13sxA3KIIcNIMGmoQDBxEmGCG9gz4QYsTgM9STFuHDKSCTKOtc6RBL8QCDAAzSZTZvWfbcAE6ch0RBLEbqCX9wfIYecgg+rJ8fFEQ/3RGKeR4cvx0D7MDLGQBYaccdoI1IPU5772yiv491/8IpBXQB71TAqeMmG+Q4QDo+Hzv/JLuHN7wcpoBZF0/JE5A7SHwX7OeZ5gQvdZzGGITcFcTwOXD+4hoqPoIM8B7qwKBrhm92dnXHsGRAzcvnWBO7dvwbHAfQ/4HpfHI66PK8x2uL48csl5ollg9APcDLfPz3H14AHOLs7w2r0HgDeM7JxrXzBiYIyOzIF9W3B9eUXrbuQfap2bOcGhFZu1+YEcZIIcBGKmgILBrF4l29O8wVCAQ+MatWdT1rFWmVZPMS6Z8EhYxMwCADltfDp9Lu0h3+mnA7xMsqQDhtCopztsaRiR+PqXv4XD9QNkHpAYQBg++pFP4InHHkOMAODwtuDyjUt8++vfxZu53rKUze/8zu/g7/7dv4vPf/7z+LVf+zX803/6T/HgwQP8vb/39970exBNO3YNQn45UXmCG6kGptCngymLMQKWg4vhhM5yGNIaYHTSADc26WBS+Ina5IrsMmQHYsYuTXmYclaFdBFExUvRsjKWmQE0Z+RoSutkIEdo4xWSrYfHjHLr7i2BHEClHtydzxMxqUJLm+kMM8PiCxKi5PUBdBx6xgRaKjJETlgwndp0UHR0YwyYk1pkeoQou6jvzEAYnaejaSNW1BAEJZX2sO2pszZUbeDcgnJTpD8jywikGDJGLqmHJ2syQ7MTtJ56wwKuIdaGn6HxrZVimM/CTU5w0GS8HUCamKJR9Gh9kmusOR6tNSBopPbLInqdoJSPTDDa3NBcztkUPYsipjOIucY5FkBER7NlDlStwaylc2LJzIA+uM5pqFzg5DSVVffF8fOKmgRkmhi9yTxMUM25c7EVHP9tPZg1mLU534zWBkF7c0RfsdvtaFyVdjFvGEox5eC6CQUQdKab47OasCCoCyuQUWmLEyRc86cxIQjaELOly5kOOQgZfBidvN5zWXyCnjwBLynQGhFAysnUGn9oLRrMl822IATkGK7UA6Si8sl+ZM49mQmMUcylIRFMRWUAaMgkk7RrDV/++rfxkx++hGaJkUP7cOX92oLWFhyvDnjisafwC5/6FI59JaMKglxEImuYFSVV6iCRiAh0zVdtBcEmjGQkF560y27I0XE4XjOoxIAlWedUOjVlVxYDHjvbY2eGLizWlgWPPv4YXr33I/ieDM4ODYdjx6OPPIbnv/882mLINuDowOjI0WGWeO3e68B+h+vekd60H2jf+ugwJMbxiL0Bx6tLNACj1hJSqWQ59NgCn3Sfa56Li+BtaO83jZUXOK51G+Cai0RblgncCmSWvUHt58mmYb5ffd7c+Kj9CGQM/r5tAHqMMf1oredi2CHg9frr9/D97/0YrTkiGWQu+x1+5fO/gpBfBYBmC374nR/i/kuv4c1cbxkg+Tt/5+/gxRdfxD/8h/8QP/nJT/DZz34W//Jf/su/InT9WVdAmyAC1sB8mGjDMgZojGysaKsEnXzGpG1n1l+AAU4U7gYwNiMy7T1hnjjbN9AR0UW7A9lPopMyEOZiLZTDRYolyUnnDYXY5kwrEBUzNQQjc1KRg82FHjBvSq8QYNES0OPS6GA+C6SdgUCDOTcB5sLmayIGLAiKCJZyAg0G4za5G4BjbbZ5NXdX9MVobW4aIfXFDdZM6YHNSSeS1LRYqIorAX4mo3wABQAyYaKCmWoKAUA9V6sNqTE3GUhzPTuN+MC2eYtKn3+XM7YTIFIIRY9cYIq53g2uRTn9JJCA5dQYoPkGYq1SQ4HIQQer54AZo8EM9OMR7mQO+AeIMahvAiPknODKGJGZY79nymYM5pFrnW+wIgRwClxBrEXSKM1VS0M7n3UyB8UIUdOTGk/qfcbJmq3o2AVgNJagNor4UE7emZKr/6J3nLfdBG3LsqCo7kzDOAH8nI6xrf9kms50r4gELIDW9KwMWNpCYBwRaAKShg3oFlDtIzbwL3YyAlgEBLJ0SwnsxXyN5BqCHGlLvX9CLFFwXznm5/D9N4fDBce1FhEbuNFe5vo6YUNckCoVt2RpSGgisExEDU9gHAe+/uUv4/L+a0AjIHQHVtkVXwyIDiDwmV/6BTz77NMIxExFEw1iarp4n4kYA96agAngywJfFvT1uDFPeubIwXltZTOAw9URlguQXWBMqWQFAQBwvt/j8Ytz+OA4DgUa73jnO/Htb3+fwGMM9KXj6sF9vOOZp/CdL/17tGiwneMYgdFX9OMRy3nD/Qf38NhjT8vOcb2WBic6Qf/V5QM8dfcpvPb6G4ixIsWQGACMATQGQlN2gWLHtaoVjIbiogIgBdhzrEAKaFrCnWuHrD5DOdrbhsz+EJie+7FslWtda817yRvcxaol3Nvcr5PvdK1/BaJDgNjN0WzBj7/3Q7z+kxeRS0dgIIfhgx9+N97zrqdx7KsMtsHWgS999et4/arjzVxvqaj1t3/7t/Hbv/3b/3//vjWi/p4Du7Yge2LtXeJUUujeXA5C0VQOCcG0wUV9mRlpcqqqpLuIbWCtYV0HzvbUj5gnQsKswYAPlW9djLqQiAFvwigFNIoCtTYdF9+vTQOX+syhCJiv9ymS5DrZaGl3hxXTEkP2iP+G0kCBnBtWNpxXY+45jdG6Y4EJBC07RqExJKxtNkGMC7MUoKu39GVRpLgBCzItA46GBgdaQ5emZ25lMUeTqZm5UIGxZKqr6GBGSEEANF8PKOt5AhYYQYQRbEQwsisKvUKWxMnn6f3c5wvkiPl9OkxGEk3unTaL5seLDvVKBfDXRibQV6Z0guCsHPtut2DtR+zOLmbEXgLbs/2CB/cT0TsWiT4JrJUeMcBOBJfrTHEElrajZgJOzZDmKwqAgI4+M8U4JEIqhZBOh04xprPU8ExHz2HJuaRqPZQxrvngUOd0qMphzDHw6ez594hKHQaW5gR8GXCtwSFtVRidDoW5NMRDTt+xRXhpZFEtqM8yo3jWgsEFxYGQsxf9oOXlbWNRxlzfKU1o8G/lHiuBZZZwEyCBac/W2Kf2BlB6N659jlNEjfc25pQftIfErWUDOLSDlqGAeG3zmSIBqAkSmDbapR9+7wf4+je+DfMF3Y96LoICb4ZlMcR6xOO37+BXPvlLaK3hGF02hvu1Gd2kyYg5MNmwWhfLshA4WqsnOgGjM3SnBm81rNdHPosZmRFLjHSEgC28YdcW3NktYicJoMZY8cw7np3sLEDg2a+v8dg7L3BuCiB3C3a7M4HVAGzB9fGIu489gua0laZ1YBY4riuOa8eD+5d479N7vPDiFSJW2LKTRLlQJZd56ZGaRKORlYrkzDAVWdoY7tc4sT+ptVSaqloKU/+k9VLfE62F0fvcX1PPJeFtBSWRWpslVQCYznSTHQBZXm3kpnSfJ1nCP/rjL+IqgYB8azvHL3/uV9B2hliHILTjxz96Gd/93rdh+wEc8XOvt0WVzX/oSgORW2ukrSsdnQoFEsh+Gtlti54Rzpg0dpwsmsjEIlHdzHkG88qOpEFEigZl1Q2QGOKCM30CoNBmo5ErJxAYuQENcyddLgdfYk8CiDG1KuLWYBVxoiERMnD8u/kCM6FZL5V9MnpKsidN6SBSuy5SJxkdAvM+6m9qDzbWJ5FlQwHQuI9ghA+3SSQw7URD6L6w2kfOz2Bocud68aQiM5MgCTE1D+6b4+JnymEIxvNnJgC3RZg195M+zkHH4AZhqvm7QG4aC9scK+Z9xRwfzOeDWLlyXnp+pTN8aUp9CAiGAJYnYqwY2RSRNDlDOtMyGjDpnkCBNgBEH2SZKoTZFvWky0fv/KwGIAIMPMW8yVlzfTeJz/SovHmyjTWCQV1FaQUmLpG/nKxIGfAK90FGDTCChiyIQrBYqZFNgWwnz1BY0eYeMVUUGYBdW2jos3aE3r/Sa5q/EODyAtOCZJZy/mMgjemOSieQGWOETK2t9vUJg5E/xVTM7yPFkDoQnfdoWjMCO94c6RslHoB0I1aUwQn421KuXmNDb6G1WCmxGvM5chsg0YLWztmclxmsOf7ii3+B1+/dQ7a6/w00FfM4RuLDH/sYPvix96LnCrNQUCecY46qBDFgpoUrCdf7EPPqiGCkPSag5ZqrtNvSGo6948GDa2RWuknpvrHOuWUQI61FbWRwn16c72FN+6wHbHQc1wP252fUg2TAowGjdBt7wHa4vD5i387wqO9wlR2v63ncHMiBHIH79y+B1nDoHWsMeAhkZUzAxdsRQCiwWwENKtgoc1GBT07RK4zOnqydTbYaBYIrKPNtcU0ZgcA6DNQ7aowJSn3u11Tqa4ulEjGMtkjfKmbX9P5t2eHlH72OH/7wx8glEKC04el3PIl3v/89uO4HFj8EsLSGr3/9q3jt9Vdoh97E9bYGJJZdOgVVRABoBrIEjQZs7Ss3SUUNqhogFdYweiCDm4SXY7cTFTkGiqI2A+7cvlC6IZSfrug/BDy02VGOohyinN7M3xe65feGmcr7Kl9MkOQLN6pZqfnJ1ECpIDp4btgRSfGmG2LQPC3JklimtCijam2Z4xJDxkz04hQf6l7G4Di2okOK+k2g6Ec+W6D0JimNSpVcEzQ0vSefoRXFDUV1Mupw4f3aIVlCL82NnKJZQTLl7C1p4KNAGmQUc6Y1Tql2ThHnlIJVAzNuRP/8MVMQjk38xepo0fBZACf1803UVtEbMqdgceI3RchVVsfobZBtWXbokZirxAy9NCUG9HFE70fszi+Q/jA9Ph2iwDR/RIMGJ1CrtEpMmFDRKZCjRI7SoNAzc571nKVngpxgvUsxC5U6sLQ5/gVMy9k2AT7bRkRVXptjN8MU582o31linsYozp3rct92oN6JqdGZ6z4BAADIgngqjcnFxFQBX7vdj4n9kSEu51drBgwUssYOjCTLgG/ALqd9sGwTZDQvCaG0ECrzRwUBVh9a88l9kcFkBYy2fVbRFDCZ917Rds7xLMBAkAS0ZhM8PLj3AF/80y+jrwO5rDAfWFrDunYCFjf0Hmhtwed/9deAncSddXMCFc23NFgBQQOQg2tpHDsagJaADTJSjtJANPTe517PTFxeHXH/8gpoi9Je9RycqxJq7nd77PbnAkC0cSOBi9u3cdF2iN7FmQL3rq4xloY4v8DhcIlzNOTi6OuK+9cPcOfWo+iHI6IbzpZzXI2rypQJDDfAGvoIrAa8cbjCZT/i9n5fLwKSstvS6HGAqLOJipi1J4rVNGMqbzJfE7RUJSLHpakq6kRtJPbVAInQN9H0FkzxM6RdgjiSsl0KTBlQcN0aTPvC5ttEcl3sdgu+8pVv4N79S9he9t0TH/zQe/HEU09IY0lfsh5XfOXPvkRWejkJnH7G9ZZU2fz3dZktMLTpDCwGFjM0g9IpFNuEnE2MEuwwdz4FYKIbmzk8RTl1Ro2WxZp0oAX/gEtko87IOjQLGAaQrNoZfUX2MRfngDMFkhWBGYpGM1dliZGiHgb0Vf0zrClKbNyKzgWzxkDPMfN90QeBTgDogIXBw7FonABMJ+VmWJaGpRnMAuaBsAAsqD5vQFvo7A0Bl8o/BSpICVJr4QBaGvugGKPxxR3NE80AFrAGvDZTbI6PDFBtOQdHMGelUICMQde4kb5lxB1hSDQMOIXIlSc1m2WkWwRigDWYLfA5HkyjIZ33aXIVMRjtJNCM95wCaNTD0CimqngQW+qIPRu2PhYICpMRSQNUAVAKgI4By5UpN5VhNzByc+yAKFd5olIRuC3WJcG0BRQx7XY7pQGZIpipI2wgTUND8CG0WILLWt98y5ipMU+tKfJvom9BpzjAaDN9voeXc5QLDmabBRSk7RJaj0q91e/q93dtweHwAKMftW65HnOss4LKKo2jiHSOTVJI6HKaW8WJ1p/AARSZj2C0F9qXrtScJefOU3ZCwUD9rPac15vBJGg0OqgTxoPgpmaN/zZVz2y0o147SoRKRrYZKO600jphW5MV8AgsRzJgCoidMnB/t8SaHWOsaO740p99Ec+/+pK0I0HOkoQrDAsMe8TR8KEPfhQf+/gnsGZIxaEUt8BHBTDVXiEy0cdAOtMdh+sHOHPDgsDeaEZ9CCBy8fBDRwJhOB47S6cLVJ+sk7LnmQ37/QXaxbneIREW6P2I8/2CZ8/vogXAPkYNDx5c4vLygOXsNgINAwnfLRgIXF5eUZQ9BJDvPIIrX2hXxFKNETisR/huhwfXRzy4PuDQh6oQlU4Wazo6n8VBf2RBu1LpVlPw5CcBEjSWD1coMcC24BpvqKpC7jUGp412M6n7WccQ49dkRGNq+1xgrloX1EdPgKy9gszZx4bV1awmuv/GPfzBH/0pnYMlBoCLW3fw4Y99ghWKIKuy8z2e+9Zf4pXnX6I9sIef6T90va0ZkhyBWOksgTIAXASRFU0vDAxEYWUZJaNunWpnyHhhVmVwAnJWpUwxWUV4ipKiKjjg0q0QNZozEkkJS3NuGcBFwQN0SqFGYRVByYrLMW/GaSuNY8SymTVGf6aceppjgI7CfdHqk2jVuLlO6VWHqhIqEk5GgRN4hCJPc0BCtZHU3zgMoyty3GmDgZsIgOh+nzGTIZGpUj5oncaYDEkBxEo9OACTECtMPV0AlGLdlWphepZsVYl/3apAUBEl6ExSoWyGtCXlJJGYTc4Ms9qI9LI0DnqfkCMfRb2KPWILAFLcFJorXkxsn2tN+gcKMfdtYSTUAx6YrFbXKlnUnAppaNamaNP0gRXxVFl5leuZO8ZI9GOHjTJAm/5gDBpJSxqcnM5tWwdbpZqixGRvmQJ5bg4Mft0qhYkSXMrf2AaqxhhIlae7lR5Geqd2Uo3kqkpDYo2BY19xFNsJMOCoPjoFeXiTBGYpVikt5xoYGDOAKRbCJhuh9W0A2hZgFrNzQn3Mv2eFTIrFggm8YgIGLsmcjEbU2po6Eq2f0qFKVLxtjnosm3PCfjssf0ZTZZbuB1qTKb3CVna93b/J2Vzdu48v/dEXsVu6gAQnjTZNWq/e4d7wm7/5G9jtd7g6rExJiAmpYLzErSYb5WKhAOqSDlcP0MBgpdJBKeST+CndVQDr2tHHmEwLHXBVsEGaeMf+4gK+3yPRpXHAZGxu3b6L8eA1pDOlbBl46aUX8fiTj+G1N15Cpqv9gaHnQFhDeuIwVuxvX2BFwrAAY0VbDIeeOB4H9meOq+MB5xe3cDweJ8u1pYlpey07qpcUrJgpBRPGvVNpzm56UWCKhLlPY4I/pFKPP1URuKXtar1SsVCz3lqlZYtR1v6MVBo45ZfYyiEE6FmGLxZLwcG3vvU13Hv1ebitYMO6xNNPP4UPvP/9nNFIygbGgj/6b7+IQ7J/jdmbEJDg7c6QKBojRUy0uKYhfAGWM1jbMypuDW3ZwRq7uqYZ0hbmjpcdRVIGUroOIUPl2cDJMG/wtiASpNWLGSuEOqMgRuJ0FD43KUCNxqJOkSnHQ+t18kwFFLw6R+Y0XnVPk36dTAXEdGyoFxAQqoBHVGBVJgE2DY/ZAqSrl4Wc00wHKH/t1HtU2Z0mAKF0CRYJpsqJTa1BGfRqIFYUQYEPnw3V3Gz2lLHTQLI2q/mMBqn4rs6bjY6mRBjarPotVBddKFgAiookxcs/HM9p7IrVGoP7mGQbSkRmYmGaSir9xJkWQGAhk9Go5SZKK1Fu9eHofcX5biEwjCFDTyNkrdEoq3/GGBVFJiuwBvgntkoLwObzB3LOg4O9bxBaFPp+ZDEt1W+A7F2GsXeKqOrEiU6gbG/ZUFe0VuJVzdlkEiR5IdWuSE2MXFSVklgzgMJRrlUS9AOQkfQpfp0NA5W2iCwN00k6TSkLiJGsr8dkUXLONXcsx7ai/BEnLADyoaELrfONdRkb+MAGVDftkVJdkZNB2fpP6L9J9dda3oxDYkuHsNSb/WJyloHXLIpRkRnIMZCDPTwglrJ5w/e+9wP84AfP6x6p7cloGOGwtsOuNYzjive8+3344Ec+iOvjlVIsOVNamTi5z0rhnqxzMBg7XF9iWYDmZISqzH72LJFtGhlou4ZjP6pJparRTL2cwshUGdsqtN0C2yltl1xv1fju9tNPYMBYPs2BwMsvPY9nnn2SlSydrB/S0MV+9Bh47eoebLdgAFjgWCJxbgtM4D0GqyPPz89UMZTb+tW8t2ZoS9P+CDLBCHaolXELBNIN4cVibVqozEo327RLgVTaVSkVgQ4ktLcrvU0bVf5lY1NzriNAwZkqSwn42gy4liowKKYwGdh89cvfxKF3VUUCyB0+8OGP4+4jtxHqWeTmeO4738cP/vLHWHY0nrUHft71NmdIEuHAyKESKUNYE/DgILIahpUnDsNuIWItbcncDLEJBR+KuoLCv0YvBbMFfXQEFm7OpvKuhChySGzEf48kUzB7oCBFo27dMZsvKgUFIjudrvuJcVIlAeQokx1L2UOBjExK9NekbSixE40WqM8w3nOxRTOVgRKCtomNyIgs0zlyQ1BZD8/y+1xoLbWZAMvNyGcZ5WJZEmAeVlExAGvbM5bDNpMWU7/vAmjs+aDeKjDAtyiBgj+pzrVL27JD76v0zYmqdpnOkjXjU5RcabTZ4CgNtixC/Y6iyiOANfqMEE+BhoGRf8gRV+RK3cyCUCE5n5NpspErIrsElHLqCVhzjMMBiUTvHTH4fNJrSw0vLZGxC6ODKUdWewciOC899e+guHtGwUopMJvU5O5ygqbSNpnWHgrQam0ZmljDmAI4Vxv4nFU6m6h5zq9J2pqQ3ss3okEOveZWfpQ0/SB7tLhTy6FoM7KkRxUYFMvTanoAqEy4GBGVXyONbKiVvLAiScyGc2aOLtaPzb8cHobop2yS6VkVZZ4EEVXFVICsFs4E7RoXMn9RC4fAZ+5XfRvCfqXRgj5T81FOBfOz6t9z4eFwfcCf/fGfo1+twI7O1NWpNpHY7XZAUqPxa7/6BZydnUsDoeZwIyYDyWBFzBBMQRrZYYcpHbji4mKPdRzZJFF70lDVXzVWABA4Hg44xkBvTWnfTbiONJo9D7QdGxcOO84xCpBBuv3kIxiU2yHGQHRDPx7w5J07OG87eNBONhhMzHZk4P7lGzi/2DPVYgR+Uu5gPaw4OyMDuljD4f4DmMrFKx3HnliN4zkGQkUBG5PFyeAzSxAv/5IOUft85rlJ4jTtyrXj5izvzSTirz0qTeNkq0/WwMblFSsqmzJYdVN9VWBMaMcItMbV9PLzL+L73/4+0h1hiQhDOzvDJz/9mYcA9lgHvvS1r+H19YBlPxBxRO8r3sz1tmZIKqJvvmCWXCEFLjpSPeZcRs4dzDXHwM6lWMgBixVLM7SFy5n53K1HQ4CLkmdUdPS1Y6wBDGCsQ2I/mYAy1mMgR2LBAhsJDy7pBYCNwRxilceBWoK+HqfBRWytzGdHPStneRqGEBGTAXA24AFgnlSZm/QfEzkLQ3uTIyYQcWM30hGGtSd6mrK6NnOUPaDeHX7iKHQvOZA5VAZZ0YIcpyLV6nY5BkGZNW7CqqqgM08JfvOhUkLmYtWbQ/OGMWSUicBtct9kPXowgQCoe2czUPehSKbhhBbl71d7/FD7/k1keTLmRjCzWGMKBXKmmgv3reFVOp+P5dbSE2ns0NpkHHok1uCKrTJyDiAj2jBFUaCK31tDWyoVxnscpSnROUARZOUMJo1Ef0ibo9iF712RdwT6GFhHRy8RtuapIjMKoF0pItHuWb1uuH6nTsXUJRcDEWwsteietqo3+ykNCbVPCJZH75eFHVQF+l2pqARm12LUepzOXtUOxUjUajQyGbM3jRguYKso8IzN2Yu1oc6LQU/viSF9RjoBNtub53wvA+bYP1QZBkwQ8pCjmDIkCddPw4Xa8wZksXf1vHplpSs2ICZ2M7dybXacZk+KH/3ox/jGt76Nbg0RK1D6KQytd8d6DDzz5DP45Ec+PIMuCOjOmcogc6CHnt1rJlWi9GAEzi8u+KyTEcNsQ5C52SckcHzjPvK4MkWI6j5ihdfhGIj1iEduX3AlFzMmj2/uuLh1cQJ0eSzFOBywa4bz3RnQd9h5w+KOcVxx/eAB9s0xDke846kngFgRSU1bNLLpx3XlOlipt3n5hRdw1hwujcf9e/dw7/4b4DljfQZNo//Vku76N+eZ3GStvfrb+oCNnNm7Wb4Nn2PGv6UXgc0O0NP2mmxNY5PETEyNTwHnsrWQbc3R5z1kJ9D93nd/hFdevkS2gYEDEsB73vdevOc978Yq5sbMcO/V1/G973wDjiO6rwhPdd7++dfbGpAUnTliiD7dJpjgI9AysIB/u5yXG2lHui21YNaktKo4gdPZGNFjDG7u2SdDCyqLCjN2gFTSVsa+dB+Y9DHZumSFkCXcKSg1V4M15evcgdI0xElu3yBgpT4oJc6tFtQlNDMzRpF6vgVsvYxeyoSi2bXIfQNUNGhliAOH4zUOx4MQ/kbLsoyY7ZAxKGw1AZQCUDP369tSmwjdNoKRz7Y5surBMUs0p7p8ozMNWcONCv9SUU6NgfnD/RHoWBQ15daThe8c01mZlF+awXlPfQz0MTDTUPJ/dT5O0e1V5jf73OiAt8iN/i8DQjbHZ243itofjGeaL/o94DDWEyFhUfgU0u7bImGxmlIBGxDNMlyYjOHWvr2qySq9kJOlMAFEJIG9i26vFtTFhtSsupq90UEXUDYeuTCBWrEYYIVKAqX7gaayYAUycThcq2dDpVBM3XENS/O5L8goyjAnMLGynH8ERch1aFlFqfxPzJRREFrpJ/PG9KXYynL+CaXdzBgN1xEDsBPRepmoExpezrgqreaYzH1HbMBsFpmAJlYQqVSl9u12hkmyj4pSzCNG8VxKTysVqfl0JL7z1W/i9VdfhNkBLE8GQX4Cu2XH10bDRz/+C3j8HU9N1vcU8LCFgKMa+NUuMgQF2qqQ6iNxdRx49InHsMaq0da9eOm6WJ5LkXcirq7QYqBhYDGXpi30XwLmWBrw5OOPSjiutaF5jwTu3L2N2+cX8CR4bjD06yuEAcv+DH0YkJw7a87+HZl4cP8eHr24hZ0A4gDQznZoC7D2A8wCfb3G2W7B1YPLuYerT87Z2RnSUvaf6+2UdS1GbDOIG/s927ZH6hDO3ILUBDUpFVXAtqoyWnQgtwqZKsUu0EL3p8AV0j+p+dqaAx1aN871MoLFGRkJrI5vfPM5HEI9rzrXzOd/5bNY7CRVZQ0/eO77ePXll+DO9xvD8c53fBhv5npbA5I8zTMbI+628AAtt1LE69++aSwATCdSZUqoDeYUZkp4AabYyiVpwXgi0eGuxmeWapLK3v08FZf3NJDIpYG13QxjrNFBmdTLFuwbwQYzNkW4pdz3BLLHBkgAGQNSimaMUuuwrzRH6VhQm9F4sjFBCqN6/jlJocjpG8QyJTkSsjRkVc7OzsD+Ktsi5GDWwXIVPW0bb2Sgx0CPgQGq0ls1TZr0ekyhplcfB5X9JnhwVebm5ExgoZ/kZL1VZYg2cXLMWCGSrMDSO0Is1ImYYhpaAAJUoqOrPwswDQY1CGNGO+5tq+0X+GULB0WoWZGbzaGZrBo5cM5jdXGMQVq6D5zt2Bp73xoWUeEFjE5V+cbwdb5HRaA9ePDVgCofptPgSc7FSEGMXTNjz53MebZLtR4PvU8aYEtFrLYZ0xPHnYrk2JfBRPWesDMC39t6qX/mjOx5gjJbtXUQBA3EdPh07huLWPNIlPkw6zLD69xcyKqD4aaGKMt5z1UBhbLQKZ6cOwGEmVY16UFOQNdQ5U5Fq9ssJXr0LUINOvB5YxXYYANUlkxW8ioQuWlWZn8SjUvPQEei59aQK40psMt7D/BHf/znGNERea1fq1Su4+z8HNkH7j5yC5//tc8BAgyG2oOyHxVc1W4PRfXAHJPMget+xIN1xcXdu5pzjjbXVwWQBhk0AMD9wzWr/Uyv0R6aTFAG9s3w9JOPYyTTpxSDE1COAC5u3cJ+fw7DTulL4HBc8eDyEst+RztOYoipzjHQ1xVvvPEaGgL75uxcjYbDgWXJo3eMdcWDB69j2S246ivCmaL11nDnkTs4u9jDWp3izk6rRqPx0Donbs4TBlUB6UL/UanZWQ02y3CzMDcZs6aeWYuARLEiCoxTvinTMdIJxAReWttpnQXW3rH2/lCXZgOB3Mt/+Tx+8I1v4QwHeHQ0BN7x1BP42AfejXF4AAT7HsVIfPWLX8E4HuEIoAN7Bz79Cx/Bm7ne1oCkYyA8MGwgZ66Pm9jNYcseg+UuVKQrnH5I3GOgAYzU96UhcWNnQAyEhSIQOYtMVT1I8JpscuUQo5FVpUMGoDERPwWVkzdLOpwtJVOR9sNizxJOsuTtlDHRAU0j4UOUdvL+6YgSEK/Qh07JbK6oVxs8ytAQyY8M6S9TXVqBOgsDsHnOQYGSEj5x3DWy8rlT6S9n3Rafh1MRTlAbU0CvojDCJDVyQ1MFzRY5zIgBcgwywvzcE+ceOhaq2MwCA+BctnbSQXFem6hQEkcJLDGFZVa9JCaosC2qtxJ82hzbJpBU95YZU2NEdXMX4+ws3QYIjLk0sR6UyhsBdDnEKWyudQMkBtjUSlSGKI2QI59qfNIwHMOubrlEk8A6YH3wYK7Nw3Pcp2BTjjuylvE2DmIDzDeRb3ljF8Au9s22H6FEx9veDFgj+3Na5hoCTa71NveYlYXeAC4rrlhIbvOTmIYUBkQOYKyhcvyNdSjnQJAsKCG2rQHUH0SlSfjaWa4uG8FeKqxIUxTClKrVSbPc01vPk9IdiQ3VeuUZWTxfpql0aZZb17z0oM4o6PSYdU5VyJW+x7Db7/H1b30TL778AoMpbA3MBsgMrscj1nXgEx//RbznPe/BGEdEJLpsFcuR5aqUFpvsj/ZlMZWJxLGveOP6Cr4/R2h3b1J/n+w2ksFUmOP16wP1Ech5GKAh0JK9THINLGi4dXZx4uOVZhZzeL7f43x3pkMe2XJhHQP3rx7g4vYthCV6BrtVm1ITYYg1EJ44v3Oht3X0dcDSdQ5ax9XhGmsOPLi+VPrOZ6VfibcNkL1WwKn7Qm56peqYW72ZxlAAmIAvO4JByHYJeKD22gkL681lTzHBLDVnBCMUZFMATfDJ9RCjmiIytW9GJdnewDPVksc1/Nm//3Pcv3wd6QeYD7gnPvyRD+DurQW7OOI8gXNr+OaXv47nvvMjsrRxCRsdTz/+GF780Q/xZq63t6i1AcOSWoJm8Or8mQlEsSGGbDwDIU6MB0D0asaqmoGEu0SfAOA6RTg6mQxLpZN1AFIkRmelgJlKZnuHtaatZqjGP9ZVXukAbOsIWWc/0AiLXiuHBsyjuGcOPAEMB0oXo8U8MLQwFekkN1Y2oCPlh+tzCvBAUZMGs+j1NFiQxaAxVASUCZbrnqRebFv4Xs2WomiOaqIlmldAjffZUa37fFH0koFWjIvYrEpZmEBE5U/5vrk1qBIrkACFZGJvWJs/XR4Wb6h0vN6RJclZztfn2qgqi0rbVHmxvCeBUFSVhEiO3MY2SzQKjl+VBdZBZLVMGXA7WltQxwqUsLbub2mLdBMrYNWEju/hYt6qDXUCaLsd14JvjfEQA819jmlGB08eNlTDvgIX9X8kBlRlpRTJQy00nGwDAQgF0AaDNajyqSLCFB+nVJm8T2m7ij5OGKq8ynxjOkzpS8+B/bLoXI4tLUbhYYoRyQl2IOdQ5y0laBcKUM4ooErJT75XbcirIm0SOZrPOnxwBjLFlOg95h00bICu1q+XkJEAujoJUxg65vhvjbQ2kAQzZJWSesjpSEAucRDHRLbHtkgcSBzWjv/2D/4d+hhojWkGrq2hFBgFz0s7w9/8T/46AX3iZJ1vx9OzMsmmqLnO5TplpsKA1+7fw73LB2hnZ1OEOXUUxerCAIlj4Y7X7j2QrWDvGW1K/o4ZUiXPy9mZtiXBW/WGMrAfz/l5Q+KgFO2ALw1vvPEabt85R8SKMSahiOPambrJgQfHa9x98jG89MaPBFwSi/OwwgibTv7+5RVGdK1r2t1Zym6sbDsFugaD1XkifCgpTRsPqsPWNbnywfUlQfrW+BECpQkO+dD5YZXSm/HAtG8GszFTZHNtJbD4DmbJ9HutTB2Sd319je9+9zuAJ4YfEbGi7Rpeeu0F/Kv/+l9h1xYstmAMx1e/9k1c4h4MBMetAVfHK3zzL7+DN3O9rQEJo8sxoyGAEX3zhoiOEtnQuHHRcr9wCyxFNSvlUyvB9HvVt2OeGprsE2LJGC3SZtCdSMTozK9pybDlt+nsHL6mTjdNYMsfy5DOfirYHC83qkv/oFbcIaYneMIqyxRl2KNEvFI8lzNWNdA8xVbOgHunKPa6P/ZgmSW6J1cZuipzlr1GFxvRjH07lBSnc+FDSQxpJwAnkN3m+wSo9EYmMiWkDBraYmTK5re2/d50ksEjoDbNBw1pJtfAJh+LCUT4ulQnRkwnw54IJUALlYZLiCiWwKbhcdRhb9S3hMbY5v0VSC3Dyc9lL5Iqh6bh2KLHSn04dCCfGfsmJKb4tt4/grljxyZq64M0bKVj2CxrcwSJVLVGRfSBqriZhEOlHwTEq5qJVPdm/H2Cg/oO4G2Zz4UC+iFnPksamdKJnN1LuHYTJ/Ot9RROoJwnwYY+q5ogmhwi9+1Dr5jCwALVdeiYoRYo53OUDs04lqGUQWYJhHOuMb7RtqdCzBMZL61lMHZAYrJKKPCVBN7sUJ+yLaYAoWwBwVFVTnBvFzLHQ+u4AFnmphFjepTP8ty3v4fnvvuXsEXO3isyAXxp2J+d4cG9FR/72Kfwzne8A6OvgDRH+RDYNlX5gSnTrNuuwwzFlMCwdqZrrbkieEyGDZqdSj06DNkD99+4N/cAx4LRe4HjRMIvzrC7dY7ITlCvM3KaKvKsGc4uzk7y3tS83H/jHp558lksCCB9NhGryvV1XfHa/dexu9hhgHqxEYFl8Xlw3kjg+vqIy6tr9NGx3+2QQ/OsuUiBRUtXh2KOdWERL31aBXayt6nghalgMcNW/kMCYvkRqyAh1HzSHNVgUTOLCOhUXgpxNxZrY2r4dem7+P6RrLL6iy/9OX7841dhvsMaR9YJRuJb334Oz337+wSlCbYIUJVYjxWZPHrg6nCNdX1zfUje1oCkJbtaZjW78qKTdT6FbY678ttRkZ0MFSNG0ccjJ3W8OEspe5fjktPvIxCjY2c7loztm4yVIfo60ywxkkyAVVllnY7LCQPUw0NGxNGQnU3HZjqiWraXlCtTugcam4xEh0qe4TAsTInI8vs6VCGhz4KMlikBUlG2FYKvdvZJwaKASok7KOrsBFJQ1C+DVhsragcIqU8WKNnhsfpqAJ1RjJydyVGPrnw3mBZrVq3GabQaKBpUnc9JwzJGEGFAnc4J9SVhNVGo8qrmmMevkxjhRpd6RpFoMBqS46NmoJyr2BhFdFX5NKbGYHMQFS0BcgBYZuQ7IjCGATbQR0dblpMyU8HcCJXwqlzYDCNWrP2Is9xjrBRiN6UBKu3Gg8gG9vtzshXW1A1WlG1yVfFMEjpY+nybLAqkaSoDOrSvRHppjW6VJHQgtTu31KjZZvy0/MRSmHqLEDxwvArQ8l0CiRjAmoHjsWOPBTEAW7hOYwwsu4aqtYmktooVX22yFvPsGktAJ+6W2DWDuZdm27OWBiIEMng/YketHKkJ1G/siKmyr8Zmts+HzzOKCsAQePH0VNO6JHkWqJbwBja26sWwTOeFydgW81Yasi2IYHdZMpg8XuOLf/xnOFyt8IUBnHtj9RUCizf0deBst8NvfOELaM3Q1Wm6epVwbATg3abNQGKrnjI+L/TcceyATlWuQCZT9q2eAQXoaANeff0BNXjZ0ZrSbOayqbTYu7MFy9kO0Q8MOiX8HGrUB3ecXZyTOZEQtMEQ0XF2toN5MUQEMtEDh+tr2M5w//AA+zvnEAzgaDrn8LAekCur07A0XK1HspIImMmlusOT3V1pnATag5RMaZAKdKWrum7QfjTfmkPOABfb5Ys6AKu0vjrAlo2qfWkAWqYCd63tZDJ6RGyi9NkYdCF4dAeiY/SBb375G1izI71sRR21UkzuKQDlnqxWHCN44O3jTzyDly9/hJ93va01JESFKfTM4rDWEm0BEXFLiUgTUO4M+GkBmAFq/MSDxujaofwywmChvKcb5pkbGNjtHKjDyoyHn82zZlpTO2+bRjwB6S6SqF86CU9GxWZC9qbNXroVd7TdgrZrsAUwz1nCBy1KN4reHG0uzIjO2nJn5QVz0IamhUknxLHhAwdLkseAD+pLorN8WYUWZCsUwdpJeWdpHvIEMBVyrkqkhM1GVyGB1mm1Z536aUFRsVU5m1Tipv4GACureibpdol4zdrMFxeYambqMbDRlkUFQ5FWQUJSq4XySy2wQyS79w7V45LZ0jgrNNatT7EZhEssgTpldho3sSfVNrqEj2bOdWIUuQFkzXoclP8lu8sjDkrHQCHhpoMxXF1fTgYEOdDXA0Y/IPKIRGl4howHyNIkkHW8gNucL5jDJcKpw9GgebTFgcbUYDag7VRaTcUiqp4oEFN4LB8+AQwgJgGxGekTFs/MKOANIH0HVo+1mS5gWrSi6OI6uG4KgBeOp0F2CbxVRaffWNDUHn7z5ym2Y6ZiQJ2aTQO/6anmGk5TCT33dLXcLpbKqrx17vlK1bZJ7XM35iyX35ouCsfoD9yYIm4z1maV4P9P5sTwox8/j298+zuwtpAJrWqkSII3X7AeBz7wwffjfR96J9YYwvRikr3K7uUeH9JeYc6fySZlBJp0LufLGc52Z9p7AhfWZsk5ZMfb4uijY42ELQ3xU/umPimt4fz8DqqPSbHe8zWyu489+rjASZMumaf2BgLL3jYRrpZnP3bslh0ur69wdrFHOtOklV4EMNOgS2vYtz2O1wdqQKC28cGKn63xHYDsADqoaeJ6T1ZdcK6jRNz0NcW0jd7JjGmtn7IZgG+BNzBZFRlIrTeNbUqgLiMVYoZS4jgD114vrUskDA0v/PBF/Oi5HwHLirCVga3QY5tAtYAK7Zw1sf8wWHc8cfcZ/O3/9D/Hm7ne1gxJORTOeRHdWpRWP+fZFHNDN8zIObLysTYdh1XkYjpMLZVfVb4cCxCD5VB9XRXBiAaz0hZAv78UCyzKPJhjdFeOXSW6FRk2n6JRd561YIB6c4h8rkPGMunA6lmxCQUDrK5oovTcXREStSzscsgQyxKTgp57uZWehF8HsLEDKCOfmA93wgIA5ZiJ8EU40TgZSzTLpMGcp26K4WLgWIyDaPWhvjCwmUawVm3FTWx2EHS5z3VQhjSwKRSmFkc9I4BTmnRr7KXH3ah1KGKe3qpElolZTofttQnMEu7ShCTECiSNJ8dIRgGQQ2AqI3ACMh3YLWIAkiCxjnyvihpWR23Ab0bsCYz1OKEVy1pj0z4kxB5yLkLl8940H6f9JmwmVGajr63iyaZB5zNWKPawbmlgWw81T2zgR3qYWJMGMwswJlNiwAYUrakyTCUXFRkXIkzoFPD0ee+1diYYL2camGmbKuf1sE3Enqy8Gyp75t4EemeTvjSC8TECg+gOZg7XAlIvab6vHCsBFIDJ69Su5fxsa50hdB8xS24L3FWKbOqUZAOymNSTeNqNoOAbX/8WXnntZaCxxJbdOGlv9rs9ReVY8IlP/ALuPnIbPchiBip1iQrpJzCCAFSxlNNvCxC7G2LtuH12wbNiZC8yQxVUWVI4AIn9ruEyOiJWtkIomy4mq4Tl0Qf2Z7eQaOh5cupAVKARGLHiHU8/jSUbjgnVabHS7PJ4APaNInInM2jZkdGxGPDaKy/jqSeegDcy8TE6PB3NEsfDFc4uFsTascBw76XX8K4nn2XredkUMkU55ya15sTr0nYrFWnYAhoe4YGpt+MMJ4MOlASBo1+hVIHxKjCoNg4VAALFvGmtlR0FWVKIya1qLNO8GhZ867kf4Pl71+g2ECoLBmSDsuwWgwa+PcHtojTefrmL3/jrv4GPffQDeDPX2xqQeFvQlmUa2OqgWJsm57ZxYKr1TT1FaBJtlrQV/VWaEw74wsNFWDZcFSle1SLghiuaLB3Lbs+mTeqQWv0FaGREWXIHK8+8neKYAZ0AqaqWTPZNiMDS9nOBhnb+srCjuVnqfAtgWdjF1Ywbs0eIImQqqY8QqGFUHhKz0QGpE6UiN5hGTlFEKBosCnsEeLYCNlzirU3abUZy2KLiRQLFLI1GLXBgjjsaI7FNUOliGDhvzRvCJLqdQrrcxHfGzdqRW4pgfgrvo0o9OaZ8/ZD+Z2dn1ElEsJS7nIpxA1cu3c23BmozusfJZ1QJpABk4ZmKaJqYCRmfPup+p9eetOq6rmjHrhOa6SzTTyMmgQUz7JfdfOZm1UUzWaAzcaYp1UjQp8T/rFYp0eEcI7c5hgQJmPnyZtt98NyinKmYAhXx0D7g50M9SGAmAy3gEsz106FLAgAg+sARbExmlrWB5mLbojSug2Ja2AeCEdum2xLVrWonVj41AY4NMoX9lZUMU1+M0xy/6dnp+5OIFClw1efYUDaR82fIAns6psKZSpxrG+B7aawH8xFkFkMOii/GJsreUk8pgH99eYWv/sVXkP3IfWbB4ySm0h84Hjre8cz78dnPfk79lmpstK8yFJFr/M1m5SD1bSXOBXtZ6K3XqwNu2YJ9GlPZBoozJ+tD+2QJYCTWwxERRx5s2TAj8Ln3pE/bX+wQnkyT2PY6g45yQOKxO3ewh+GYPFgzEViWhugdS1twyIMYbGdxhLFC8Xi9wkbgwnhcyBo6jtOY8kF0eKzYW+KVF5+Hfeyj8KROS6ZXe7+CIl5lC7bSdtUUGqjl6mOC/mkn3JhGMT67o82AZ64rldxW/584FW9XYUFSS4Ks4IV2iz5saN9sAcXh6hLf+vbXsY5rZHtYOJ5IpBvuPvEoegzcu38fFxdnuLx8gLESvO2WHX751z+Hz/zqp1Hn1f+8620NSEhPsrKjGlNF2GajstqCYyLIqTxXFUXFfeaMaiJyLiSAotG0UJMYm4tlDMPoA1jYEtvULXYM9aUw9ZIoCtXU2h1gHrFoMSPNTbHc0LRRsc7FxzNTyunOs2MUeZfxbK1NYJKhE0mDC5H3jpnDjVJ2A5tXAaZzNAnnyB7IsBqo6A6bIGyZAracyNqxOZKZpsmU4nzGVajj5ZttlRpACQkd0SsVR8A1887GeD/ztAV7iTWppJ8ReaWTSHUJVLGFupcwMHM60Iruhg7/49Bsjmge/jWdejKi1T7NMkRyYtW/A4DU6zmd1ib2BKyoVzdgTYFVY+538PyM1gzLzig8daYO5lkUEwQpzaPKjsWdzFpilmBC8+GQuN/4vJYnkG2yXWoTrmnjEfOsVquy1S0OB4rFcDF3HE8+owOgeLpEpnPyJkCvsaMx35rWuQFj7bCR0vtsKS0kaWiC5mI4s5YAP9tBuhqhvkIDS1um8Y2E+mlsQLCcukWeHFSWJ8ZcYKc2knNMYVxbMWkzCpWrsqi1qnzKevyHxj0VQM0GgSh+pQCXWMPSwdQkGiY4qCq1jMRIniL+3ee+ix//6C/R1Em3yeENJB00gByBz33m03j07l0cx5Uq1jQuWQJIm47L9dF0VAIgCvomyzUS/XCNW7sFO+3JrpRgzLSsHlTp63uv3uNp5Y29MyhalXVRX4+MgaeffBQt1Y07i6U+BWSG3e1ztDvnGJf3AAC9J9Y1cDysON+f417ew7H3edRDRCDWgThyvd26fQf37l3SfmsOR3QEAuva4a3h3v17SAyM6DDsgJC+zGutxPQ52g5kA0cCGOoP0wSQ29ynKPZ4rgMBavjGXpp0PiAIhJjMzR6b1qmhDomdolYFhg4/2S+J1159BZcPHuC7334O3//+d9DaEWFKUYpx4Z0brtcD12EfOB6PPHh1cE996JMfx3/6P/2b2J/vcXl5iTdzva0BSYp1gPOMFZ7R0VGniPpiRKJzEjTVG2Lh/q0KCaH/COYyCRy4ubYuNSefn5tyv5oWEXu4GAuZ3ooae8iI65RT3Udk/e3cbEXXDVpTP+klMfPDxjyzxwaeKHQFFjmkUJpkZCIHG50lEtSNnqQ4kl8vbTedblsWleMOLeaUgRBroVRB0X2mCpOiYcsAIx3uC0asGAnKVSYt7agzfixrE2KeD1LRNOPemMb5tG9IaXqqRiMmTWEbMyLmqw7iGyNkNAhgkVJPVMfI2JiK6q1Qzb8IIOt1sx8mpnXmwpRj5Lf7oEHNIJis+JtTSk0DUBoNRZkyGsuyKOXGzx9jwANAsXWpCpgp4MytD4IVeOI6MgFh6i5CbALnMObi1t8TbGhewM6NlaKZ84MSoIq5MaUsBKJLwH0q/Ky9iwTc2olIlGlGHgInQ5qYTtHd4QvZAq7Bhj4G6WFsjnAOfs1DiUi1zgokVyqW2EFOV/tBr6YzUDVI0/tWRZurXLhYQ+bdHaVvwQnwdDP2w9G/62ezmgKgrdLeTrEs1cunKpVSYpjUfi8nihSD6balzkx2xBr+3R/+CQ4rNrGkmVJMQNvvEMNxfn6BX/m1z7DRmIAXrBhgrdp6tiyHpvREljZCzbgA9hTJwLoesd+TOQ0xAUxJ8n5GAHDD6EybvvbqG7Rrach0JPaopnyOZD8eAE8+9gSyKpSS500FSiPIefP9HhePPIJ+7w2xuYZ1BI49cOvOHeCFV2FoaM5jG9Z14LwHFms4Xh1x6/wW7t+/JPACA6QY7FtzGB27Wxd4cDiwAR0wy7ARWvlZIEPsiRGMjVGVXCyZnv4gA94WznFzAQDAfMFS4ttKzTp1TyVqpvXA5uNkCmeJuezhEPNrSKg8Rn7Q8O3nvoff/9f/Gg/u38drr76KdV2xOzNEGLJje4bkOD+4dzmZm37g+XA2gHe/7734z/7Wf4bzW7fQx3oC9H/29bYGJEwxjBlBuIGaEBkUSvAMw3QOSEJCHiqBTYgeKv9KAezSeY4es+V1aQEM/KBuLLuqUsvT6GozGloMisZZKSNjfYJuIgZPGGa5y1yYKe3HNFJRLAA3XBPLQKUzFyXp0JxIfICqbrI8fIIIGpwGlofW/de5HnEC4B5yIc3RfKlVDu+g4zICtnpu4Q2idYEdsz0CA+ltMu0l4g2J/epQsjE6ZttxjVRCTvmkaqAAX0p34W5y7jLOg2m8KvEtHFMGmwVCTGmN00hto48w6fPk6Z2V9ilNxaRVy0mnUlzJKJdx+Sa8pKOqMTsFx4o8MqdItYlNscb1EIPdEBGpA8EqfVN9NOiQxxqaj81xltCl2Cw6GeoeOL4FKOp5MJ1cRcT17N62KhjetpJacqKTi1FEXeXQNaZAMio0k0HUfj1ZiwWQJoMRwBo8U4PvTY0V0yMPbaeZGhsR02lnkF0knW8TZyXYSK4JnGOmjsQqGeZ7MNdPJ06NlMDINPzbPQzty0AxCBzU5hJ2i6mIGuzJTJaQ9bRbZmloNkWUcXAeipGmnsds2oS2NPz4R8/je899n/YgNhapTk/mgWgrfv0LX8Ajjz6Gta+AghDXHmXwZxMEVy+FSo3xWQlAs+yFPmftR9y6c4uVUb3S5Zwz9wY0NVGT+Pvq+gHY4MDnvpki6AowYbh79zbGWBn8RIoNr7ZrTGkGEhd37qCPhkXVdOaJHgO3zm7BsYdnw94DV1m7qGHZL7g+rohmsluBAR4j0NcVIyhe3Z0teO3+AxzWMUFzpsDLDDT1wJVCAf3Csuw4lgInELCtJmd0HdwvsxjmhKkqbRRfooBN9pa2plzSqY6l/AWLPKoKcrGGe2+8jj/6/T/ES8+/iN47+pFzdRxHlAj+FFlUUDYrfGQj9ufn+PznPo9nnnoa60qRrMWbQyRva0DSFP24QiFDRb2bYZ1nwCQj5Dr62ydF5kLcQ6I1RUYBNGdbXXPmBRMpkaVoswEsCx3jmAslkWATtNrs2pc82E9pCIVLBCzuGLR4XIBJg8tUR87NmFboGJvjA5v1uLH82Iz0/jR0+pssSZ/j4saImYfvVUWCyyYrzaJ8fIOADtc5olP/USI/6qIC1HgM9fQwMLXCG/cGVJZlq0Shw84M6hBa5akV4aDen2kAD5rmyIAaziDdRBMOhMlRax7MBFrn+yliVASep5tk9kTgOqlmbZYhULgZ2BxMgZGa36JFuBwQWIVjraFHwLCbTr3yupx3zSsG3ENzsRnrMFYTUa9ER+VuUtCLodGzwk6am4klGGPA2sIOmyO3iB1AV4VIOQ8uE5sKek5bbGsIBMCtGEN+B1Ut5CdjW5h6xBatMg3B9eRKfRoYnRlK3sl5bN5Q+hKvtWRAONhW2wxj9AlMaz1FVDqW+37o6+oxM69CD8V0OBBWInDMPT8iNR45HUaGTbHrBDUJlOYKVpG0TXYEE+hpjZnNQzCLcRyK+ovZao2B0wYeUz1WbK7xrQx308RkpKq0xLqE4c/+5Is4XF+jWUePgWVZJsu4W3YYY+DOI4/is7/2aywBll2pENsyxdpIejvLsjemEKieJhuw1Vc4joHHn34KaGRBNkG0NC8SZS9iMa+vjzpPhfupOVnRUOuACsZu3VKPkWTAMibwlQ1trLZ78sknEeObwNIwBoDsOF5f45Hbtwk24FgEJMYIrAPYNcPV4QAs7PAK2calLViPBzRfWGDpCx5cXqLHwH63YByLGS+UnHO7lKzAfUHvHQMCFEul5FnBld3FQGv/gP4gugI1ryCGzzq1UsH025Dgf+7j3NJuaUwbEtiq5B6O/uCA3////Dd46Yffx37XcLg+YmBleipqjk8CL0j3c9LiQIgRZonXXn2VZwO10qP9jwCQlC6Ex7/Q2dfGpKisTs1saL45DrUXmw4G4KDxDBpMFuJh3YmDOTQO/lB/iiXG1mtDcIQUAWbJYEW9QEg0yA46I2nEHdWEDdycE/ZKBV1OQqc+zhSOYpLZN8S2jpMVaQ6lVQw5DfY08InJ3BDb6dA4OZNUBOUGVQD1yWJMhiNBFgFyZoWjp5CQz+6KiiMpeJpplxQT4jZPo+WTM8obYgNYKTDmz+sP53Rgq5oZW+2CK7rUHFRzL0aKgyCoAJpvp2USGA6JEK3iLeTg98jIyKkm0z514NVMLJ0aC1RaUFStl86J8z7iCDNFQVobXCZsI23OY8b3tiAGI/Lr4xG3nQCuHO+mcbEpHITusZlh5NC6FTCJk4jHKjrEjHaqZLE0mJ5s6Z+1j3LLVKUipdp/1b574pmKoCI3XVXtYxT4DDEOAYRPJ4iK5JK56rGu2C3Oks0kUJGvPjHgJ0Y9MOnu1AuZtpqPzXsIRYHO34Ecy5ilvzn35azm5EpFCRXpsKc7530vyxRfs+cJ96lqYngfzcTiyE5VUGUMZIplaUJcpxVQcz7npgCQCW8LXnzhRXzlq18GckxhYQn7zQz7sz0uHxzxsY99DM888yTGWOe81lqvVOMGvCoFpwofUtMTEJcRqtTWq2/cwzPvejcOKwWoPN9lAzNWgY0+84179xCyHZld4hj1d0ne/263YLdbCNJkL4dAUoHDlK7l3e96l7QnBscCxxF9PXAGcqX1k66lq9IMBlwfr3G239MvDJYwL9ZwDUN2Qz8GoifWkbg+rDjbn2HkimbL3Avb6sYUwFtVVCZbMmxgE2Q7Y8znKIAKhoeTKQkB3eaL9p5OGa81bdtimP8s5kxjvVOX7Huvvo4//G/+Hb7zzeew2y24Hqvs82bDZkVdzXHt+5M9DD1XwHB+5wJtx99tzmNe3sz1tgYkFW1YOcIp3BPaLGllFkp05t7FTITCfgIYky/a6GIoxz57gxiFjpXr5GaUOA7ARqEy/TFP2oQ0E/BZVWJq88uuoDnvY6YXatahBRlFAZIRct1nmtOAZme/lOlkRSVLVNV2OwKBIbGdEYDFCPRZehui+XVlInpHOLDkgtPD/WLwHIitiVuNcYAH9m1tkGv8FboC1eIfAPufJDIbqjPuKXUNABkdPJGT9fpKPmMkAULdK8XFW1tuYDs4EcAEjgU2h+5EEgamgcTYjMmWcMzZvbPmUxG41JgVCfITy7kW2NTtzQ6+xBzFdliIzpRuZWTqVOrNtyytIYaqcHQeilMoVDGYghNG8jz/iFFXda+cup5kc78tqrYJTApkTsBZEV3zk+fU+soT5iFKYCvhsMSVjPBOjKLukQBWFSliHKbe5YRN2ECL2JdM7Hc7dkuekZkEjdr/hRlCPRjKHfQY6hUB1BkwMMAVYZ8a7UpJmMaE5zkZAYfmZTqKbZuiOIE42buTIUEZbXv4Z3WHdsK8nES2qL1T41C2QkxEFgKwsnVCZvr9r3/jG3jj3muoTrbNXSfqal31gbOzu/j4Jz6JtlSAJ23KUBIm2bgxkiX4TDlzPFBCSa3nAgF1z8cIvPTGG/jobofjqAaVmKxWgSg2FWNPoTfuXWo8A24qaa/ADXy+8/0Fznd7tAq6yu5lm2sP4Fktjz1yF7ewiD3im1XX2P3Fjr6gKopi8OyedFxfP8Cjjz6KnSkVNSAK3jHWgbUdVW7ME9Et70jLJXDdTjRIJxVhY84rg1jIVnC9VfNMyJ5sx1uQ+DxBfJnIWLW/Byzatr5s82KTNcxtjboBuQK//69/H9/6xnP44fe/ixgr7KwB7jyEs9a6QODUpZRRR6hflqy+7MWdO4/hgx/8EObxG2V73sT1tgYkxhOkpIIXCi06SUwEN67K0056T1AAzuhz8bZpJxKosxPMGJG4N0YXQ2VZ5jg/O6Pyv6fSM4ZsW6nACLINtfGKnnYZjuY8wXYjQ4zHjVu5N6Z+MtSuHg63UOvwYiEEbjQey1JlrECoh4A3w5C+Y9J9oc+gF9OG2BY5OaVKP0hrsK6KmGKCOmSlnAzIMuD13jGrLXiPLnq+TdfGVtiKVFXXXgwGrCJM8AAo42Y77WRLJovVH22x2R8GyQqgMZX/jEpUXzQZqJnWywQk9GLUpPGYQDdPon++j0zJ7KHAA8c4cxVFVO8QWveU5smp1RFlXem1SOB4ZCVXKnXgYNowBrDYMsWodUr1diaMKi5AFi2yw2wrEY0AeG5NTAMzss4ogcrOpS8C5jwWUCuxaq1nBe6AnMgmbMVcU1yafI4RQ2nTyln7Nn/Yuu4mNOHFZqbAr8qAMwOHwwFnZ2eoBpg7nhCnKiLDQAFubBVggCrDFI27s1yeu0r2ofL/lfLTPXaeEm0AyzmxgabE9nddW6CAqY9arE0ha10NBnOeu0TZuM01v9kwzLU4GS2BG8i5sGRbqS05jhJfXl5d4etf+yaO60AaO4cuSm82GHbecH3/Ep/4+Ifx8Y98CBl9smHVu6n0M2VYqtKEgNG1dwU06v6stEOJ43rA4XjA7mwPLE3bIWdFH2NERf8GHI4dr7/xAEtzNHG3xaaWU3Pf4datx7G0PYq/jDT0HrKVNucCGbh9foFHbp3hQb+k3QFwPBxxvD5gtzRcX10jnSeQRwxkPyJjj3THsizgqe0E7myJsOD62HG+kBFoOXC4fw/2xBNYBHCrmq/VkQ+1PrLGUmMk8G4p1iyqNB1idLZ045xvOKwEIoZtXbghihHGVr4+T2An4trE0IcVD954gO8/9zyOEQgbWNJ44GsmWjCF1Yz7sioj65RzTBtHhtnbAkTiox98P5598imMtQIfPATSf9blP/8l/xFfVhIvdTcUZaq9rWiNXSm3apvE6DpxFYqhjdqHqmMnu6DTbpPNxFhp0diRVOLPoZMSrSYFCfb/GIDcOTKoHUlgnlyrHHpTWamBXfSmU4Y6jQ6WEOYggKLCedFvME4jdFhg2ZDDpYswmC9b7tm4mdfO833SfRrloippPDsiByI7ejm4ZDfPGEG2pA+dNhxqqsTvo3dS6APwYAMqy1CXVGo+qiX5iIEInhhZmvyqgmFL99O28w60xqPUR1I+YQ2Y4mCUfQTUUXX2tMjJHcgrYxrtSYcbO3+ylj+0NpTaEv9ZzIEp1PDEbNfuyVROg6E5jxxoBvZbMTJsJpX0Bj7ZXyEELpovcAA7nTdRgsYRrEJZfIes7rUa96F8egI0RgJVjpxlzhHJ9E0kxuzIykiclLzN02qn0RSAqv3jsBPNB3ROzkmUDwiklF5KFUP1rwgsCXWJhET9Y4JKr4iw+htEEBxavVZf1zxOp83n2p/tITNMgFFAqkCRfmdUT5taM8UtnfRVCARGDgrgYarA4h8vVqVSiPNJf9omYY5PVRudlm5Wx00g53pQTM8xzgI+CRQNX3Nzko6bvXan1kLMUwaQTCN//7vfww+/+8PNQTrPYBkJtLZDYoG3c3zmlz6F87M970lBRuiU84EhMX5MB0c7SZtZzbim0xSzlLXPAnjk9l08ducu2BhB62s2nhN4t4ZMRuaH9YgeFJpz2yqgLIErgP2tC3VE5aBbNux2Zw9NRfGHvhhuP36XzbsUxEQEDuuKi4tzxOi0ogWqjEcM8ITjYGdbb+pJw6Co2FOLjugH3HvjVTQt8Mgubcq2l0/dsSHnPJWmcAvCKtAjg9JHSN7WNLb6bJgCEQVHtj01g4mc6xViC5tJ0A12T172O/zmb/4G3vns09gtCxbfsztu6ER5gZx5g8nnU6JRgVGb1YuRQFt2+PgnP8Ezp7CB01kn8HOutzVDEqMjlh0HQwyAKn0ncjMCSk60VQCdMNuotRiJZdmz4Y3MBlXI2mjGboPUKujYekUqjPA4Z5F9It3pyGAqX4PEknp/rVDKBrb21Cbqsxf7oZztXLHuiGyb0yxK3NV0CTSgs7qHP2W0s1Rpsp2UQjuQFT0q7k3GmphwjxFTqH/BxsnY1mWR4e4cZ0wjyT4RW+Ss3i6pFIhyi6XON1QbfEbKmYDrJNyZZzWjmBUVtQW2So8tOitBMKucZCi1kXjL+n05kYiirDAj9Ml2bckX/v/UTNTrcn7uqfZoXmaqllEJ+Ix8BzJWmKWMRTkErfEc6NHRXH1NACnXNddypuWUCsR1CV67qgGqI2P1RKhngG8xSUUxs4KpjAkEumsto5xuTiM67ZXxmIKMnN1Ki5mJzLmMIaNcES40tyzZB6N1hYGtsVQ7wVORz8/OsPZ16sKQNMBN0WvU+Tz6nAI/qLSiVfSvNK9oHzdVUWVHKu04WVXg4b4rtgUiU7RY3HjtkNoHqY7MwIkeRWvCTVqlk94k2M5Hqq68xbaFhm6m3HyLQAu00SE5vvqVr+EwVlbdOQCd5Ds1Wx145O6T+MSnPjXLReNkHXM+ZQHM1ai4wNQGqgBsYnsTG1pYricevX0Xd27dgk8htewvgLBiqfgxx9JNtara4SEAE6xpF+/3jjqYlmx3YFatiQmuitaewMWdR3AcP8C+LTN1eXm4xn5pwpwJXxbE8Yh1DLRBR+8O7Pc79OMqZph7sPcrxHCsxyPBzfGwAS0FOhD4h0DytAdG25UFTPRwTIdiBgalK6y0VqJYPPaXsVr7Aq4OpaOz8EMN0AaSa60hEj1W3L59Cx98x7vwwk9+AINzX+nE9CF7mKBt5+fFPG8L7qoUYvA0euKxdz6Ld3/4g9SMlEBLr30z19sakNTjZjod82BuuZkxT2rsHRAqLdxq6VVG54ZM0udD3VvLadaR2sq8AIgZ4UnKBQPQk4uWlFZ7qCTXK8cu7Qf7HojCq3SHnHKdIzJARNxzzIOPIjZtQh18lMEGVVXOae0kci3HskjUCGDy8wkgOtz4XmyytjURq/RRgpHsabWAmetIPEaiIS9Ehz7k/Om8mf0o+tDmpjNjc6q5NyUItCzAg1n5VIcg8pE44tQtsPHcBASqC618/TzqfTYKMraGhgBBHVSncSlRaNaqqrr9E0A2weH2Km4ypUU4T1sYMFMk0okQNMhYw6bzp5ZpUGSraDhKK5SOxRedJdQRcZQA9nwamXmsAQCYq2cHub/z8wtGlip/HKDTZURFJ9lPBZsoB8exXBYdSR4qV7dFcyejuzQZ0q1KJCJ4MGWwao0FsAXyq1S9UoTldHX75YSn8LbE2ew8XH02DusRVWiwrqsaWgsy5eb4N6ar9CxRjwmDkY5eBFJRNLcOxJPRrjnh79deOokY9fXpHqFwF3N/hNYvgT1voLRPNBc+n616f+AEzM1uxJhLDQb1PikQUjYrE8uy4JXnX8fXv/rNGTTVYXhRqUVju++/8Zt/E7duX+DQj0odZlX0orYtK9ICaHSYzXOm2iDwKZ4TW5hAjcr1/QdwJHbO4IWksUCqUpdDbRhaa+iHS6Cv2DeytWmJHQwdmJ2JzYCL8x1aWzQseWJfNvHyDKYi8PgTTwAwOVO+yRqB3bIgLLGm+iGJdYjRWY2k9dyMQcQYXSW9DEgO1wec72/h8o1L9npSugM1Fj25B2Sb06ufDVCdsRGmA9zLnvG9WzOy/lZSAnW3rbkxMkOWoO9rSjSmAG1WKtCL3ACCaaNA6eIGHr31CHwwNRV9xbIwCIhiWtc+QRIfhYBvtztH252p2KLjzqOP4G/9T34Lty72WA9HwLTeDdio2J99va0BifuOjnzKy5mzLVEexX2OxRag0bj1HlPlH0LUZjxe2hXtRZYhajj2I1B6iAz0MWAZSDRkazyhsURkaDwrB0Wh02exYowLI0YngLIdIEQMsO6cWhXm9Jvv2IhKRi0dQq4FHHg/3nSUu5El4BUyuMqUVzSjtVFGzn3rHcCgpqEtzvIyAG1ZyLxEzNb0EXUcdwmyysl4xcnwtlNzMeW1IYV7o1ZnSLwKqJpHpmyraOEY1tkVmE8lers298laOAUDxXQwR5s6+8YmWIzBXDMKhFg1Q5NgL9UnRmPv6VMTMOlzGfRi5kzrpk7yZQRI5zTslEEoJ1TRCnA8HhFpWHZniHFECU0zBrJ37JrPFEsiWGHiUNpLrFe9n2mNCpw4toqWGANV6VzPkDKsVRlSLs98ATtBnKTG+CtwYxqCoflWMUXNhyFHVWicng/E9Td6n1GeLwVANtZi+5yFkXPouXWA3NXhgNu3b6P3FT0CPRPWlkkxb/eY873JltgMKEobA0BHKzgsWdIvuMbx9tIv+JZiKtGiDO3DTEUqDaelE9vY1tkk1cCvGiemWIapg9P3Ko26NZbD3G+Iag64jVk9kuuQvH/zb/8t7l0+gDeuGdeaCiR2Z3tEAI8/8QQ++cmP4Xq9xhg6HkM2hEyMqhGhCH8IaBWscpsloVlgvcB8Agsa3nj9VaYRa72c7l8FgMUouDmOD67gawfTcByHju2080p/nZ1f6PkZ5C0QA6dGjlVxyNRQ4vFH7mIRa9IlxrWxYnfrjBYwBqoVPyKwmGPnDb2vDBoEuJla9tn6oa+B1va4vDwgO6twIqsjqzSF8k3TlGWxIMWUndjlBLWEOgZlcR7/kajAWkZEab2mFvwEQa41ue1Ffnyt30LjClib47h2XFnAzvbA6Lh7tsehXwMw7FqgrwORNiu9tvTsDhe3n8LdR25hvyx45zNP41d+5dN457vegd4HW0VIbDxPqn8T19sakGSytTV1nowB3cguWOpwPPhsIBbIStiigLUgCKp/BneJpH0mpBiirZaGEnKxY5LxcCbw65Divw4Mw3RetdhUppuYhhKAwIFPNXY1JGptxx4UEVO8N9MWuR3cNbumVrQkhiwV6mwBcMUxzD1vLEexRpNI3L43WaW6XwIN5k/1s2KVgNnIB1NcJpmnWKlqzmY4GUerprTOyp9C+MA0iFX2aOp9kRClWJ9bMfJ0uEWbm0ik0yjT5HI2qoYRlZxPNSlTJNuq8y4qstEcmoG6oK3z4eytcMLC5ElPgSkAROXZfUvvGA1dPZNZpU+AZWlYlmWm/zZtUMxoqJ5jWRaM0XE8HtBsOXlun+tklpZPIIK55h8GekNOeAM2HNdau2Voy7iqeZiWnHmbYHaCy+nIq6qqHNTJvWQ1MtORB73DnI6/7XZYR4eOFaU+AltaBJaMFodYiawzcdSzCLVW8VCVVh16d5oyM0AUd8B9p3WxDR1TJQwG5t6xTaZbBRbl9CpFAxAAJVHEnDtL6BdsgtiqPsq5d7SLBdi3NCGF7S+//DK+8a2vAq3mWmmGKLtGRvhTn/5F3HnsFsboWo8TfoCNBQhs3cCTpa0YX4nNxZZx2k+ChNzA2oPrB1j2C5ZGPUTZ3iIwccIsuRlef4XdQXPRe8+lvdmVzMSjjz0CXxpi1cwX7epMK04c4EBi4O7tW1iWHRmSoMGxznTdsuxAoahsUZA9OGvSRfgCt4YujSKbLpLVXPsRkYk3Lu/j0DvO9wuQlf4s4b70VVoHlbYqTQ6Ah4tinez9yAHPRXPGNPpk97eNsukAG2YlJv9XvkasGyowytnQ0N3w8U99BLfuLDhcXeHVF17Fl775VRzdkTgikulks9w6wUbg/HyHX/v85/DRT34IbXHcuX0b5/sdjmqqx/N52k/5l59/va0BCTJgtiBNAstIROOR1m6OIacXI+FLm06nDIo8HAKBJmaDTapoLCNM+cWT1EABBzNkS/Q1pERuKtGCNqQ2X21igIZSp7oiYxqS6hJpZlPJPLtDhiM1S3Pzo8w/N9Q8YTWqsuWkgx5Syu4yzJW6mINAw2/G8tqoD6Cxr34r1nbI0VUdvTnAElCV5qbNMuTK+TPCZqkrnSI/lznPlHYiss8ozyoVUtNc/xeJcDb5moZYIMRtvhJbU6YylKUFkgOVmHjuU5RCxBDrCmt7zUGNE2Dqw1CC5rWrpBlM+1WTMMPJsfTVb8MqOnbA1XJ8KA+fxrEGxbypaIYjZIjecTgcdPOG42HFUATiAnQUHpMGb2azXNOdZY99BJs4GZ80lW+fh8idrtEsJob4lexISUb1elWVlaBRi3syP6dpPi29+fV2UvBmjOvrOj7Aq4QgUm3+Y+6X3W432YGa1Ijt69Iaba3MZfhdX5mg5gldZRl61gowkj1cYmvzXuXkleKtckYtWOoYlC6bYFhA2lWFli5x6LyvegvZoZMUTK2/CEeeuKtK9VoxALU1ZuVZ4mtf+SruvX6fpxDHQednkRXd7ffIAJ589An84i/8Aqpst+aFvXTq1OIZyWgOi/KV0NKtwhvEWLU3tlJ7M8ODwwFtt5/gAjNAV9qw2idoDT54cH9q21Kp6Zq30pQt7njk7JYaWorpBvcZZmChXa35u7hzG/v9Hoe1oyXHI0ZgvT6yHDySgs4jne4IMo2H4wH78zOk8SwcaZyRMdCPB+yaAbuGNx7clybl9rTBOedeDMec2pxi5SkKnoEG5nozoz/a7H0x6jZZENrEAhljirrtZBVy6DVXRpurRQMD8PS7nsAz73gcLQ3/6r/8rxFrwC8WrHFgYC9bVF1+Mw2PP/YIPvNLH8Ldpx5Dj8AYxrRXa0pT6UmLHd4szM+83taAJEfAIxGlBNbEkK4bcjg+K1vqyPWi3TL7ppMw1lGbjiwfudFM7ltnS4NveWbehapGWGXRIJq38p3YFgQPxAJmZaJQc1WFBKAKAzl5VbEUhW9Ke6S8+yypChoIAoMB5ogkYMtg+auc72w+7bq7YloqkV/xlwOTLtYpqJnODiL1WamKDgCOrfyyCnthCZ+psGKLXIiZeWOdBEcHbDadcebWyA31dVb/ldiiRacuosR+7QSJs/mTAlDRtDTA/HlbNqbCzabjMs8pEA4p85s5evRp+Evc2RqZkVEN8op5cZvGC0pFzeh7bM9ktlArpDU5us69SWpb1pHYX9xiK/IMRoWZOByPuFPylQTMDWuPSee3xsiqTj0tdo57Qzoaszm+pZepXi4oQFVAuQyK2QlL6BN0KCjTZyhXX4sfhR0qxXAKGDdAUoBy+nkYltawuKN37t3jccW6rqTYMyhih0pdE0g4Qj2IBk6AS0kzkJM5zEg0HbNQ3UdD2gbu9RPQ4mJAYuiE7W3caj0W87VFyLWmi8mSvkFrKHppCx6OHh1bCwIU6FbkO8t/lZPfxNEEFW+89ga+/uWv01lb2Sug95U1eW3Bejjiox/7ON7x7DPIvp7s9WpGJs8oxqj0DbCmjr+mZn2a0+DeyjCdqyTtmBvuX17izu0LBnKja51r3Ao0ahGnBa4eXPKwRNmeAE6Ya8AisSTw+H4PB2ajP9oQzRVAEFtnTo3E2a0LPPLIXbz84ovYCUhZc4wY2O/2uLq64iGnrlTjGOhjxYKG3X6Pnn023jOJPqsn0eIN14dr3L++xN3zWxLbmoTQUGpLerITeFHC0dmAkHlYwBtTzMhpGwLURkYmGmIKTL2x31AAZOdrt4mFaQoqafsl/BUjlZCQ3nkPvQe+9dxf0i5aZxpTa1itkghNfY8PffIXcOfxx9iqQP4zSqvSKp2bajOBN3297QFJdC68LSIZEuEp52uOtED2jlO6DJEq0y2jvBlKoDpb5nSODkhPQWGmqfxvMUZMUGTQlT+v90lRwVVhkHKKjCboxKfyHDLGmsQtrUODSLskenI2hrKHGIMEeIgaCvBoYzT1JBljc+ba5MWlV367nDSAE1Bg4KmlY276ShlU2WZpd7BTl0w9T4yC/bLv0jlA7ruo+qFqo1lhkMVKbMAL3bTgWVZ32vnTgK3j5SBoY2UR6Vwa+VGBtRwpDURMwMDvZSRTDwKmBWKqsdrUTShoLAfHdswlhJz+DDGrtmyuzVILDDXV6NW7pj4Hjt35GexBU38Ntss318m7SeBdQlTTei4Wp1In7Nq6CXCbFatTQEBgRKXWNfnVorxCcZcRgxgKN525kYFTq8M+P6Ex3NgQFwtQr7HyefMe9HkV/SW1FjESLGd37Pc7mJHO5ugF3FJiTStb/1MVPVuESbIlFFQIpIEiabOYeyZRTbjERpwwIplDJ+GWfsimbsD0PG62sbYjZqohu6o3jICVrEjtJf4j9AeyHUxNYu65atcpC4BKw7Xm+MGPf4wf/ORlpPFUWmq2yJAtjTqis90en/rFX8R+WbCuHdYMY5QAGDNgQjAoaE5mb9OvqZRcIIYHZHoZjIdY4RdefQmPPP5BxOlm0B6glmcD/8MNl2Og2wLYAcVwVbVeZmBnjv2+4db5gqYeVH0yS/W3wI72Ls/zWnBx5zbGiy/J2QeasjzLboe4vKINNqBaGgDBysnlHANkwWMMLLsdxmALh3VdcX7nAnk1MFZ2XJ6XVfIfoNSxGgWmyplThRCYeg+2dU8WNbghdcSIVXWjqnLKjpnY19Is1iSWjq4EtlwqqaBDKcViMpFoyw4/+uHz+P6rr2M5N2SuiHHkOtJ+HFqvF7cu8IlP/gJ728wNJ11RGtsUlF0YAuBxMi4/43p7A5Kkg/FInTciwdhUpg8K8xqPgi5nQjKlBihnFIiEIgtGgZbcXO6YBmm2Jo+Ag+LIYgnyBBkv2DqPIssQ/5Rhk8F2bXB3x05gxhEYVdID6G9GzdX2mpVBZRTB+0aBhTLOpmKTLcJNL6NQIjYafweoAdHvFTtQ4AA4ifycgKbG2mHzSPNMpidmbJwEM4Ciu7pHN8DK2Ciyt+qWmur8pwi9bU6qqEaraD0GUiBA8EMOXYYaAk5yknBMKrJKC/lMBJxDm/SUPk85DKu73xAnzMgcDYwpfC32oTrfVvOw2ZzMGXoe+8BYB0YYYMv2iWaAJ9Y+VFXictAdaw8c1xXVGsMn0DbV/3POQt1JK/dPooiOobQpM20gIINaOwIS89wMvacXqMKm3cJPiY9n7r+cRGJ7X/3cprEUoJcTrhLQ+px5QJ2J8ta4llDSzFFN0VOVZA6lRE8YhUqFWvK+LYHFHOas1CC9jlkZZ8VMWDmQErajsDVOhbjbv206xblatD8z2eekoViF7VWV2kmNT0pXtOlStvFk/x+BudwChhiGb3ztm7i+vp4pxgKbMMCWBWMdePbd78L73vse9twBVfdmDGpOpI+TrU1sIlfOudhXVSKSmSowp/blzkPoXn71FXxs+SjC6IQphoaeXRPB3waG495hxbE5WlYauNK/YnyaYXdxDrt1rqkpe6QzjmKlDdIpwFnlvzvHfn+OzOp1xF/tvU/B8exhFMn+OUrN9QSZ3NXZqVZM6EYqs/fI6AcsiwLEpBieTKmcPwqUyc5qfRnI5p72yCkbgpqLCk5P1oS7qyiA69ZPg2vbtFmnadVQytpb3b+qbZYdvvqVb2CMwGKJdRxPSrldQQZt1jPveAbvfPZpxDhOsXJpG91UITlXv8rx8eautzUgafsdSw+zz4hn0l+Kqo+947ztYCpBtUwsTWcJxIDlln4p0LB10dwUzOaNDXTUFCcr8l5XuBkWM3ZcVBpmDEZwTekCN8KlPhErDVj1jWitHOx2L+YbizFbtOvZqwvqPPMCiVAlSTOoRI9phhn1Go+6t2T74iz2w2Qc5ACY2qIQkaxQ9bU0uC/UfRgABDy1uSNhuwXVXXAyO7aBlByJtmPKISV0LMq2ojw7+cMHxWQjTGIYAkJ6FofU50L/qw4QtIYZgQ39LPgmU0NS1QJcC+pomDbL8SqxIP/KTo6ZYnc2nQ+jSJsASWhzOqKQgcis3G8o8k0EHDEkcFREXIxL6Yt2C0scKafQWMJmB0bq+TTfJSAdBHeJjdY/rciZjiYkejSbacDqFPnTYITYMkF0qOeSAHMCGKgKI+lMUiDUxUbXZXMegGKFkEAYnWDoYL+MQB8da+efGDJ8k70EmKniXG3vnVvFMSo1Jwcgh5hmcAtpmBLINh1cOYNCIFvqit8bY2veNiaLonuPeSdQEldrKlm5FrmBaojV1a2WTqXA8HY2j22VEuV0shRxnL9XXnkF3/jGN8REia2UmH6WL9vA3/iNX4ftgeNxzPFIKEAqekQgs9ierHuYfUkKMBTYym3sACANx3VF9MQjdx/Vri2NDfcl2UJ28W1mOKwdb9y7xoidAkxGAC23IAMAbt2+jbPz23NOMgy9J9riyFxkp3SwZxBouTsubl/we9JnmFebhWSflqBdjVhh4WjZMIYhegK2oIOBItcBm0x62+FwdUA/HHF57zWYD+QIZHLec9i0oWmGOmoEAsFpm8C6znfmWWVlY8Vc6fsVlBGAbbxkmvraCujNPQy21i9QWkHEGFzLQ6mk4xr44Y+fx9kCpRhd9hJMgQ4Gmb7s8Jt/49exXwzrscONIt6SdY3JzpsCxGKrTtbGz7je1oCEaG+HrXXOpkUA6MiY1jXA1BVTzY+GxGunUUih1kBFkgCjQm4ks2UrKXUgTCfb2nSfmDZc4IfijjqPgRzhblkUURqWRaexKo2DGFjaIidNZ8ifLULJJcp1LbYBSxoNnifCj2cfjMTS9nRSUvfTefk02hEU2VX6ACHnglRWKGYYVyADkbDFsWkJToxR5tROULSquZp8tsMwZqRU4xdzY25dJ+s1JUDcDl/j+Lreb0asmurSos4NDIB130VRErlvhhjaVDmdjAlwsUS6RHyMCpurtC8CaNQe1WFUrRW1bTOaqXLrKgl2Ac8w9aPwBa017JcGR1QmH6mW68icufvdbgcXK2e2sQ0FcGN0AsadmqNhK4eFov4qQ4UAlNUeITXB+eOITcfsTiAeqMg7N2bFHP2kLqXy8OYLLAI8yZjrf55/o8+wVHRY1QOWaItNYA8BfTJmVO7Xnxnx6Xls3i7H303t/U7Gp9IxtWYiE/Q0LvH6KTNSkGED6nWIWddcMoSpwLfAPNmqueRrPaoktMdKwtNK31MSRDKJVZGHaTPK4HHfb/S3gc0a2bzr61/6C1zdewPWGgG/A5EdkYGL8wus68B73vFOfOIjH8V1X7dqvtReqEoV2dACcBsrVJOmj68meXOMOSKpNXH5xn2ctz2efuwptDBpdzaQ2xUkUbZn6L3j+vqABM+ZmXOQkM6N97TszlgGngZDQ8NJwziUndL9FxjLxGN3b6PZQJdAOSpnCK63tQd2bYcjDug9ADS0oFzn7GyHQxzB/k8ES2WfMwj+16sD1sOqeQEgO4sc7OiMU3tUoKSmVwEiwMo2q463OZnbQggpB++lawKm3mPXFsTosAK5J4xfMXecKxVVZMDC0O2Ij//Sx3D79qN47rvfwfH1BKxPIG22Q2s7fPD9H8KH3/9eWKzYtwZmYxKVtgS21G8IDM5005u43taAJHtHDhrzU5RWzZfchEZtIKyYD20qTXaVT84QzSpA2NICs5NqVr5WIESOESbHy9XJyFDiQj8xhoikhtNzHtiVEFU7FPmaKeIyVkZk0kgp57hFcMnDH7oMwvT3JTTkZht9SOkt/Yh+fWucI1DiNnPrKQquWjsTKJSzllC0nO2J4w0+lPR2cvwyzq01gZHNvlKbYVKkE+TBgZ4neXYteIjRyfIVmUhnG/0STzlrG1Fq+1Llm8aUd+WzGRidhKOHhFslFgNmxDv7bYA6k5JL5CCNvDSJcjeiAFXxxGVm81lPL4oNZSCkD7EcsBgzHx/1zEkGYFl2PL5ddrqKU7fxpJMcajIVMbBf9liMWqdUs7LZ/beifoFBZ1c6VP+A4RyXVvsGmOwX94fND6+URTXYSxD4R4Ksj56aTnfTJlHcnMwdmaoSAoAH6KkobD1S1jvPiNKno1KTp5VCmTn7fNRn1T3Wc8zql5qPrLSk5itS/WswqxhOaXSzzYbUJJRLLg2mJJkoDRIbXAWdcAH1sbFIBdQUHWHoyIgttSFNTYnYldJs3vDaa2/gy3/+FXgA3Q4wpyPuK/frstuhH4Ff+szn0M5uYawHBjJpvM/EBlTnvs1tLT60dk9SS1kA22ohwNyxtIZ7r7+OfRoulh3Q1cfIgK1QvGwwv4pgnxpbfIsqwMCuGschgF3bo7W9QHUxqpitECrErGcZGVgCODs7Fzsi7dlIYGFTTUcFfJhAsa8rFtsh+sDeF6R1rFCaREA6RgCLY2k7XF2tZDwLiWY1BxQ7b7VHKzgs37MFQqfFENA+ow0gu9Va2wCM7GIdjBoAWoE8/bzKgAuUV5BVfVpYDQiYBz73y5/GR99/wH/16ut445UHwJLT5wWAD73vffif/c//Ns7P9jrbTEYvgBQjX4AwENOuazm/qettDUjMgMWAaqfqidncZ2SvV6Ey6IaG3mWUQaMxdc/FcpgMgSLppegzZ661RI6M9gAgJXjiIggDGY4cyB7SWGBumorqUhGmY9kqX0B0PJxGJkzVCtFFuWIiZqCYA+7bMRf65jDcbOZQueBPNuzo28I35kRDwlQYpIuZru5EfMhvhxVTI0DhCTRM+pmMUok7FS0bGGGoLHUGfnqOWW5qAPOWjHJILMU0fhpGUPZJOpyfJ52KmKg6/ZiwiQJDqKKpyo+rTp59j3wq44UO9b7sasscOCsAwmNjnMS+yZ6oWmfBSJ6FpM54AAQMkAJdApPR4RioDrK0MwQXgRLudXgohThiNpcjAwKmAeR4zAzr2rHcWSi6TkZ5dTDCacltOW3Looo1AWIsTNVTc9xl8Nw2ihkFwE7wcv3b4SozzI1R0wtMQkkOTcDbbksPlNC5DxwOR/SxVTi11jAi0HY0X9WdlRF/sWqY6/chIBJsfV0pkNbaDMQJXkL+o0SriXk0hcDvbC6X2/tjW5alTiV7KdDnlg/R2ZNJOR0w3RP/gMdeJFSNstkM5WSgKYe3BV/9+jfx41dfAxrTA62OIUDi/PwM6+GAdz7zTnziox/FOB5nepvrvRg5uboo3cvWRTnBBn+VHs4C4aRtJnis3/cFeOXFF7GzxMVezr7WO2awj+p9gkyMdSB6cM3pUyCHzlOI2ZBxtz+jVkrDbi1hgVmJWEEBdTQ1Zg137z6K3e4COS7BQz5VIQKDY4/AEfPAy+R8LbbHiMDFxTkO968m6DXfWtDHIBB//pXXkcteTdQ4hlF0oxZZMeWp9V/MAm37QIaY7gwdiWEABlPlmZjBj4JXNldIrfnEij73aon9M5Il1JmT9RpgcLyx+7T7r7/2Kn74kx9hNZ5pBlAcvFsCn/7MJ/DMs4+p4sin5itOgHeBduK6JgYfWsw//3p7A5KlIZttUXzmLPVttlOnUsBsAcUIRqFROcBJ6W8goyIOkh2JOlumjjnnwmDvEYMhfIvcC3FWAyzLnGWXQ5Q7UEY5FR2u3NyubW4OtvduMBtoS7ULfpiaL4CxqFPrOgaWRcerW4LVYDE3Q21S94bFHCNV0RE5AZIrSiUoqHiPv9MM6GMw5WW5LT4UbSzgscUrnBPn+A9aVr5nhYK5GeUqmXTmwnQPSrOAVPYmp6z9nQCGgKEalxk/gOcwqJGQZ9k1RhS6a9Wx6ava1MKdGvOwFJ6osdFiU2v4mXZBVVvo/txgoZLkkUrzJEotMI2DG9YcGBFq9iUx7jQ6ENDYq0RxQUMCvQP9uFUkgfMdSRF3K52H+jigOSy3OmEz0Yn1t0rnDVT6b7l+zIid9y0DVzcIDmwT8K2a5iHjWaAgt4lHGWuzBvdTgD0QcB3g5xKOM615HB1V6sol7areAqrCiPEB99my1P7nPVSvkhKgn4IylO3QvAUSnhR0s3+RUr+QqN0251u/i6wUp6Jng1qbaz1oR0zxq+xLjQVTPEztzq4jBqU5YpaSzkiqRsIMr7/yOr70J19CZEeGKFN3rL3DvAFYMMbARz/6KTz6+BMY44ilWiUAM72rYrQplN6qjpLmM1KpODkdsWw5nar2L9EBDpdXOD87w263oM9nUJqrCTgCYmYbRu/o68qVF7WmT5+X4Gm/30sjUUGd9FAVLG4rbg5kGvDIo49gWRoOhwVugSUHOFyG4Yn1RFMHUEiNxjR9aw3pFHC7bz1lyFM6hjt+8vLLOI6YAa/NMnAjwE7pciDmLlMRjM1cvwlwnFZqwkw9aWTTp9NPLK1aMiQWd1ZUWQnU2cGG61ms8IzG9ZxNviECu6XhG1/9Ci4vX0F6ntwj8MRTT+CjH/8oejJlVfau3r9VpaaZUp/Ufk2N4+l0/IzrbQ1IAlTmFxhpO59oPgcdaUVl1QV1mgZzIDuqKVAExZCFxBl5GCqfa1oArTXEcLj0b7l21YZDAiodcQ+gWsqUiOChPGuyc2Gy/9h2XygRKIVzFNEmMgvNQ86K2gBvC8yBpRbtmB3IAJQwasaKAELlekLqAObR7GraNqtnZAgiSx2fm2FkGKuxL1SfM2UEO0lrTSqUhohpIhljVIRrbAIHpYvMJo1OpX3qeUR9ovKtNJpDJbetRLQWisqSJ7WCBqEQfPWf4cbdDBmf36TZ2MaNQt6iquW05aiZkjDUCbRAkmspR6X7rEikjF4ovccTWA2t7UENAent1hrWNWZ5KCIRPbBrDcssdRc9rXnKMTA6y6oj2aOHjkMiTKeZ8smA6O+KFCfILLtnen8Kfn/athQIL3BpAnflJMplVRCA3DQaZaxK7FuCdDJhgC+O0QOQTiKTZ89EdMxOvRqFmRevT5zRZE6HVmXXJUbOBNOxrVK5yoXP99MeqfU/oayXLydozYTHFhErqavPrCAFyPRaEtuYa29UaXGIcRg5xB7IwU5tCYFDpWyWpeEHP/whXnjxZYIG2YxRTmrZY4Tj9u3b+PgnPyYbIrDnQCr5xePk2YPFFcyayscrUKsoOpR2krKDoMkx+3JQFJm4Olzj/M4tYPHZ0ZorEXNONhYkcThc4XC8D2t9MpcAGzsWlm3muHNxG7u2Qx+rxphHJkSJpJPzx9LvrSP1/myP/dkeD+5dMqhqlWrnL9GWLBr/3AIITxz7QX5iTP3PGCx3tka+5fpwib4esSxNj6SzowTWfQJPIrFmJ4HPAEX6zaevsBSYAPd1tayv2WBFWE4QU/Y0VElYlqE60GLuDtsE5QB4kOWCB5fX+PLXvg5YwI36NVNw90uf/Bgee+QOLjulvTzWoU4QZuep6gUUc53q5zAsbxKQ+M9/yX/MVynaadSOI7Cmets5zxKJEQ/1JQEwHRHHiKdGTuR4ctGxcgsVMFnXld+Xoa/qnlBezptKt2QwCs0yP189AZKRixcRS0+RETy8KQb6IMFupvS6fj8LTDmRjOIICbeG6LuYzuQhp28Q2CmHQ4NTf+p3ZvdALTag8vASKiWNT6FsrvWiy2tUMccBCUUImGi++rHUiZb8VVra6UwIOae2whSF5mD+18uWoTofOmvlTQI6W8AOqE3GvQlARGUkUPlmPruiQvkem5UAAJKAI8uRuOtI8hLPeXln/k7wd+o8G7rC0gJVr079JzDUlmUDAeW4bBOesjEe2SKARxqM5LOyIRiAdOyWPZaF5wnReYAaIIEYLmmChjqJOeWIA4pwzOBt0T7Z1sxcfzSJgF5fIF8qEe4Fo6GmMDdgKsXkH6ZANyKlIsBKvXC9TNARgabIu0bO27IBIq3nOXDJyicH5t8UmZfi/1R7sEWkPKW47MSMJea6h14TvYDVNhaRdHynQRCXudYIDBn13A62YK5OuJvN2U6KjrlPkGO+X2liKn333e8+h8PVFWArzKvHisSI7hjHgfe+70N4+pmnsa4roPQm/XDt6ZxjWQLtjUXyrbrJOXu1BoSTEVoLQ4BsJHB9XLG7uCVdhc09VmzTNLdaA9f37uNwfQnEugFipTZL/5cG7M/PEDWDhXUTM4ChfiQm8EtjwOXNcffRR+BqYpi2wHyZ+iWmknk7I5L9TSrwKzGxbJg7hbcd2pdmiHXFen3N5pEj9Fr5DtWbC/tIQLy5nNN9mZGzAs9lw6qkurRGBfxyJBC0M80di/PEewpbAy2p92tJq9OQPIV7MM1l6YA1nO0u8LWvfAsvvPwafVNpBmG4dX4Hv/SZzzLwlo0LzQuyYCkmQ1hhf1V2AZjM8c+73t6AxJhoTQtkS/iyoNpwQ5E6hZwxKaxaIGN0IF2RP52Nzk+iaCwq4uNZGnDqNNbRcegHHNeD1NA5KyFKM2FCsqbJqrMAAHWWHCu77TkPThq1gbRhGc2qpbq6LGx9Dk7ETKmjeXSfiET2Eqj5ZIgAh/sikm0zekVbsO6+VDaGxXmCZGkPmEDCyeFkXJg0w9Tu1AmeVdMv7ScjDZA52sJSLVotVnebGhlGrz5z7FOMFTFBCMaYYGRu4uQ62JxVQ7oDrRE4wJHWqKkxsiXsNZcnSvIyEAN1dk81R7MAFjg8Zuxb+EOMzIZmJ5jQvRHUBOl0RUcPLWOIFcrUYV7UMUU4mu+nONvAPiR97exD0pzdEdFg1hShb1VXY10njb5YmxRyvZeBuLYZKXqHqQFfjZHWvwbGq0rpREdV69Ay2EkW/Bs5QK6kz2Dg9LEzB5Adk+Go6h4Zrh5DAlmn0VTTFTPDfr/jmzidH3V1OoCtqO8T5nSmRjwBY7OrzEHbAYmgi3xOtv4nEBZ7kSYQE/P9SqhaALPHSXn5BBWc7irPNmDeA3IgYmUPneo5kokMQ4RmR+AGBXwswUZ4OaPo5194AV/96pdlyTctAhKw1tBzoO12+I2//tfQrGDnplUaYBMujoSYUdmj0Tvq8DwihCZwRZA1563u3agtM2cb8dcuL3HrkUcoYhXwlSppOnacgMT1cIVxPGKJguy0MMPIFNQps2fn55yLoNOd9rLaJMw5x9xX1JkF3vuuZwDp56IYHei+imF2IL2JDaZVpPaCIvpN+Asc1451DGnFEsfDtU56L/0aWasxgOMaJ+OkcT9h73w6cAYBAzHXkfnCQCYNGaasWGx7FQakqk2lqo4+ZNc57xF97kt7yI8Y+mHgz/74zyc7FpkYFhgA3vuBj+CJp57FGEAdD+DO0vyBwBoDA6k/2ntuQGOHV7WwxJu53tYpm1MEVlQxNzHFNsOIT8Y0kBseNavFRyPsqY1sOrwtpIbXirU0LA52hzXM1IFVzw5f2DshiiIMoUybETgMs5yY4rkynpzkqoipxRlWJaeJOnW3qLZqsR5yxi7GxBam8YvyzDCJpxg9UkawRYxRJwKrKU+cnCFTn5NqnESKEtOzLIoaEtgU1942x6L+KyWaK3lpRS6MYtU2pwyKFT3O19Dfs+FXjq1LbNHkrTW1NRZ7UmOe1E9QjxBiYIbOVpQwUdqNOZ4TzZ+wSBB9G6zAae40Bsrllg6p9z4jBc5pRcil94Fyq3Ss1ayvDt+C5nL0BJYNgK7rwPHAyordrmGNFeFAeHVCID1fjAJgPO9H9xcnI89GUbWAcgNSCZQIWRhVQAYoto0O3bYKkoj5tDWd9e+KtOfXEhoiKp2paDG5d6rhWEWak1icDlnrVOtqXam7KiDCz9/a2Kde/1C0pfmA1hOfcUu9ZEV3VtUQOcHc1l8FZQw4zhncSYapFZsVYXqP2hs/PS5lG6CIHiXuhRr2KcKfXW81T2w4yNfulgXf+ea38OD+G3BjjyMzY8NEsPtmjMQHPvABvPMd70LE9YxqKzU0x6OuKlnXHuO4C8TqXonfqhUBJoChSaMlPh4OeOPefbz/bK+ApNK7WnozsSWdVgbGYYWNFWbB5iMnjh8au2yG89vn27zN/bbpn4Z6+lilK0DQbTnwyO0LgvZas7opZXoZqDQeTsk9zDTWGB1VEh+Z2Cn1zNIgOpoRiQf37+MdzzwjzY2E4hKhuyoNofW69eZIVGVM6Utq/4d+XAS/GVsDVEBnEuoX7LAs605Rbs+uyhylr5xBDVkfWsOl7fGXz/0IP/rhC8hFCdpMIB37izP88q99etpYBMEhB6eqxQQ4lCbiXMVMKaE9HLD9rOttDUgACkDLeFTzMICOifkzUIxagkRU1K1W25DTQfLMARkRa22rLIAcUDpFnVk9TLhg+9qxW3Y8O0EGu4wrS3wDrc5VMBpo9wUh7QfTJMVy8N5HclMmMNXSZtioQ2wUcjluvUAG3fiagE4VzdkgqDwIqXVFmXIwiVNAUIa5hFYx0xi8WZ+G1PR7aYmqDxlD2hrabNKmrs2R2nyOLRpXj5jTQ7dOyxDr+VL9HKCUBLuTUu1eKSbmz3loliw7eCR9ORiXgS8gW46iUiBymK6crlPUnNORYK6PcjSVa5/dc73+XX83NfLjx7Gk0mcqammN4rNwzPM7Etjv95wbtUfvObiuYsCd2o6S6pIlkahUaUtTF8ta87J4Zf7UtdVQ57XwZ6z9OsFYMxKG5nrEeCg6rqC2orQ42Y9mlQqi/Wa7dpVaa73G/EyfBrr0JAaeGWJg6Ssy0XY7wGiea+9TdD6UFtiYzpSIe2nVCoDGc572W2v4FKHYNrentqC2ml642Z+5TjGZM0wgGtpjbLznrcD+pud6qIKlRGpjTGAzSiAIYFkWXD24xpf+5M8ooDdS8WYMwHxhE0T3BZ//lV9Gs1RfGjk1p60KpYa3s7keGgxs6VN1wAVmIFX3bIC6KmNG30MN7W7fvo1lYYOxev4s24FaO1y919fX2uMbSOLH5wxM3B137tzBSHayLqFw2aEKdlzp8HoULuXEo48+gmzOYggzsdAJayxxNmyFDyyTZzo+caLhyAFbdgAODE5kOXsfeOP1V2GWWEeH2xkBgjUd15AsJgBQZdyl6nAhtWpfYE4dW6W6iOeleztZoxSxZ6F3VB8b8wqa6Wv63KuYfU1S7zHWwJf//GsY1wDakUwKgNGBd73nGbzz3e9EHzpji7M9wf1eDUYDdUYY9/4MAHJ6GryZ620NSAwuerOQt2hNS6TZbOOLTER0tGURrcpSSTeV6ArtnfYe4amJVIbP8ikQ9e2ybdGv82j0DcYLHgyWdvL96z5J/VE4lyoBlZCPeF5OE6QxzTDP0UCqbJcbrNJLs2KlnIciFtP4eEuVoWnMpNVI0FBaNniqY19uCLfy2BwPARMkEH1jXHScOGCqyV8BNNb2m0nYyZvkGlXJc7Ep5RRnefAJ9fuQgdw2b6BOR+Z8DQOySmCnwyzjyLmoqiTeJx11PQ/99KQF5mtONS0mz1QMXCBnaqMquUpdbmIboEjHm89S6rlQ52MpCo4234P/bS9rzRDjqHCLbNJutz8RBdf6T6YpQ2WIg11BkQVk5uLcnKnAYytECUzwWaNYhqfG//RyU1+Q3Lo/zDObtL74ntJ2yHlVjxZrcpqK7Kb7SM4l75l7cqxHjKPSpK1p/26ny4bGLrPi7i31wUKVMuyuT6nP2762+a+aKj6Jm6q2Kt1Xr6sSYyTH+CRdVKhzHmhmTL9a0uEUGDtd4RuAO9Vv6B4ABTvcl4s1/MmX/j1efelV7JcFfRxmRO8G7HxBjMSHPvhRvP/DH8SxU5fBTs4Cb2AAFtjaBJR2bFYL1h1MxtO3vYFUNVfWFkVF+GM9whN49umnCd7zZOy1h6qhlo6Lw+uXV2T9TtYnEGg2VyOWnePOo3fY1AwECGzC1edr6r+q7FuUPh8ZuHXrFrztuJ/6gO/2gDMNxnM+mSq3JFscvWPZ7wmiG+DdMHSopMGAEbhoO6wx0JY9XnzpVZjv4N51ivA2n8Kqcx9Z23wXq7f4dai6zGAnepvE0paZ3rMC/mbTDLtaEeBk3xlcZe4OnOg+mm96lNdffR3Pfe85rGOFN8oQepC9/sjHPo67jzxKgDYF/OoCW4BQTFAGdTrzCA7psRwG5b9+7vW2BiSwSptsEQ+1Y2Vo1WPAMc8xYQ+DEwcXoTJJGbGs5mAAqgdgYgMHyiNLIMLIJQ2Rjp0MMzdszsoT1GKcGx5ADEYyquoA+Ds9k6xJQnQc73UknUqYgIOQrplhRKcDUqQ7Bl13g6uwyDaaDdsmSFN+2JqYBbVlF/CpKJX0nRazNQSonmbzKszxKQEkkhVO1fkyYjO9FIRVp9oS6MUEJ5Bz4vT6CZhQtZMAB6eZG63SXGwkFRNAPuT8dQ1Ry9PohRwmF8SJY9HYT6yiCHiT/1f4djKmWcgYmaajB7QANVBVOWGKZkrg6DA14NM6TqCODtjv2sz/H64P6OuKs/3ZdNwKx6HgkCxZazj2Aex26hngaGiASktTAunJ8giwFPh8qNcNZwMleMbJmgYYHWc9W/WsINI6McIgowWxfDiZR1On1dofJzqfZkCdlDrnQR+8WMPm08UslLA2qzvkBirmHM8Z2/6RKOB08s0TB82uww8DEujep7g6sekjQJA/e0rkXCXCKjmZj1nNdpIuLfBAPVvZpJhzc/ngAb76F18llh4JJIEXxfXUfbk3fOLjH8V+t0cfHW6OVopd3V8NUR1gebpnPAuI6Im1RjK2MaxKqS3JyjG5vLoCADxy91EcrnlQXpP9GdhSxdXwLNLw0uv3scJU5Vh7m30uDAymvDn2+z3twiwhVOiRJ72R9H22ZOBDRgbOLy6w35/hsF6RIZGtdiOr1gePEykV3BgDi6BU2XWAaQ92Ic7JPjVb8JPnX6FeLQ2jd90XnbfDtgAHhmI1Kp21gUGNo/t2xEdLPV8lDrfIooLG2gUuP2XzZ0wmh83fnMDIveGFHz+P1179CZbliJErIB3Y7TuP4L3vex/6GLPlQ51RVvtpjTH3ZW0Csm429wZO7u/nXW9rQJIRcIEG2uU6oEglW8Y0jIXKfxUpiixEHdxkYUzRKAdW7bHpJiSwNGk+0uc5NYzUBnb7Mzb+cqOgL8Y0eKY8Wk6DC8CkVhfKrgCgmY6KdpKjId2Lu0v/tzn46YCmYHfTZswTSPklZvrh5Hd5G9RfbKIoLjR3nolC42cTiJTuhjXmZALcq9lPbv20QDYJwZ4uw0I5WeOR3xhK3WwOZh5bjpzU9FTKV4UL7S7ZCLaxVY1CRSxiLmQuy3meOtUyXLPEtJy/AIK1hjYPrt+Eq6bPDYGUesdZfCtGq/yj1VhXNBMVGVWE4/Mz3RcJUXWLJdRRxGuaZzPDbpFq3myeSzQdmiwZl4HL4ZgaKMmhCGSWwNlkRFypqbqmKHQClhIzVsqqUn6Y0TRwktKBUl+ubpbFetT7maloISerMddtgGJxmESVqsSq6CKp6+GfOnKhxqwAWolSc5t5L25yY0MyT3oVTaCldeQuWyD+pIBysYyT1cmZjrAaVMPUaZnYvLJVgaCWy6rDpthAgehaW1kf6ZuWKgG0tsO3v/NN/PgHP6EwPleY52yxv+z26OF4+qln8NGPfVTCX1eqpeaJc3QauBY48vm1xk7zgxHUqbmrE7C6g2IbBzOHY8Hl/QeI0XGmdGoCWzmqtDc19xg81+n1+/cYJDlZkaw0g9xnRGBZGvb7Ze7xus9KP7OZ25jbKOZmZarImuPWrdu4eu0S1a26mMmQnVlm4Obw/X5DmwjtSd6bNa6/6/UI84b9bsHV4Yh1FEtYnW4L0W17q8pi0SBhbu0/buDI0r1ICxYr5gGRJwUac99azHE6Zbf4rcEgDWBjULFKS9thXQe+8tVv4vp4RYlAhiqbAu997zvxnne9U+W9Lg1YYGl7rfkTNiuqSCDQY6D5gmpnzyZ+1aj0Z19va0BSJ5baPG13i57IFjSKUDX5Di5kA1sUL/tqbz0YPTrPs6hTbknLB0urUAKlAfOmahD2QVl25Si1uLOBx34PYDajIrXt7qLqauGxM2FRxq4oleeBDGgPw9rCbZ2hvOTJZkwAVaKqTRtKKaUWeuke5j4WtcdKnBLxYkYdlZOPKlkVJTc9pqcYI/bRqNNCGS3q7IWJjmnArLneJ2f0eXpV9MfzYGIzKmazr4wbdNQ8ZESSHQ1BR12xjT74RKzqcw7LuNVn8qRlNuk67SZq7qiUb8rxz9ORg04IVUGhKKzSEU2Ax6txkRWzsIGAcsDVtr+Ex/MZZFTWtRNgVDt0sQ8U4On9q4zQGIUNAcqthFTgwiGHuYW9ZNzLoVajpYfnx4x7Zjp4q/JwOX/trGJY+IEFezYdREWC0+mmhJuTaaj1ZhNMMnAYCDGBI4AYRL8UBfN56I6kCTJDHQV/qoMCsIlmzSbrwH16Yg5te0aAnYZPAZXuHm62HUUgkFKIle8LmO0wnafSnRlV15J/hZkoZ1ZjBiuBdYNloK+Br3/zm7juKxYfmtKGANeJeUM/JD7y0Y/j7mOP4djlzAxMjU12hpVCVucvFRip+3HZltzsCJkC+6mx4N2VjbEEjpdX2Fliaeq3JFBiBWoFLKuNe0TieDhO8I2sirQtAMhMPHL7Nna+oNep66i9hDnmFjl7vfLtYrINixueeOpJvPDKCwwGYDBTt+w5tQlURYs1iVN3cE+4LdI9Jdcf2I175w3egH68xuHqARZ1yoVV8COgPXVlAqQnMgGrfWgFLAhGSn8CrTEAG1NZTKZWTfXhiupbAjJhlX4/rf6xtuCVF17BN7/7XTZ4hFj4pO7kM5/+Jdy+dYFD7xsYT0NT64SQLqu0cgml2k+ea87Cm6RI3pzS5D/Sq/JsANEZiYJgWZzKCtm1lMI9X3wKk1rbYabHTyI0QIbKgajyOABIR/REhs2cGPPcyTbsY8U8slyLjyLY7fTJyQaMgb6ubIedKSqSXSSrcRhyoMk58yC2rZtqLSreBz/HbQdqaE5Ee57IxhMtGSlDincu6NEVSQj0MGKqZkCmvhVyDKpa8Mb0TvO9kHsBH2wsTIpi95MqCLgM84LW9liW/Uxpnf7ZWAVumoEqyxXgDNGhFa0kVKpoLNULigcx1LfE+Fwsz44Zy81yRuPYF0ULGYSZ9sHmvPz0e4okuCmL+SBd7sYIe27+DGSVFmdOlo5Gh4xTGubGLiCyUTOOtt8jrQFNTjNjM7p6TZ2GbMlTpve7RekPGsLSQFTzs5mWgWC6WKtqSV2nhM7I2R1tURCAAbOagw1sYK4DRsLRBzxpVEuUSpcsUa/Vd2w6ZZ5nw546rW058b527euYfTbq+PMG9lQ57U2TEv+iYR7DUOs7IOkQGLjAWB1W4vZiSmgvDLPFQK2TxrXNE75n6HuSbsqtBDU7DCwprrXNZ5TDV1qmnj8hGzGq90jtD3bTfO3VV/D97/0lLNUkzgKZatC4sCPwxe3H8Nlf/jx6bgWZ1X+lHHhqnxcDZMAmAocemf+adgeZ0ovVidgPpxLqZOnRj3js7m0sO1bolT5lAzKBKrWmvIFt4xd3LIEJbEz3Y2Ag8ujdx2FoiMEzrwYooB3JdDfNoU1HXXs6gv2djusR73nPu5Ax2FND85bm4Am9Sl2bdDAjYcnSX+QJsAw63pC2C2Idsq+4euMedvoa2ETYm7BZQSdYcmvZZvDmZbszUOXnM3jJqnJUw7FabxDQE2ucShWaM1XLlgcswS3WbSRT9V/5ytdw+fo9SRZ4HEGMxFNPP4uPf+wT2r+QLWUPGVNxQ4Jg53hcsa6DFYJweAXYdpKCXf5HAEhgYNWCGdvUWirwJ5NAB5Hss+BAnUeeMigFHAJA7yswOpZM7NyxE0qN07ydmjdV+iBWpSXMkX0gVp7TYqLLqwkaecqNujM5n7Ys0hnQ6Ub0h9nBSGAwgvDUn3Ik+f+l7s9ibcuyLCFwzLX2Offe11rf9527mbmbeRfp4ZEOGU46lRmJUkmjkqIqqoQAkRJSfiA+kJAAiRQSEuIDJT98AhJUqUpCWUUJArKCDDwaD+8ivDO3vnFrn/Wvv/eevdea9THGnGtfiwx3DylLwk6Eudl799xz9l57rTnHHHPMOYmwp2mj+xioHmD1UbGqTcyJvkVOtGhdDJ3TYbsODMKAqiwVI9qNGTkF0uaA/SGKUlVQL4yoUAknyYoYRRqiIi1yu25Z5WCKcBkQBf0aL1qn0Bo4xqBEnl/F5+FALJrecY1g1C1U6WTgHVUAsBowrZrCxfKP16pjbVcjNxebJMZnzTiYjVkUAaRMTBQyqBmVQNwLQF84rygqSmxVBmoGtE7R87z0FAQGMxKGKO631Ipo9GVE26uyURsMm/xTAd+/Vu+7x0YdEU5G7hHtglFdUXSnI5mRGcLJCqhFkytIC2Qgy2OgVoTyRjZNKyiohZOw+cUFZhM2ZULR2eAuLIrioV0QaZpILfkQLetcRKOyAF9R/XOCtVsxFgGWhlM1DcWzFYuRxxtwMmSxh2MgpUFsXvMUugZA+fPm2lZgiB+qjjN49sc/xaWPPkC1Jb8zOrPWusGyOJ588rO49dYb4W1GCWbDAnpGwNZXoGmVKkpghBN7G0CWIfMxKp0icX5zCOB07OYdbr39VrIB6ASw8dxXn8fzwGKE1tl5tU4V27191GmSSFKpZFScPX0OU5kwmaEt6uOSWozolmxYmqP3oQtkiqTBWsPNZ87ioE4onTu5TAU+OWwCYjp2ibScmqhtN1uUQr2Ugd1wp80GHcbJwF64c5vj6Oo16gBBncu0oRxgqvo7RoYSn9O+E3wJrItR4f4q6vmif/IcETTxWfgKPJcMrcKvhI0swQg5u0AfXTvED//0R2ja/67ADmXC55/6Ek6dOaUAT0kxMz4ndCwgO1umwXx3zSlDN/bTaaCw3Au8/WqA5FOdsnEscnZqZoNxsPq6wqXRefTeBDBEiUcfDQeAljQXxLqQrzf1Aajp3Ia343daKWjzTGZBG9+hCgun2Il+l/XojvXwuviwkmmEsorQIvdHuj5EniXLx4pFH4+VviRazgs1RwdV2iMDeonANG0No2D1JLHCNFUyHixXNoBaFra/AeDqvxA5TQzWBIOdiM/PyFVC4TR8EpkWG91GoajeW1DmEmZpuaIHxBg62AeDYTwIrXF9S1H7ZpjExBEhjmoerrkqKlAwpnKangk0dLEjU2dmOUIg9ADpvE1RS5aIN4GqqucsAEGrQmCaPS/UP0SprVordjNFidFFl82VpAFwKuLhg1FwReRDDOqr50DnDNNkbC1GPPMSHSX1CxZ7Xc74kw3SIrqmVevj98qIeII5cwd7wxSKODl/SesJMEprS6YFomLIO2TIR3QYQJyt3AWUOj/DtLaj90iwNgKBgWIQQNtSJJ2mMxhPPVc6zpJnAiC7Fiki/Qo43WRFjYP7c5y1VSM0rU2ut+kede1dDAr35oSjw0M8+8yziCoX136nvKPCvGIqe/jKV76IYh011tUCnIaAWOnQcMp5HUrduXPKcdiWsBVGFqqE3s1rphfDdnZ3zK3j4Ny5tLkw6at0zurEHhgbpzV+96P30HZXsN0apr0Npu0+4I6joyNsrKPPDRUFu90hXn31Zbzx9pu4dOUSvvilL+Gm225BX8g0MhPk6roq564In0HCgu3BHjbbfRwfz8Di2OxPMOwwTYZlRxacjIizN9Seuv0WQ50MtnRMmy0MhuvXaS96qbBtwXJpweH16yoK8LSV7iNwWmIeUg1mUGkSGDsAFza1ZMqIC9/ULC7LmeOsQz+rqn6ySOErDew6jOpH4Z0+bioT3nrtDVz98BJQZjgWWmYz7O+fwaOf+RyOdwsDzwAscV7iPBs/t5SJtq1JY2gtK20iuFlXev6i16cakITzn1RT7wC7V0bJLDyjE0bjNGJNSL2UyrSMSemttu0pOtJimvc00pKVoGtzxGwXzkWrI5LU70a02DWunr1JakYJo007tIFLzq9pHtqYEVVECqBokyx9xjRNcoq8FgZ0zNO6okLA0FYdSKNrZ1tG58eIfEyOwxSZWVmp8Dtn/SCMaVvk8ATkjLX9U+U0zGgER2mKNCgebIPyq+6wWsbgww5YnaSDgMToEUWGSDQiR2Rk290BNXLiuklo2hfadIGScFRW1ZxITp8AYKwDoPvurrJCfbePqEyqHzI/KKvnyqZs8cySQhC7VcLBQ9eSFUrjmUP7q7lSdGbYbjaxCtjNDWUTLcC5347nRXQsYtHpnJO5QTogCgB1jvR+72NPInRAcekGLE7FCHPaEmtaRPu8Ln6U2jfZMiJw4fUQJutGqLfxcb36IOQY9xaRdZAFnk7RIXAQZasAzKZ02AiwE8CqDGYt1wbjcy33ss4/wuiGcDwCmGCZBB890oxcLMreV2ySvq/n749XMnMrNrL3eMogskPHtJ3w7PPP4r0P3qXzEeprmrBdJk4z/+Lnvoi7br8Ny+44RccAwc0Qc+fR0a0OkBxi9hiYFs8kwfaqx0dWQOXoBO7Zy9cOceutt6I7g4xYUjOyF6+//hre+PlrOLx0GbvlGB9+9CH6fBXTdsLZG87go48vYbc7xlRYRYhOrc4P/vRH+OGPnkHrHWULbPf38bnp8zh75gybooEgloUyjYMtrcDAhpbujWMfpg3muWNv3mE+mlEllA6hKzt+k/VuS8dU10fYMFWg2sR9OM84vTmPM+fP4q2PL+LSpUuwJiaqILVbLnBYFLzAQ2cQclQMxldrFU8lVDg8qmJVqgFFDt8iuHH1dZEtD7uNIXQ1N2B2fP9Pf4jd0jFte2poDI4nP/8Ybr3jLHwRcwOnX3WMBHytDJJXNi/sTPee4ndKFNQZ+Vd4faoBiclZhaUzHbowMctCJBplZJAzMudgJFhHmfhe75p+q82RDEIHUCvMgmIWCg1DMwE+A7tlxtkzZ4jEO8c202ixZsOjzrwYYpcVDF+wzq16oFBRg/SzJ5szlRDymrrvpXixJ+XHe6i5IYNJCdlnaBfSs2fedYinotSNn22iyfnqcYrAQzrWHiPNVJDAAqWmMabtUhRT5VRj4TMC97xH+kdGhLyPmlFXMVoLioBXg+N0GKPpHPOaEl0FRkin1geokB+GAd2EQFMwrTkW3vNezXmP0ROjCMj1zmmrdBwCOzqsTkTC/DPYz6RueFEEw2o0VCbeo4zNbjfDrbJVeexTWGpnttsttRpmmOcZU2VzpuLhESR+lq9PJ+oSNAoTDpclQxli5NVzgb4/ViKMpvVxD4Cem6J5E7Bn47YynvnYhVy/QdyomSCS7UkxsZiNVLrYOE/EIXqQAjIEYvoLWf9gOAOViF/lx5UqUXSN30ojW+NqQ6CtbwghrJdVSqh3nQ05Hu0dlwAxSmvdojIs5svYat84jq4f4gff+0F2ioZ3WK3AslDXVSu204THH38492cpISoNOB90PvJ7Q/fmAiahLTKxnbCoyor1d6XHg5EkWHYwReBecPXaEW67YyPNgtKxZph3Dd/9k+/j5ed+At/tcOW99zBvCzCxC/Esrdrh9WtkejcTdUuF11LrhL29DXpvuHblEr7/x3+MN15+GXffew/uue9e3HjLTdg/dQqbzQRfomX8YHQdHMJ6cGqLq9ePuHeMaSLTqAX3oQWqZUKxgr29PRwdHsLnGdYarDtOnzmFq5urqG6YDLjp3BlcPHsG146OOAeqzaos8nGOBJoZaLn2MXQuCVZKVYWck5kPVrwUU0l3gVd5Kh9Aglk4OpeOwUaGiJhVjvz+Dy68jzffeJ09iNBzLMi0N+GBB+9DqQ5vAYBsFaQFayg9XPytmJKpjAiGqX+jjQ0090ten2pAsiyOvq3qMQLk0TINR2oN5gvqdi8FWSFGitbsVdF1g8Xk9KyXh3xGjwoIvXjoSM1GWS8ALH2hXkUXEWyGIdAlUJooYiuwqcIkOkP31WdRtNc8dBUCXIl2ccIphLaDekhT58ahiwgtQzh6AFkdmYG+nHNEupMZG8wFMJERjxLdMERxFWwz3VWpMqUz8jbSNl3VH2UKAz8MMhs0qWy7MeUQoigoMggjTTs9NDm9MzUhRl+HlPlkxK1B0WE8W/RkKPieomvm4e29s3pLTACvMW6WLMGoNBEg8p5gJXLlsfa9xV4hyLOMeBrgE8wp6DOLtA/SexhiU4FCZf3cssh/nIloZe8OtKUjeKXh7IfQDC4nXU5+SBjlcPKAJ3tUIzXlI2UDqBXGei/Gt5ai8lBXhtRPNG/qBghagXnuDB0ICEfNFKIExATsirs0UibmY9xFAHoyp5y7kWDAo/JBdH48ZuPBiF4QQtEAViBqVT2W2MaBUTrPD4q+KoMOEUu0VtJDfUZWZ5lNysZzjYTYphpee+01vP3mO+z6DKapm8/o6NhuNmjNcdcD9+Ku++7HLFaXz0DdgY2VJq1L01Kkv5HzigBKWzyvYZzDcc/agAQjpah0la+2NBwfH2G7Zdv4WitqKbh89Tr+7E9/iO9977t46okHcLCd8P2P3kEzYHe8cKCcN7z3zluw6MniHG3vxjRWrRy+5OjYO9hHWxrefuttvPnWW/jxj36EG266EbffdTvuf+A+PHDXXdjfbLEsTdN7Ccw22wlnTu3hw6WhAWhmKFPFdruH3Txj7mxg171g1x17VmDTBJsMN91yCwyO06fO4NTBaVy7vsPh7gh7pw7gpeKW227F0ht2rQ32qUEpL5PdUJAz0L90HVHGr462bqi+Ou+9M9XledhST7gOIOLsmICs20gTba3CvOCVV17HxcuX18QWmgN33XYbHnjgAfTeqZcR0xMCZ1t9rgEJNDLWzqrD2M2mYacVv8rr0w1I0BFTBx3hkNmhshRgWzSUrNQRnYbTsSDb1UshIlZHGrjuXPAuY0KtbId7QTYaS6q243hesL/ZIHLSYVdKUUWBh4OPp2qodULrBfBF3QwjKsHJKpTYCZkTD3ARURVYeeBA8eiGqgZlGHQrfbEPQ28e4Wfu6XDZJifM/c58rJfRnySrK4LhKEplISaNchO2pZEMKBOZlGAT3FNMZSAlO3oAWEbvKaLziNBX2hn+ICM/K4X5dBvlmChQ1VOwR3xfMF0EmJagIsoyzbgGmeHXmodUIkrxAGRfhlDUW0QSeS8QYCtyFEAM/ire0OZjGHo+e8lPE1izDFcxdu/wpUmcGs3wFoQ+gs3fHJtNXZUVskRx5A4iCuQeiomkYeDC90L7Pv5SjyDXIwCzaV+luHUFVk3DGqPUNBiZ8R5eU4CRxTmdlJuvp/6K8KTn7JPJDLVTS1MQQF/nnLwkbxVOhkjHpwp0S+Kc1yYiDAuaWDeAzOaKRegn7+9E3CeAByBLTV0atUiBRbPAYJq0PfmsPRqfnRSPRhnlj3/8DHZHDaUuzN8L8JpRP+J9gyc+90WcOnsK826mvo4XRdYm9o8oKAYEfcX28Y4i/c0zHNUcBJYBFrMiTPYqRx2YYXE6281mD8u84NJHF/GzZ57BT595Fh98+AFaW/DmWz/H0fEhLvUddSjO507kp/R2rYz02VcADmNn5tmlEdxgqhu01jC3hqOjHd55+wLefutt/PTPfoLbbroR99x/Lx56+CHcdNNNDIS8Y9o4bjh3Gm/2RVusEWgXG1U9nOLJ51AMF69cxrS3xVNfeBqbzQTMahV/7Srq4VU0AM8++wKWo2PceMN5vPH2u7j77jsFcnvgB0CCcpYRRxfucAd8XpME14t620RFVgdnXbkFux5nV6xdLez7JBt0Ahjr3PUOLHPHSy+8gbnTdjMkYMDw0GcexPkbz0nzcVI7EtfZFjL3wbYWfU+XPqXrukqZmE4M+/ArvD7VgCT6CYRVKHHQjEg6aPSIzCLX2boG7Qnhz63B2ij3DNHQyQgnoskisaSMPAUl7JTqVXmMSJeMayOlVfPB1ImC2h7UnAOozBV3ReUGZMkfGoclmfQg/FBGerUWLMui+TtiAZXb7eYZVRvIHEV31CzLMrXGdhLg01QkyAXMmxhHj1L0Ia6EqOO+JPLnJ0eTMKWtZAi6ypd5UKJ5UaQSkFUFCUQQeccABUwKmBm8iqUIB9gZx/YQb7ka9cjhWmUEwv4PdC+tNUzTBJOAOSIRxwyrirCdn1u04ZYFCRrCGYcOBF45vE/5YjZymmQ42CXTweqrqGoxM5RGcIKmUAolv8Ph2G5ZOg4H+gLMS8d2n5OtvXO9CQy5/tU40Mu7oxfpVAIEawNKTaPvE10vg5cdMONl5AebelSncRFIyuZTirrXZaquiBxuuS4xVyZYBRM7ZVB6Lc6dO/pC49paY7Qm8V8plaMZDAlIw/ivYUJGcqQIBpMRP4vSZ48uskggb+bwqNpy7c+4dxOQCXMd8UlMw/Vo/KbnFroeOf22YhRMQUVMdtWvgLvGMJWC996+gDde/znMGho6QkQNANNmg9Ybbjx/F+67/0HMy6Kz6pnOyjb+2g1wH4kM473GM8hqiq6yaqx6WQQjkundEbzAmVa+vsw4PDrCiy++jFdffh7P/+xZXLl4GTm3qAA/f+sjatOmA6A5zNmziVWMDJIICajGqXUCULBXNyjG1E83BgLFCra1ApVnuoMC13fe+wBvXvgQf/aj53D7LTfhvgfuxa233Yobzt2AzeQoZYelF/S+Qa2F82fAqsRqBVM1lNLQfYcPP/wQ+5stjo6PsH/qBuyODnHt+nXsnzoANobd8Q5nz5xG39vHxUuX8ft/+Ed45LFHcPsdd+DGm27EqYM9salxBjBYfQFFav4UKpqRbVbKvFgOpKC/gILNBBzjfFtlUIb0IzbYkjrhjTdex89fewtmrIBqnUD/9OkDPPzQQ9pXYa9lPxX4MN3Mady8RgnwDdioJUFXDyQgKuYcywnk/he/Pt2AJISmYdw6hNwKogyK5apiRmR8qx5k96C0eUyjlLSr1InUOt9PoQ4demgJIKCg4A191qA3p7AnadG1gZV5tKDETFFXFCcEU9GhCBRIdOuOYiEMpSEsxRXhRBoF+b2p4td69RVaHT1XhMtkUHunKK2cAF9BcX9iV8lYQ3qRoH0VsuXbIgqOCqfsptu7egEEjekwzRkKUNIVpbEPURWggByxjwjC5WTddU1QztWQVQ3qoOu9A8VQugMqt+3ekA2MlIoLQ5Dj4cF16WLAMm0W6xnlcQgRZCjsM6xOwOpQ8URQpggxmmJ7I/AjSyYFfmup+2S0mmhXzlAgUSp6fq0AdnHUoQQYjke/X5DSpgQX3j1ZizB8VpgiI6BQlKb3oVhe1zqlCMT7ANNgLo5AsQTOAYrs5BUCKrFvswBsph19MHSI9Bcwecg6ZCzD73dVYSGatUnTYgUxU2U8N0tWwcoGCmwVYYbwcdybwQFV8QToKLCcJD0qerDKpXsGO7311dor2tS5cIGal195FZcuXUIgcMNIP5ttsOwWfOHLT+KWW87j6PgQI5E8SutdvzMesjZv7KWitdN1ULM27AQQ4mvPag3OL6kqLHBcvnIZzz7zAt5/921ceOcttN11ikqTTQOsVwqZG2DFsTVg13bY9XDLQPeiMy9A28m8fuHpJ3Hq9Bm8/fbbePvNd3F8eES21Li2dTNhKpsExL0zlfz2Wxfw9jvvYH9/D+dvuIETePcWODYq5dfojWqjb44ZrDXsDo/Qdguu73a48M47KAA+ePtdLNnaYUGthqlW2GZCqecwzzOeff55PPPcz3D//ffha7/2a9hsNlrDeDohMtXTcfoCj35CUe3GjY8xzDACb7ERrnPePZ9RMQJs7+xYHnZkUzZ49plnce3wGmy7AEXl363jgYcewoP338uZZA64b7RFQ7hqMl+e1+NRJNFXbHrs8B6VTpb+5pe9PtWABGZjumujo+LU6i4hEZ1gX9hgxkF1cJRAkcbUCHsh1kid58tpBM2YiEBvsKlwCmeTA3Dg1N4B0BeYbwHIWRbWaLuoVQQ1miWA0auAjEHrfNBDNBSOYDiEdWUBI8qehxipbiZIKWJ7XAaHgIuHO7Qigbsl9laX105abqoq7xsLQi0hDW0Vi8JnodJkbXxTZ9VBYVTAORhtPaMmWo7H9FfvrtSqHKCz7BOmeS/5u8b7iC93iQBdWkmzzHu6t5xGGkaardrrylFmM3V+DpBaiFILh/LxeI3mWwal5iQUJdcuI2Ms914ZfwYsEwGkQvqlB2ulct6i3DJAaOKjBJlb3lgFJSMarrs4qfLoF+MG1M1GQEf7flkGK+bx5Hld3QwTxPgZ91URSI2HHM8nZg3F3gqAG6AdctAUFDJVaSXSPSM/zgFzJcudWwdbTut7soOOF3C8e1S6qEKrFJiNDZiX6gQ71gsrdMwARH32GlwpaWsBUSRotCHQtni+pQjAjGcFMEUUgk74AC5BoytGEEvCvW09hL8hfB+6HD3NFEabOw6vHeKnf/aTLJ0s6gMUZd0VBafOnseXn3oaviyI7EkAltx8Phx+gExi+eiTYiOlpL0WCCXTjEbQzZtqcsTApUsf49lnnsHzzz+H9z+6iLk1RucT2TqaHYLk0wfncObcOVy9dgWt7+TMOvY27KS99LbSSlXUDddhqhWPPf4o7rjzThzPn8P7713Ez37yLF742ctwNJW9ssrMO1Nf01SBTYVvWbW3WxouXCA7s9lUcCAdnefeqVO4dniIKoY52ij4vKS9fvedd/DOm2/g2sdXlO4wnDp/CgcH+9jbbIHu2E4FpW5w8fIVXLt2DY898jD2NtNgQqzIn1ADBWdKMQePIgKGETimTs7bCCTA1FkLnYcDTUCRARLvoaqYoBTD9YuHeO6nzwLlGFY6HAuABpsMT37uCWyK4WjuYKUa7RhWe5huVenP2PcRDBemPRm2aRxIRLpxyb/k9ekGJM0BOWQ4RU9WIlryzHuynJEHrc2sdillDDTrzhRKaywTO9Egqjvz7UbfOtWKpSuisYg6O7ZTYaO0jIR40CGGxkTXe6TxnZueRAhpihBRLk3RYJYfStfiSGo0RJPel5Vgl+kfJaHzWiLHZ0YU7xb08MjtRQt7CtTUeKstGZGnkcJgNxaVSEeEa5p3k0JMGUUaPM9oGvodqxXdBjAxefmMYMEDWYw0P5sg8T0QkPS2FuQpAg1Pq/y9tJDQDSD/aABVXYYQ1gb45P4hoGpNA6QU4WWU7sFOmfQ7AfrCGRWJfYMcJ50aoDKi16jEoY3v6KbqHIGGGgBFkT/lDZ7MVO+hxYFA6aKqoZYUu2vPrD4IrqgqCL+wOrItJO2CEbQRccf7i1VEg+gUbJrBnDOeuEYNoafpYhEiJdQ9eilElRINboCEUgzzMutMRgNBVrApaORe1BnhkLaEnCzJVxoxNB+9q0dPVA0ZsjTfxApZMXXvNcCaGhQ28h5WghlfBS4uwEF9GVTRVFf5dDNn9d3SkwlBNzU0CwG4qmEymmS67pmf/hTvfnAIK1v0viODoH1fygRvwNNPPo3zZ8/i6PiIzFAAU2dvCYu+EApGaLVGp9RhDyiAjYAlevMULXj6FyvYHR/hg48+wnPPPosXXnoRly99TKaoan6NdxSxv9tpD2dvuBNPfu5zePzxx3D+hnN8tr7gteeex//w//5/M+q2zlJfVzdY66i9o0wTUIA/+MM/xj/3zW/glltvwt333Iabb74Re/un8OMfviAG9hAOAprWwxc6rBoqKif5VgV1hhTjllIxL3TEU+lMT3b6lwLDNG3h5rh2eITj4yNE1aUBOL56De3oCP30Afb29jDPM46OjtDnjs889AC+/NTTbPLXVoJ1Q6YFzVydUrWXKoFLg6NIXmBU0ieL29QygQwEGKAUzWMCUGLfwURoFEzThO/+9Cf4+PJVbDaAOZtiugO33noLHnnoQSwNgE8n9rpnKnGk/hnU6FyZAn8ZBmYHauoXl9ZOBLW/6PWpBiQ0grHpIrKJXG2jmBIAIu+ciC6YBX1Oa/Ci3GgIC+EaCgZAnx1leWEsvYt3kYGalx069giIes8Kg2gHPlnoWXoaylIqWm8U/0RDs6g7lWgoZgZEG2nrntdKp9oFfuQ0swQ4fty1UVs2UgrETwqa3setqdLI8iBnf4UgOkoAhmHEujQ11QxobIdcNLvFkwVhFFZAEOW9CKzRNpu0PnR+niO1iW9k3DAMIpWrAeY8I2W2aB8ULjUEjki/IOpJcz1V2RORiQz5mLAa7MY4UJkq0YsfF+kKicG8gb1STnZlhdTubgHWFLw2Om4mFUJDQuEcwFRkm3fh+zh/BA3QjJVwugDkQFzOnffI9FjP64EqF3wFEsZ9C3ippw8Zh5W2xEYqMRiZAM0hAIevhXdIgekne254fHb8PTyBl+J4smfQ1GMxorUYJkX7Eal1LgKiEqwlf7QCu1bp9N1U6CBuLJm8ce5oXEPgaLyL1H6MqC+GQQqBQ3AxQXk04gOM1WFOlonCc4l0OxRcOVw6q2KMfn/wgz/D7DMmpTwhYThLOAvOnL0BTz71Jcx9SdCXNku3FYJrJaZ45jHEiJHiHtG3UuGFts4KgzFvjqtXruC1136OV155FW+9+SauXbtK5ymNXG8CyQDOnTmP+++7Hw8/9DAeeOgRnDp1GnWasLQFkxVstgc4OtphXhzTZqLWyxzVkYLdquTsdm8fb75zAf/LP/o9fP3rX8M999yF/YMJv/7rX8KmnsP3vven8H4ALx0333IObbfD1cvXxSBgpKQKNVy1FlYTetN5Kzh15gy2xYC+SCgOXD/cwWG4Ph9hXmagGObuqN5Rnez3blHQ4WDXcACPP/YIvvKVr2B/f092tqJH11UPnwUxdUnncs9ny4KeATIxoicgGEyfUQeEobXjpOmqXUvwMs8LfvyjHzHgxJhbY17wxS98Eaf2T2FpM9gqIvzTkOcznvS0v8VYWRr+AmCzPKZvuQ5hMU9Uy/2C16cbkHSDe9FwN/6dBRXsbdROS2EPaTaya5xHdYR+1wpioJTLuGUnw4gyliUNTdHsFNOmPjo+xrlyDkAwGGzXHsI+r6LrsoqjZPRJStQRzXNoYKVrMMt6fjoPkHHpQmOucLawkkK+LMFa0WaN6cH8FRXjGiO1dYRZV8O2kKCEUV9GlYoycsDessBRifTVd4GbWWWl69w/kFFzVH+4g+viPb83yx+d4lfv1DqEkrsHmADys8c/ojMjYjBT3pNaGjIThZ1gxfRk5ALuA3dGohDgKNoPXVF5ulAPJ6zvKgWLQyAKWYEQTms813C2fB91KYo2ihynvjs2aZTV0egNIIowRx4Pn0CsS48CA7yaKotChAspw/n+MH6mayZgUzT0CSp/3Twu1j+rR7R3ilV4IY08HDlOfk4CXl1PRR7mqOaKVNG622M4TrXpQGTlY18kABz+Vb8YO4TnjiwW914a+h4ieOQZGc597K8AHtRTaCghD9KqGofAczAl3As9GSReew99k4c+qaNuNnjp5dfwzlsXUIujo6FMQ0Q41YrWDQ/cfx9uu/kGglfZFBcTFDTO0I5xDzYFSvw7is6j1DuBba0Et5Vn6dKlS3j5xZfwwrPP4v0P3sf1o50Yu5CmG5bu6Itj2k74zBOfxZc+/xTuvPNO7O/tSxszjzk4sgm2nbB/5jSuXz+mIFWl1zyy1PDVzYS77r4br73xNl595U0cH/8+/vlvfgP33nsvNnuGv/LVz2FZruNPv/sMUArOnLoRjz59D65fPcQbr7+J99/7AEe7I4JLadLQHHUysozm2G43AtsF1hs27gQguwUFE3xH0XXdTFiWWbaQKUcYMC8zdvNEILl0HB0d4dy5c2Bp/1qAqvMazKPShFkR10fFSqlT/qzrmQjq8j0Brtdb3KidcpMuzAkWX//5m/jovXc5SRkLOthF99zps3jg3vv15inFZGUj/1RD6BbjEwpam8egSPMUPZdS09Ynk2xDWvHLXp9qQJLDwGTQu6IMlwUuYURMRjorOmjF3EsOaSNt3zCcBgBMCNW+i+KNhe1LULQ68Nax2XLiZhc7kPl6OZY6xSRVpRuA1HoEI8C8uiCJhLUuf5TgBJ0Nu0o4Bn2HV/RGg0W7XiXmYx+GQiUh1hUQmW5BOIghxLMSBprohus6IoEyGcLyTltNVo6hgwArFJRO4ocWLEEZK69ppWCyiR0W54VAR6AstAsxabi4w0PIBWRDNVuh76JGY7zHyH2HER4lkul8K0trDdoa2h9kVZpSODzubT21FKEb8LEfnY6utYZaJ+bC84NNc430nKNSAg53djJkF0lkr6Qe1wfNFlIDL+p9BJyXaAQHmISApYvijXVRFFZSv0GGYYk9AEbAxSPqH2xFKfqUQQjoTCH9Mq81vspQa8wSiRqPsT5ZjaJVSH1TLWKq9JnBaAWLBBrp1hqj/c6KpN5NJeW8oOJBGQPZcTjYArhKpZUuyv1uA5DqLimFMdSKwfjUgtYWPefQxhisbhANzcIYu/lKcBjAA8nehKA+10aGvpQV6FwW/OiHP2IKt3QC2Fqx2+0w1Yq9icMqH//MoyhFc7MciFgZK8YugEaccYs2B1ixi3CBgaJeMY7dPOPi+5fwzDM/xYvPP4/DK1d1NrqevemfgqlOOH/+HJoX3HHnLfgbf+Ob2Jv2xLwNFiZsTy0Vvix44nNP4tbb7sAHH32Ei5cu4Xi3Q0fBtCk4dWqLW284h/PnzmFvfw/PP/ca/ugP/hjvv3EV/+P/6/+Lf+6f/wbuf/AelE3H1/6Zr2Bvfw/f+84P8dpLF+B+hK9+9St48nOfwcWLV/Hqq6/i1VdfxfUrh2jLjAruUxRHmxdst2IiF40Y6Y5511ixYhUAn3/dCLR25xmyzkZs3XF8fIS9vS3MHG9feAdHu2P2YzEM1hkEY603ngF3Vd0V2R9uiSjVjuKNmJsVoLbp4Bkc04rNnOeZIMepEer6vReefwFXjq+gbvlsm/bH/fffhdtvvwm977ivT8za4hk0BYVw2Usx/JHmS42ed9kRXucituCTccFf9PpUA5ICdg7VjDs+TCdlyAUiAJhqzUMOK8PIQM1ylCdkPq5k1Ul3ADHeXRG3O6es5lA872jzkpvs+PgYBwd7cOvZZwKq9ukxPh4so4sJmmHwHNzowUiEBiXjP4+oggbVBVK8j/kTpVZVvLiYI5MTKgkAvLGt+cnUwzBa1EzQzAzptCLSMpqEWY/86wB+6nyOMRQseheQDp5qwbxwkmuyVQWZy+X0ZN13KmYDdp6ssgiHmA4nIk5b0Z2rrpMRwZbVnwOUhGMOwMavjVTIuP8htlW6Sb8Tl8PvChFLOKdxF1Hhhcjbd0YZrc1w5fTDSJl3WKlofYYbBdhzW7DMHVMtEkdC7gCjbBVMCSL6lEAzf1r01nA03VMYScDy2cW+GEAidDpYAbAAtZDB8cFayfmnQNIMUKoiKwGMoCknDi8OmwIYGKLpG8s41QvIVnQ1m/sQYOoZhNGL9t/BdJp+L85cAAlYpD6RTjm+N7VR2mqj0Zl4f9kQbzqruRfkeXwAcz4P3ntUKEUqM4BVBE0uKGml4K233sbrr7/O4W8+A+AwNsCxmSa03vDAXffgwfvvT0o8dEJRDYNgHfPx9fEMo3GgBys2zvf169fx1ptv4aUXX8Jrr72Go8MdDMA0IVNJvVNncPbMedx139145NHHcO999+HZnz2Hjy9+iP29fTKn3dEKxlkk6lJ/HdqK2+64FbfdcRtczwlZYu2AN/Q2w1vHFz7/WZzd38ef/OH38cZbb+D3fvd/w699/cv47BOPYZomPPXFx9Hc8N0/+QF+/uq7MP8Bvva1r+Cmm2/A+RuexuNPPIH33vsQb73xNt56/S0cHl5L2wiXjLpQpbR4B6oqDU3BYuMzRwcnvsPRasHk0bWhY1M3KIXzpy5duYZbbtrj3kgwgcGGcEUEjsPOyIlXrkEPraHOl8X/GQQupSXhKWSzz1IEHMmQX/roIl59+RVV9bG8Gm7Y3+7h8Scex7Rh6pfsCYPOlv6FzyGqI3m+K0W5ekQMMHvaQphSRaBOrP1qRTafbkDCuvmOikitBItA4xCHs4UhADdCLVUlgeKmWoP3GBdPPYkp4urdM5fe2lDCuwwA/1gwbbZY5hnFJngrZCi0kasBizfFKpGWsDTYoWexVWkXc9t0bHRZETXy+5umULqsclTd1GFDE4SFNjadj3k26WLUpvcpyIvGSHFAkmXkHaeh6Ivo9uEK6DSmmOnDa436e3NW5lSw58DoupqNuEXLl4wdCTLIJljxdDwxBM1bh9UNBs/Dowl3tUOOSiPtje4ctBjgRaXEcYjW+pFRfSEdjDEqstDyWPSgVfRtgwFjqmgIWIOVYhv7MBSW4+sjeqRAbUGpE9w50dTkwACgTpP2uSJqsWBQJFUQZevqdRABl/47qHvHWvdgeXZGusPEQEjQu2JIcoMBuj85bN07n+Bwfjbers9SdQu3Iv/aDFR9ZLsydLBZVgdTb7Vu2JXCyFagFs0nEYspEFd05sd+MMRE1aqzsn7ea92ES5/lshXUI0U6TF1hk7mxsT8DsMb3BRgxILo8U9QeU27w50pwc7aT0Xm/9NJLuHLtqs4cPy87aDow7xY8+viT2Dt9Cru201nWHlWw1MfKZ2Rted38GQNo9h768OOP8dLLL+OVV17Fexfex7ybuTcn8i5mjmXpaL3gllvuwKOPPYJHHnsEt952M0tuNxu0tmBvu4e2rBjTYPUMehYjxdc89qAPGxCVHAo+Yg/PfcEDD92Hg70D/C//8x/iwnsX8K3f/y4Wd3zhC5/Hdh/48pc/hwLHD779E/z85XfR5+/ja3/tr+D0mbMoU8Gdd92Gu++4Ez/dHOBHP30250XRiDhQOlqbudZgSrUtjm2t8AUorWMy9sGByU6Xgrk3nDm1j2mzAZaGthzh8qVLnOmzdEkJuHeyZFrPP4egxvoUdUVW/mQd4EX6PPa3o2PpPccZBLiKvV0BvPnGm/jw3Q+0R2h/vFfccNPtePDBR1HLhjODECXrDcUnVWoCsC6mvktwH5WiaSB1PepRpT3FkmJAQ99+6etTDUhKGBQ0RFOHEZNYls1mzlKbp7foxhlRnsxJRA7NB6sBGjx2yxvfnRoLRVLcm1tYLyiNETQK2LK6zJk6YZlWRxc3bxhVMMrLJBhCRN9gCqaB5XOlFkXoFMA5HF4Z2Sy+qCpIgjU4JpT87jElFAnGiwmMFcPc1WV1tRzxWmsHDGwvz+um1/PWUeqGRqaTEg+Vflc0QeA17qtHFYeeWzBG5eQXIwTLSf5F5NA7ah0RfFQJFCtY4v0ehzDC3WiCZ3ng6dAkVi6jNDkrFXwAB2O4hJxJYrkE6V9CiBa/G9eUbbtbVD9UeAN6Z2lhMcNGbFov49mEoz+eZ6Z0utIVsBRHlhhV3it6yyVerWMAKa0JkI3GAILU7o29dDBAS7BNgNgIvWJEX3jeVOU7n3QxVnSN+RqxSF2lvuP9BsvJzbFuFg68t2yQNpUNWcTOc4RJqb849wHydW95rUJmTc+zCIxlVZTOf/z3ABgYn69IMdKUcYQ6LEwBorrNEFoQibJla7LjaTAokUoSM8Q0WcHli5fxyguvofhCoGahe2uYpj24A3feeRc+//STmNtMp25DCBqTuzMGD48uobcLDZoB1js++OBDPP/ii3j22edx/fBwACbBhO4cb7E3TbjnnrvwxOeexIOPPoL9U/sM7pzT0r0UXL16FQf7++oPIkFj7+hWQYJKCqyivk46E8hzAgp7ob2CoQ1iwNVw+z234G/+rW/gH//jP8Crr17AH/zjb2PZLXjq6Sewnbb40q89gY0XfPuPvovXX3wPi30bX/urv44zZw/QW8Nmc4AbbzyH3itbRYBrNi8NxUbQFWvf28I2CA5YJwPf41x2di89feY0Dk7tcU3NUTpw/dKVBNu8Pc89ztMz9mBsOEMR+7LA4JiMtpf1BhTENwGY6OYdhRIwpdI72bRq9EfP/uSn2B0fAhtPdgbdcPfd92H/7DnsnOmjYgzSilV4jxQqn0XM10GehxHUhJ6xQlV9nSnvKiH0r6hp/XQDEuaTRU1SpZT2giORAcAxTTW7Y9JBDS0AZBRLWbEOyVhwgaMUkJ/G/zUAi8o5Q+AJd1ZLlJr0cuS2A/D4stCoy7gxL1jYqVBUG5+4aabOcGoR2fQWQtqIchRBSUuwSCDH+2aE240tylNwWAsjes4tpybFHehyEuik76JCZ80WRFdbVFQLo6wZJbHx3BHMAAXB+rtEDjxktQvUqDqAX6UGPBiHNIbSRWVNuJoCsEoqIl1D9jqJlBj6mGYJM4yW/ENjEF/k0DOXAYwDGNUkNcpFdX9wgkvDSrMExve9D0fr+pwsadTN1loy+vXW4I29QkoInp2D3NhEj45uM3HiL7UUIbKmASLBNKFOW5CKZldQFwjNGTZiNIKxCy0RgYUlAAFMvRJWKxROO/anUmsZeenzA1R7iOQCNHRXB+FVxF8H4AxNDAAxVbG/le5cVmXrAGL4ogNAV38OpYTS0JeTwty4jlh70/2MNEu+KT8j034WfX88wVe81qnDTIn6WpCsSprQYIQwnYgeADDVCS+8+Cze/+BNFGNr9whaCOQm9Fbw5S/9Brb7ezjaHQvsWYKqeFojio71HGfq6pWreOftt/DCM8/i9TffwG6ZsalbmNG2FefckwLDTedvwMMPPYjHHn0Ed995FzaaU7NInBtHxVBwfP0YZ06dDnyBGGbJACTO9dBmnRT0a13WWjbQvtSJD7n1juYNt9x5I37rX/gm/uhbf4KfPvsc/uD3/gSXP/4IX/31v4JTBwf4/Jc+CzPDd7/9fbz52rv44/Zt/PpvfBk33HgOvS84e+4UvB3Cp4rWJly9PmO3O8ThtauYd4vOIGBK6dRj3kMpbH65SCtY5ZB3R8f4+Pgwz9buGHjvvUuq8qFdrbYKbFcpyDg/ofOJc8Ouq41MjfFJZot7sPIwALRjaO/cKtP3teCD9z7Cyy+9SkbWG4Ow7jh1eh/f+MZfZUqldcCq2j0ENlwwdE5DjxZnO/QjPm6HVVmq4Ovq8u2Iw/nLX59qQMJhbT4EWtr0JhSd4EN9JGiUV7oNY6qnqP7djAVmiCZIK+MVIqwsZQrw4EjBFjCr9LByNLSeQlLuwQT4AJ4MqsLh0+nE82OuVpHOGo1mZC6BmsCEGY30VA3RnZZRd2xYQwp6jSVb/NYwkso6S3cANFHYI0r23P6Rd6XTCEUKb6UgWrjXbKnQIkzjHwGljaqAlwuEnFzzABnp9KTRYy+Bnu9LMauEFFF7Hw4uDBs3zohSTCxFDmjscf09Kzi6jOOJKJqlGHAHkpdrPhwCsVPcabITxUqWqhp4Xy5am/c1sZ8Nk728vqDgdzPq3j4cDbCJlVahfQCy3Ltrb1imHrlfiw/nxNQDuB9cmiRXZUwfzoKIb0Tan7Qs4eDDkDICtgQMAFKUDDEFpVZ4i0iUn13LBCDGJoQjswQ3aazVnwUwDhpT1VCkIyAx9qCIErOnW47W56YzljqWeL80DBEYIFcYeU4DUCDSgAEqcn1W64IIHBrjJmf6qEMt5KPRnDs2tWLZ7fCTH/6IFX11OKzW6QwdBbfcdjMefOReNAU4AYa7AgCWX0N7jzn+qtkw7733Ll577XW8+tJLePedC+jHxxSX10KH1QGfO2za4o4778ADD96Pz3zmUdx6yy0E1I1AOHdCgBFjILDMDdvNlu3YYw/7ai0FXBlHeuAoRKAY7MQY1CbdTjKrfC19xrmbzuCvfeM3MG338MM//TP8+M+ew7w0fP3rX8Op/QM89sRD2C2H+N73foS333wX3/mTP8Vv/MaXcMP5G3BwZh9WJyxLw+7KVbR+RIZpWdB6ozs29k6uZRKrGUGV7F+cY3fsdgvtnMz8MrMEwKOKMc2/glU7mW7PIgjZPEP01RnMP0DGO1K9WP2uO7Kiy8uCqVRspg2ef+FlXL1+qHEg9AkNDQ88cC/Onz+LNs9ZrNEieBBucgGQUifkdGJjEOCARiA4onzei6klg4S/8gf2K0KNTzUgGUrfPvL+iNyW0XBl7XnkgRc4Jv4cQJRNRjwXeeHUs4Wmw5EVMctCUDIEqYZ5PsbR7hDbMsFtT9tHEWKwG2AEEYjTYYr6+bOsxCzRubKhNQKOSAFEn4eYe0EhmuXVRwqqZFQeyLbkHSO2t7kcSEQu0FXrswQSpmkiHdvlygTkKFBURKjIp0jQaWuBAKKDoLiIVSSXw9yAbD/vvcOmVUdW6PmlMJcsQ7SJp/AqDqxKe7u0QKZ7CZlIlOCqwoPGYBnVQGYo6IPWxMnIOXz4KtGD8PnAMC4tWCQDvBH09jBGFtlW/k6D9q8ay7UONQyjIytm2KsTrnZS38neiOLnOgetOsO9YWkN280EOKOyEoCzDaYodmhJQGsnQKFILaY/MzIaTnfNNiA/cu2UuXbRxGswUdzj7Mtj2Z2S56sOcBH71SiE7l3snEp/cu6U1j37NcAAs5zOu9aIxB5ZCzq5lAOESR2yuifQWXoZ6+b8HP5eXGvcf89/c426qnOCldV570wTwgzRSK5OE1576RW8e4FTfZtKxKOB3SR27NHHHsG582fZW0Tnz3Tvtq7mKiXZp7ffegcvvPACXnjpBVy6fDVTMpvNVs7FsbSCadrg/gfvwRe++BTuvvsunDl9GvKRCA1SfL4saJaJt4X3furUaS2bJ6uZk45DMO/SUyn1GntgMGzxPTp5eV8hUAfmZcGpc6fw137za+g+48fPPI+f/vg5HB/v8Ju/+Vdx5tRZPP75z6DbHr7/g+/jzTc/wB/+0Xfw9a9/DWdO76OUguOjYzUjpCGi9ElsZyGLvdnboFtDb5wTVADpYAAXaCxqPhfM8MHBGXz+STZF642FAMXHuQtblMFI6s0igJSlNiMzhghoLOPvYCUhu8KUHf1gKQXzPOOZH78A9woUTTHurAJ84okn05+1RYJ76XeKjZLx7i1tGIXvsn6yvzClTwvtRNd5aUYvmzHNr/D6FbWv4/Wtb30Lf/tv/23cddddMDP8w3/4D0/83N3xH/6H/yHuvPNOHBwc4Jvf/CZefPHFE+/56KOP8Du/8zs4d+4cbrjhBvwb/8a/gatXr/5lLwUQLdQWUkdFjqk7jZHkQEmRDwTaAbDjY5R1NkUrXQCkN4cvjUIhHY7WHG2meMi6q0soW8LXUrHdTqIT2Smxq9y26dtQN5RiF24Kb8wRhrgU7sxPGoi0oRbAAEIfQ22uHLAH8iyrf0KE6nlvGWGqFMzcYX3R+HYahUgHUNnaZYA7zDqWtqMRCRYH0AFCRuleqF+ZfcGChl46Gjr/7I3VSrkm3LSpP9G/W+tD4Nsdm8o27ZCIlEBcSLEbLYHuO/Ko7iwJjZxzlIlmlNw8hXbh79xVARB0u8qAu7OsrylSLlViXQELLw5UR/MFrc/MsVoszIjI1+4qmu2F3oNOsMuAADHrZWkdiwKSYoZ5WVCnifu6sfHR0ha4L8zfw4EK2GRAdVUOkeUpLk2TmKFs0R8gxEmBe+XzD/Yn+n4MpxyqkWAjeHd95VDohJs+p4E5+BH15tHV+sSE2+4OB5m1BnUa1W+0rr4204TNZsMKOiM4o7iU35F9WRBG3oEiDYNFzw3Lnj4lxdd81s05ZAwhIFwDDQP1MNE/ZAVe8g0ZFIQYUyoBZ3o03ucS2bMLtDOi7Gw0Ne+O8MPv/wC+OEL+GgLhyQo2peL0/mk8+vBjaDN7LXmPCp6eDm4yxtXXrl3FSy+8hP/+//nf4//xf/+/4bvf/jauXrrMZ6RrXRYHbMK5G2/Fl3/tr+D/8n/9Hfyf/s//Rzz+2Ydx+tQWhgXeZnhfBlAw5DmOfcCGfAWGhlMH+6n7YQ8ZoHcbZ09BUQWU9vVkq07YrAheXGX/CmzogAmHdssx9g4KfvOvfw2/+ZtfxamDs3j+mVfw//kf/ke8/c7bsNrxuacfwl/56pdwcHAWb775Pr71v/0x3n/vA9x26xnAr6PUhlLYg6lut9hOG0yFjnkqlWnTaVIAxDJXvp97qlbqY0rZYJr2cPr0Gfy1b/yzuOvuO9Ea61G6M9iI0KZHfxpDilbNNK0bQ3MVx687JwC7/j52ewe7ZlM8HPPbCmrdw/PPvYx3LnyAzbSBWYMbKyjvuvtuPPzIw5jnWQwwWVz2iKRf7X1hZajE+egqFFgALGT5rDs2pWIj3dmyLPSlAKxWBpbF0XJQ6i9+/aUZkmvXruHpp5/Gv/6v/+v4l//lf/nP/fw//U//U/yDf/AP8F//1/81HnzwQfwH/8F/gL/xN/4Gfvazn2F/fx8A8Du/8zt455138I/+0T/CPM/41/61fw1/9+/+Xfx3/91/95e6FuobKooaTLkidoUhNDZBO7ghRYtAGmNA6BbGUkKHRLD6PCFXMyOduiyJzgGCElKSQLEJvczooMDQjDVAiA1kGTdxUxbD0js2EQh6lE7qOm2gbdhorEMHWjNK60pbuQ/xbmx4VhOp9j81NA74yFWGqNGRJIHWCMihet0l1A1gAKBGvxYQVQelGqWNcKAOwVbS7ujqRolkDfgRpu+MyIEGh7lcg6Nm9YiVolkSivKnkloUCr8s90M8b1KPg6K34CV14pOyjysSMGXzNtM8Dua8rWo2ihMIhGM4sX4Y6eIx/2SlXdAba6TIGDap6qAj5t60ZUGZJo4WCJYFAjeomQZwGDbTRqBsRo1SW4GvKpbDfKQ5IjrT7YI0sZqpnSi7hvZjYC5fOY14V6T94v2xh/jTAPuDsFgzCcjRCVE6G/lpt4lr0Y45YLBYGshaC5qMc2hbRnVZzWj6xKvL8PbRaTbOAs9sxCAGlJpry1/tGPNzuL/WwV84i6Tbcz3E8AVwcwKGWKsOx6ZOeOftt/Hz199CnbaY/SiBMbxg2mywzAs+8+hDuO222+mMYlijq6tpLViWGR9/cBkvvvwSXnntVbz//ntYdmxitpk2QAc2HVg6sH9wgNvvvROPPvooHnjwQdxy880AOnu4dApzDWEHBjVCsyr7EuvrhrY07HY7bDYcPY+0RVFB5DInbPy1dALgULt09frJmV3SSrBgg3ajCRhFVRsMOJqPgAJ8/qnHUazgj/7wj/HWaxfwrfYt/NV/5jdw1z134bHHH0QvM777Jz/Ehbc/wE/+9CfwtuDU/oRjsNChlAm+RIaIKae46bQdHuCLafAI1Gop2O4d4LbbbsVnHnsEj3/2cbS+Y4BUuKdrsaxWQQiqLRiRAMLa/0pNdndYjw7hNQPkNL1KSQfMmyVDOD6c8dKzr2FeDlE3PVkpGHDPffdiu79HsXIBmgHNG6qYEcoCgpnX03HA3LJlxDqdHilZnqE69o2L+fzEEfyLXn9pQPJbv/Vb+K3f+q1/4s/cHf/5f/6f49//9/99/J2/83cAAP/Nf/Pf4Pbbb8c//If/EL/927+NZ599Fr/7u7+L733ve/jKV74CAPgv/ov/An/rb/0t/Gf/2X+Gu+6661e+FtpvdRctowMrN2nJ0rIyLCC66PAefnn1Hvcw9iqrWnFNIbLKnhs+EhuAAdVQekWtMjwagGUAp0FO1DxkvltCLyumCI7fRUIkgBIdrIOVNY1IZGRCMuocJV4U3UGHHKPc1ZEtlKMMcYgHLTBTRqRxWzFPh1Ek56pEKWHMLokoGQgn71mCisJJuol2MKoKYh1GiRpS/Ap3xCj6vtIwRDqK1xxVHqs+GZZkO1tfBACDpdB4fZw91t3pwAhIQysDeHyHWttXm9D1fb3xoHIENwCVGFNrM8CvhXZj/Yy8UZDmiqBRgW5qkFThVkFNRcfRvGOfAGN6Y2kNWzCVFqV14fDdCXiYx1+fFEfm5SwqjGJdO7txmihz7dOYOspnNpgHh1iGBOy6p6zgkRETqs0yW+0pan7KWGNuJorRJeYdz7ii2MSmXypNDe3QZqqpfeFtKU3rK5ChB56feQJ8raJwCWzRDZmDMxsAwjgzhKYkmgTq4wNHrYDP2D+e64bV8//kK8YivPzCCzg8vqrmigAK23HXUqgBaY6nn3gCm2mDozYLuAEFnB/zzoULeO7Zn+HNn7+Jjy9+jLkHCztsXW+Os6fO4MGHH8ZnPvsZ3Hrn3TjYPyAAl7C0r3YHPnG5jKcHkM17qIbjoyPMu2MBY5x4Nlw7A9nWGNfgiEGErgBoBHyRKhy6jBhCR2cXLljBp+z405//HLal4A++9W1ceOtd/OHv/yG+9te+itvvuhOPPvYAbKn4/ne/i7fe/Ah7G3X/8YbWF5w5vYcz587i/Xc/wHa7h+Idy9JQyoRSDEvROJKiogBtl94W3H3H3fjSr30Vt952K/b3D2S7m/paEXyza3aMHCm5tF32kcC4yBdEepzpXM5XCvZNYEDl0g4kB2GloKDg/fc+xquvvQPUDg7qJJN49tQBHn/kXtTiWDo5OO+OqU7J7kUX3RFEIs9Ib8j0lGL42PSIg04d1/qErzQBv+D1T1VD8uqrr+LChQv45je/mX93/vx5fPWrX8W3v/1t/PZv/za+/e1v44YbbkgwAgDf/OY3UUrBd77zHfxL/9K/9Oc+9/j4GMfHx/nny5cvA2DOs3NC0kDp4cyjf4BzTgxZPtc8hwm1UBjUvWO3zJjUsKpFiTCMampghf4gY15RrLPMtVQhduair12/DrOCWg9QturWmU4uIkI6qhLakAgw3AFnrpzYY1JfiQXL7ogbVA6ftd6qhgiErUNdEZF0B6S74B7mOpEgIJVtCCegHLkbe6loM7YWgJ2CRVaOSIyFBUEJrJX9YzIowUB1ghxf9ffIFgxF194ZeTLtRoKvqgLJEWxPR51o/bmmS0ZdEZmywqqyf4YElMHWFCOyH23PR8ayKaqwArSWt5IvA5JxCpEn8+IzupUc2JVzaNYOS3uzFJbBFvX7aC5xY2OTqBCRZSqrktGZtryHeZ7lqDeA7qV3y+i1A1g6Bz5uNxyr3hCG3gh6ZBjDNwDSqVlJRmlMiI18cKwVaV0+W/aFCZwh0heBR5bWBnNipkFpyoYEUOF43wSnFpFh/GJeX08pVERgZkZHsXJ0LiE1rKh/WUthcv4b+fjy2rPFQ75K2tZaZKDdCVjjHSEyQ2TU+YfQEMXPisp84wuixTbTgOPvrTve/+AD/OzZF7H0ZQCaruGE1TDvGu6970Hc/eiDOFpmimCL4fq1a3j1lVfw7LPP4MJ7F7DMu1wjN+o6Sq3YlC3OnD2HL3zxC3js4Ydw9txZdYwuiBklnIGkO4poHQTVwQXx/sSORnTkvNejwyP01rG33aI4+8iEjXC9B/p9b6GHioMWC8qTNKq4mCqLsvCcU+0hziZIde9oPqP0hs888SjOnz+P3//9P8Q771zA//w//R5+/Tf+Ch586AE89pn7sakF3/mTH+Hq9Y9RpoLWOTeqnJmwd3AKfXGUTSXzSlqUbFllabNtt/Ddjs+mFPSl4dabbsSDD96HuWn46qqlewkGtHkKQG0VREPhq3nYzQBcXLPmrCiNNcqqRp0ZD72SNt/WJ7z+yhu49OEV2ORoxvJx9IY777sH9zz0ELxUeGdb+wjaoIouhH02sGImIzmnvbUBW3l2C1mcUpT+jH2EVSXZL3/9UwUkFy5cAADcfvvtJ/7+9ttvz59duHABt91228mLmCbcdNNN+Z5Pvv6T/+Q/wX/0H/1Hf+7vtV2Hcl30oHeKGuHRY6DkwrFNu0oyo5TXPY19INLo5DhQH99H6orpAJ5XgxsPNfvjsCusF8fS55zjwbbtoylTzAyBPmOYdH6fwL8YtpolVKwA4ShqMgqWTAIAiXvjkrlhwylWRYihtOaGs6GR8ILwRR1ERTWaiK2uNSKUYGGIb7qiSFYGRdOujp5gMMRpFiYlSo1lxJVx4jtc4El5/BQOepNxrFJwGw9VQHj37OkRn19U1saJsgFUV2JHZ68aEmLBH5kwBde3Gh1cgJgekYCtAFIHoz9V+fCeRJWKqWGe9+QmjiF4ZarYbJhyITLq8Gqkv9vCvLUBBrWZdz5LdKRg2EMH5SoXRmfL+GAzMKIyk9GoFpEolC2x4SQ82KdwSGLM9GayXWNvxLrS0amzqFgV2krLvi1hP4tFBK09nc/aFNl1VYUBs85dMBQJM8JgJi52GVX+m/fnaQdCB7JmT0dqMf4sIK7zE456RO7iR33so4As0fSQtqalVgDFcHx0jDrVEeGXgt3uCD/7yY9x6cMPEOMq1usZ7M5XvvxF1M2E4/kIH330IX7+0it4+ZWX8d777ymdFTYvplRXnDl9Dvfdfx8efvQR3H/vfTh37hz6Iu2RMzyqxP5yHEoBxPmCwxpW0bJS5MBIkxMe4+j4CNNmwnZvj2fPR8sCaM3Qu8i63BX5WutGEsgjGFqWuRJ8xoMyIWquLwWfDG7uvu8OfOMbfw3f+tYf4bU338Af/+H3cHy8wxOPPYYHHrwHVgq+850f4urVSzBsWJ20GLa2wTRVOBomq6iTxvsVwCZpzaSFqyXYDMP1a9fTLyxiGUuem5UP8WE31vtuOO0IXMuwmEVsoN5XFYSEeyqqDOSGNBwfNbzy0itAm4FphqnrpZUJTz75OdTtBvOuaTfzObSlY1rZplpGUnFdMRf2PNjMAEK+6i8VQWdUeK7qG37h61NRZfPv/Xv/Hv6df+ffyT9fvnwZ9957L2IKJcdq8+ZLidJDOi8+HwISt6LSMVUkSPAYznlM8lXlh/sQUyo1FMJJIIxFdOM02AQETQdVTsTB6q2PtJAa/AArQ2c9AVAgSjo4MQChUSjDWOmq03BCGpmm70qD65rbIRBmcaABCAKvDEAYQEuEnAwKHJNVBGUeZRgutM/LD6eloVOO7MTIZVVUDzmJaLhlpgxMIbiLsm1wTQNUhWFjXtn4PgEwAjQBBAEG/q+ElgJ67idZAINlVAA9j6GDkNaFBXy5B7PTpD6Hglx+WxFlCompoxsjoGFYvY+SclWaZBRfNMRAbcTF5cJbw1QMkwGboiK6hQArDRXisUjTBKCCfRImA+bVI0dUj1k469HVM/dBoUmNqcR6FOmogALzAFwnXxHlxZ3H947OoQbEOmGIPhP8GFZpHbJrk7rUMtDU+IICnZ1V9B5gEZCDECNZebN/vuoGwjSi/fN82dCIrVIC8cytmFoKFPnDwVJmA0EBI3OmXV9/8w382Q9/iLNnz+JLTz2FUwf7WI6P8Qd/9G08/7Nn0bDkio30jqE5cPNtN+P8HTfh2Rd+hldffhlvvfkmrnz4EZa2SFPF59gWTry+8aab8dCjj+HhBx/AHXfcgb29PZiDoy68i3FVf8/wJQAYOAUwHaAkX8Gm8CJPCJqvH17DZn8Pm+0mxbYR+EWJbwiZ+aRGii56HrGqaEnmS/4PkeqItHd0cR2pY7EJ0FyfvuDOu2/FN/761/GPf//beO21l/D9P/4BfDfjs088jvsfuAPwp/Gtb30LvW3EWDj2t3vY324wLztgW8Qoh51lxeA8HyOqE7119Lljd+So3RSAunpMZcimFRKAt7GO3l1ltHEfA8RECwJtoxHEKrBxge4AOtC3vf/hB3jt9VfQq8OsZdB0cPoMHn74Mc27iWcg6OMANA8rujZnoNtizIOeXYBBpZ1ab0OYq4utRXOVDFj+CUfun/T6pwpI7rjjDgDAu+++izvvvDP//t1338UXvvCFfM9777134veWZcFHH32Uv//J197eHvb29v7c34dKPerwYw5DojbQmVopRG+QENA1cC7K7nRIixmm7ZQ11h0F0aWOanKV0gaY0EaIkjxAPRYwNBIceBVCWB1M+yT9jRMGEAijKWOGiPa0WdX0zSPyWiHwYmv3cDJ3rZBaBsjSwUf/CsgJsIRPEbiBVQDZxAcCgV06BDmwFkh6OLpR9RCXGAIwvkapNnPXyEMZXTzpmGqBlOr8v0gZGXoeorx/VHUu5VNjhNtF4a+cpNYkWnnH1RLkupgGpkx64xrHRNf4/S7nBdHZYUCDaeCSjpRSHn93RFVBfrdT/T4rDWVhlJwVGaf2t7h2ZVSWGCX3sI1rpo3DiyFkHwzmqVYb1wYEVxFNlpDUq6dzWYuQCUxGNNfb0Cvxbi1BdMxZQg8w6dnQK6Njw6rHj7MirbOCJFit0EExXNN6OkHlpJTlktenR+qDqekrkItJnMXqjCKxaJw//kWwQwNCBWgcrKA+DDHoMKqUTtrbkcRxMY1wiia/+93v4KUXX0QpBU8//Bj2Tp/F93/4Azzz7PO4fnSIsqnZ6I/3ISEjHMu84H/+n34XH3z0AdDZGXVS5ZR7R99VbKaKu++5G5998gk8+NDDODh9BpM8aQziDDEmsZ9DHpcpyQBsega99zCBPC/BILqjeGeljcegyooPPv4IdbMFSsGy7BA2TCdDe+UTehFXGtV7PsepSMtmVdeqfeYUj/LTVJ3l0YeliHqjne4GzH3GDbfegG/+H/5Z/PEf7eH5nz2P7377T3H50lV84Uufx9333Izz50/how8uZxuHK1euwJXmL6WwuofQCcUdu+Mdem+jp1Dv2N/u4YnPPs6mjK1jgo9UhbI1DDaifwkyiKLNHOnAWJcT7J3+gQXb4Cjd1BdFPk1LPdUtnvvhz9DmY9gUlqfDesevfekLOHOwj8N2nA0ba9hkdz3rkQKK41CyClM+qUbqXX7EDSGFZHClTt0Y06J/ldc/VUDy4IMP4o477sDv/d7vJQC5fPkyvvOd7+Df+rf+LQDA1772NVy8eBE/+MEP8OUvfxkA8L/+r/8reu/46le/+pf6vmI+ZlNEpA9DoNmIhgrAqMEMJoPqXXk98CBOlTn3kddmagcA4I6psAnTatgtbCoswy1F5VH0RG3xrL8ffUCQzrl742wOMRHszioqvAw1dTp7aF+X2KwS1VnhJrDhYGO+CktfuQmroHS1AB4SJQIAGkoOl5PT6aOxFasOGNk7DLvW0ZcOw8lx2i42Jg5LsFPxSlFbsAo28skUUTG9M4avSafiNAJE3itTn+wTQO2J4gpbCWz17FwZneJAuI50vCUcHsmz5gOcKK9EgSE6KjjRM2bOWLxv9WpqnFemKcuDKzAEnzb6x3BOjJ776pM8ItNoYrRq2tYaHX+tFZvtBuIwQEaJO3q72WA7bZDpRTcsy0pLYoYWjQxW4MP0nODIuRix2eN3exVIUmVEpv9RQluL7gXrIYhmBuvRJMph6DmpmU+0xDHLve4omJdOEFnU0EkXEtU6PCOW1x2Yu9g6kiNYKpmTcD0LnSVov66CBdP+o+McgD7e691RlC8fnZ0HCzAcDu+fk4wnvPDC83j9zTew3d/D7vgYiy948dWX8czzz7M1eSmY26J1ZaC12W6ZMugdV69dwbXrV/jEE7QYgILzZ8/innvuw+efegp33HEHtntb6pKcWrFRLRPDHSPdxpJMMo8DPMaaeAkwFojW1cLcYB7N5aJ3jOHjjy6OiegetH5spboCIi1Lrcd7Ze9UAo0IVAKYhz1ScOdxlcWwNJ3s7Mkk1hJAbw0Hpw7w9b/6V7G32cMzP34OP/nxC7h+dB1PfeFzOHf+ND547wPUUjHvFrzx9ut08KUk4OvdsRwfoS8NE9QoTHZ7Wwvuvece3P/4w5jVb2YqBYsAWDTBwxqYdwOssay4ksML5p0jJWh3+aiCxbL1AcnihcFfOSom7K4t+NnzL8FLBcoODo7y2N8/hcc/+xh622WFGbvOuuRMFLVS4E6mJyxTgqE4Z8ZbaC2GQ5bVSVq1sgfgreWk81/2+ksDkqtXr+Kll17KP7/66qv44Q9/iJtuugn33Xcf/u1/+9/Gf/wf/8d49NFHs+z3rrvuwr/4L/6LAIDHH38cf/Nv/k38m//mv4n/8r/8LzHPM/7e3/t7+O3f/u2/VIUNwAc9mWW9/rI0Dm+bak7WDaFqOtdwtIr6Qh8x1ZKOuohB8YjAjY4uIlsgGuCockWRUrWCaZqIoFvP3HIRDc9ZDJ2UcKUqfrBfBFMqPoPm8uUmDWMbryGUjM0T7w3w4hK/Ct27Fiw2l94fQk0CN0NUvMTgt9RRQL8EJBNlcR0CIzGyvEvdWGIiqlA3MBzVmsVC3Gc4EPSkDAEO8zIJcc1XGVkzNhATGIGcRijErawdnVJRDk1YJSDtiOjbEYPUgImAKlorBlhcAdRi2QidhjVAUBxkVSrFtUb0NRxnz+cQolQrnIbsacBoFCmq1B6rE453nN8z946Nqk5KgFEr6EtHlfHvRu2Fl8oWM1GRMx4n71HOes2OxN6DHCTTEiEoHMk5Vrnx47yDQsrGdfEez8W1bumd+H8nIidLh5VntccgRv7+vMzYbvewLIt0WJbnj09jGE/dMK1Dd1jRA+kEwFWgwySCJRPiEkoOlpL/O9CSCZRFBFwy3aS8cSq2ucZ1qvjww4v4/vd/hFq3aG1GmQr+6Pt/gkuXr+DKtSvY7m/gx9SdRWdgA3DL7bfg2vXrOLp+pO/keWozRwjcfvsdeOSRh/HAA/fjtltvRZ0qlmXGfHwsILROURHVWy1q7hUgCp9gmMd6wgxeQhg/zqyFTegKjpzi9etXr2HvYH/onUZ7UnWlJSgd05OHDWkR6ZdRzove0/YQ0K9sh9V8vusqorBRtBdisb1h2qt4+umnUOs+fvrTH+PFF97E9eMjtHkGysL9mkAyjjpT/b03nNo7wI133Ixz587DJpZhc+9XFDMc9QUHGvQpQ5a+wwSMvQxbPU0bPhIrGciNVKelXQvGhPt2OP5hbwJ4E3C+9srLuHjpI5QNlL4CvBvuu+d+nL/5FszSUHaTODtUOgFIYxZaUoliUDtU1dpHUK7g0mFpM4TD1Y2ZQcMJ5/ULXn9pQPL9738f3/jGN/LPoe34V//VfxX/1X/1X+Hf/Xf/XVy7dg1/9+/+XVy8eBFf//rX8bu/+7vZgwQA/tv/9r/F3/t7fw9//a//dZRS8K/8K/8K/sE/+Ad/2UthLtJi3/JhLjPb/BZIvS1nPS8xLHnMyiDpIQTsnX0WvI/qF6UKClYDzno0LIoNEN31ZOTZHQfNgRoH3UN8yNSBoYxx0z0cQDg7QzPO34k0DrQZ6GRNTdF08GRUQ/RGKl4VLQBLtTSIKZTynNvDZm6uskDANZgMCAA01WlUHVk4eebCXYYoO38iKgwElIIGhGUUNESkUJoromP+91SrSst4ugJohcM5OdhNdG2Tbkjza3jvoQOxbH3M62sCCaYqiaaUHhsW8TkEBe7oM0W9NelUgU9Qp2NQFUXQ8unEwtGtrjcNsIBuOPrOe2jLomiTzImrPBCdkePe3p5AGtd5XhYOMNT3duVro3vurjW4ARsr8MpIl/6A4LGaEmrBAggdFYbROleBMijc4zIOTcVIjcQoBieIE74x5cbDQlk4QRsgpTcyCIgV0XWY9ouB4joDm1bxOQ+xp39ifWPXnagUGRkngRV+R44E8AbrhRpwlTOaWIX4bIQmwAVN8ottcFtWNKBQzkcpyXnX8NOfPIP333sf3oF5d4wyAS+89MJg0uaGeVkoQK4F3jo2ZcI0VSxthqOh7YC+OPb2z+Phz9yPxx//DO65606cPnWQ69baMnqDFFHt6TS09GJuc/1cYZYVlafSgTaPsRqgDmDpaacMZTxfM/Q+o7eGebfDufPn87ygJ4fFM9gHuxYMVYcqiRycg6KgcVSSuNKmPtJHxYBICbsAfzh+OejYQ9zP7F8yHVQ8/aXHcersHr7/3R/grTc+wGYDnQ8BX+03h6PPC3oB7rjjTjzy4COoVa0BKjvgWuEzn+cFl65cx97NN9IOI66PAWyVI+9i1piiIXsZ5MEIWiDZAAOovgqE0BWcmQoPwkYWMla+AD/76fOoYAffJnC83VQ89sSjmPaYCTAacloiD1krR6iEdeouAIgYOzFYZpqMSAeZ+n0a2gJY72KeHeYddaqY60hJ/aLXXxqQ/OZv/uaJyPaTLzPD3//7fx9//+///b/wPTfddNNfugnaP+nV3bFrcwQ9pLYK2+VuKqPcNCCgVLKUosFyIcTsqgoh0nWns+7LzKhfC7ksFI6xYZQctA0NBgDEXJHdvEPvB3AnsKhGA2NeYGrBa00P2EoyCIJLdGwoYCdWF2NAIxc5fK22gJGztLmU7A+QtLQ2OAVsE0tBg9UoBdOGlF3rCze5ct3qEZz9INw7xbJubAQWG7SGAJhXwxr4YKOaxhqYmn+tNAjASiAYT0gOSo6cKJ1PzjuwtK7IS88PXZpPOkzoM0M7DiiC13M5MXoeYMRemP050SxNKztl9B7GlM7CQFq19YbSIzKTWFjPI6xGahIEnHnvEeXQYVqFGrBVwLYER+bcN3o/RWhcjWoFm2nSOo00BMvgiXHJolbeV6m8nugNE8/KpSWxSJ1lmVOCV4o8peLHYPQiYl6DzAB7lgjA02hF6jSeKxyDxvUwcBigIimcns+kVHZjXpaZ5zrAmI8GZwlUZGSz9DDAlsBoAJOEzXLY3rt2j/ZmpgyMoAU9nTls6DLGDpb2AQ4UdYzuBDdH145wuDuCY0GZgGmPjmpZFpb3emNZuCsV5cAH77zL72mGg4Mz+NznnsKTn3sct996C9w7O22KCSIxWVIcnZo1jP0e12wWNuckw2pajGCOByMSibUYlzEAHVsJTGRudjPOHBzA3FPTEOxYnvtKJ9ydQKQWDpAzgK0YbAhZOwKMIK+HzcEofAU8wYlOWlYg9k6HyJUoaAgxr+Gzn3kE+9s9fPuPvo8rVy+yKsxmmFE0zu3r2Nur+NxTT+HM2bMaVUWWMlKOZZpQS8c0bbG0BYsY3CJBeJSlR6AHBa9DKFvyumOhmxpjAmGPXMNhbaD2+KVOINJ7x8Yq3nv/Q7zx1tvAxgn0pC258YYbcd8D9+r75XdoZgRYO/9xgqGAG4YotVbQqgDRs6oywnyN8kDL+83CARjWGplf9PpUVNn8ha+orYTQvRUJIDsfRkEenpq9MVYCNOVAawhce8/a+95p1KepivKjuItt6ruAjWE3R6WOIfVrjc5hqjQs0Y3Q8nCHil1QV4ZxTYeWUViXhtbT+I40BZ2aDnBnJAcZlnFAw5kEoU1xlbqYS9HOHhXcSNp8J9IQGoCWtKaWMJyQLIh3OTVR9aUwTx0sguv6zYzDngx5fxai11Ip1tIxMK2RFxFKiRNsVF645/1GmgmKNFgiHEBoTWHrWUjLse4tUWR4uZ8WViMY769Z9AXoCTQKfOh+FDFohXgdAsaZEkFYawcwoTsP7RBVukC2IqjKYWLbukWk/0aVAY3s0ilPrZU5Z3P13ZH4O6oRSo2GbNFzh2dko8g6tBMR2wqh5NOgQdVdJ1MXDofsQjBJi7dPukV9tq+w6BA0R7VBsiACG0tfULqARgP60hBN8qJsOM5KPlmJg+Pzxl721eGwBB+2ei6RMgv7n/vFdDaDxubBG2enFJReMup175g2E5747GfxvT/+E+xKwd6ps6ymMebWex8pPqYCKxZf0IvpnoE7br0HX/v61/DwIw+zO+0yq1Sd1r/3vuq5E5V/ugc5tez069yjkRoLgMJurzVBXAYK+Yz5GIuHrkRA3AHrbGOPhQLPYJLH57D1e1TuQGcxxeNia7r2aaQgo2CAlXEyLcR6aqXQE/zmNcJzlpSDe2SJoBGqCEHHvQ/cjYINfvCDH+D9Dy6g1AV1UzhSgIpe3HPbbbjx/Fkct4XrWibUamhKIZfieQ52u90KfEUvG1fj6hF8mbM7M4GrtEgIBhJ5dtYvEirBDNaEwASGsgfmePb5F3DpyhXYJio9DdY77rvnbtxy/iyWeYjms2S7BDuDTAkBwfLoGclvMiUrwK2APYeuykfRdrkALOfj+PL/p9bx/3t6OSqg9tIhgoS7tJ5dQkxgUGccIBTVLTGXItBwTN0tpQKTyeg3iX94QEpRq2PlQ4seWCDOqRg2U0njUkpFazvmGi36CdiIsJDHPoWu1HYYc9560HHHSkTQebshbhsYqZOhNBwK/cztAUndR0oojFCAC08UHO+XQS8giCtBo44KlQTtLUBdYYRvJpEmnXePw2ZBddNYAUOv0iLKBQQOg8KXen4N1LBkzwv1weU1y5Os8+fseLielaH9Ir1K/L6tbj70RzE9NkGaR7Ci6L2UlQMLzcRqr0pzVOLw9xDojZ4icENRK3imTHpe9zRN0pM0rRf725De9U8wDHrIBlQ1/ViDgmCJAsBqK2bp5SjjJECzcjJFQwdlvJlgIDJ1Z6hGHYO3oNCR7KEDiLbb0ajPANK8Aj5BXdeVlsQcWOYFXaLhaEQX6ZR4jesUeApIG9509cySGcgIcNx23Cevdz1cAePcrqJ+d2TFhWHFDuj+a6nYTFvY4RHuvONOHC6HuHj1I8y7HTpYyeUd2ExbXVDDNE04Plpw9z334Zt/45/HbXfcDveO4+Md1U9xLrVXM6UZoC734ritiHhdtshgOTk2ggoZr5y7lOsE2ogqm4fsbcNtsDs8xrxbcHBwmkUEQflHWlDX0HzYYz5DnFhPdwUfqyCDA+GUYmiNmiV36sHgqSVr/6R+O/HsigHFaaPg6D7jvgduh+Pz+INvXcLhvGPgNW2xd3DAzz13GovWK2zfIGy4LoVNitAaB1sasGL4pMHRPoLsX3cCWwPteIKRGmyvZALo+TvB4sE89YluyNTg9auHeO3V15RqKaog7DjYVjz5xGfVzVx2rS9wr2LSkExJdiA2pnUdkA4sbGRcC9/XJMIOZrLWyrRSi+fQGahnA7hf/Cq//C3/+32NXDYjwSYha3HkyPaqMlaK6UhLtaZqGihPaE1Ilz9ffIFbg1Vu+OYNUVo11YpNrUnFleIo1eFocKceY1Mq9SPOSA7NULwiZhMAgUTpRolk9fvW4X0B+o75ZAHrKEX11hB9LBw67OoyNYBJOWE04cjUjf4AlM5/Au06D3EpG5htAFQqsGVxulI2vM5wivzMKjFmnQJEca1iuB1CzwJF51kujGSJ4lmG83OMaNbbAqjB3DpqK7Xq/Ryy537CrQAIrYpmciQY0e8UAiZM6rRqlg2PijQ8rgi2B2UW9byIag4tkRg4XheFbN0XNF/GvYEgIGr6TSCXVQKknz2eIcjEAQ29R4dWMXQ1RGgcYsfv9xNGvRYwfxvivgRnBd5tDAKkhaPRz0h4BV9s3Fd8Bptv8bdi1kUX8Iz3m5XBVEGpoihX7o7WHBwuiOwnxG7iXQyL61x0vtc1B0TBgMelZXAxnnnRGkbvmbW98NU9GkCBqoy6e19R6QGU2Wiu63cpYPbcv7odOVUX2l9kLxiJW284e/4sfuPrX8c9996NB+67Fz7HoDqmY+A8b9N2iyoxaqkF+wdn8bf+hb+Du++9i7aiWDaWG6HMSInyvhfaEESTROmdQJtUgtXQUL8U766CpAjO4s/CpojGe6vEFs9WrVi6Y25ODR1YVdV7aMIAl1g/hsyNfwYQgZ6pg/N04E1dfkPnIt2GgFDViI7uhh4UaicrWjCBqR0GZsXCDjpiQrz7gt526G1G3W7QC3Dt8Co+/vgDfPzRh7hyfIjjtqj6jtffvMvONczLMUuAizope8emkKnns/IMjlY4Zthm0KZkqrEPIM0YpSiAZEWndzKEIW7uCgy2e3t4/4338e7b7xKKWWgiG+684xbcc9/dOGrRIYs+wKP3lbQ4rc1Y2qwghQwHu2H7qj2DmGunJi2ebdpb3VOR3enah2a/GiD5VDMkBcoR2mpDu6JQ52jqWgtzlMa2ud4Z1dFYVhrElcqYQJpWJpxilE7GmPQYTU9WpGkDsF02L6KTNo88vIUQLA4RBWFd5YgpHPUoGxUijUZpCCNK48NJxh21qMW7oqEukW12jjRDSSduiAoaXovhxAmR8/BuKjkLI8/UlAHqutk1An50uezuMM03YKOuLodkKTKLdYxlhkWeNycwJANiRVqIyGmv+p1EpDtNIQqLnKwcdlcEbaacb+wJ5QcEHggMpHkp6lWTzEBBYHXGBDU/P+VuEdbZiCCDeYhW50GtDtEoXTNAwfA8L6iF/VRDFO0ea0OjQNYk0l1ci6V1Tv5tLr2JnH6RqFFOlkx99FNgZJhmwVeAKqJKaWksNqMiwJOpO+3DEzS5S4xL41tMwmfIgXXP/cXvHqmDYBEd4xlK542lNbXhdp4Fgbd5nglqg/WQpkshvq6tIGv0w1WvovSIvMNZZw8SXwHeFX3NNsLp8nWutZCOvH/Teq71LEtnL5knv/AkHnjsfnz07nt49gc/5Oc0nYlKbVuZeH729/cw1S0+89hncMftN+J42fG7pSWwUoiXWCubYJrHxfL5hHidnWHjcvkQswOz1ruvgEEwF2ZyfrI9rLghgIxzEOvWDehl6LHSNsXPJRpdV7IUXSfH3g8tTjRZZDVOHQystnuC5xBzrr2ic9/BmLAr2s4tRP0p8qWdv3L5khqNiQVwSPPnOLp+HdNUFfDOmMoGu3mGlQ128w7zPONaY4XnZtqgdAUDxiC4hyYw10Al63Wcv/XeL0Z/QTunakNtw1KnMBACBvFADWYT/uynL+FoaaibAmuaR+UVT/7aF1EPtliOZmp9aLRG4YHEwAC7Oxcxp9xenKHUWgQ+KiCP56IzFieDPcFk6ps6lNPp4Vd5faoBiXeHLz3rtQGmPXjrleWzi8NqB1Aw1a0M1zCeMWEWACZVqtChuFrnylECiE8GygAsQYEqGg2q+fjwCPsHe6rW6Sn+jFbfcSY5oE3JpTDkRDsRMiJafEN/VcQK9cDRNjYYUbUiQKn+eSAIXlo03lJ56Qh/pO4OA8vEPMYYdTIhLSTYQHimZB+IfYpy2XIASbnnLw1A0JXX1voHRR5RUnYzlfEPqpBGpQ6DGpGVbt5MgtkSeWlg6WKWdNn0JdFmfhyD6NzbQYc3mCz5u+JZghsVL+HivADePAXFTOOshhGGyA2GzWYfvR+j+5z0OY27Si87jWkthsnqyDsvZOF6NI3yEG5SvBa9amBVFQ0YTdpiXDGQTcyiSo1RWfydWCTdeZSGtxYNBeMAGqJRUhHw7N2ytJEl55bfH1qnnitm3FvScqGvgAFiLcnKtdbQp4puXWWHpO85E2Tsn9gv/MxPABE5osTiLmCh9bC1k15tc4DPpWovZ+1Esm0gANUaUOfSmF41Q2vx/IHTZ87g5y+/hquHO2DrcphiXuYFx92B3nGwfwqn90/hySceRwH7CYXTiMi6O1Ny6/vMKbRmqraJ9gdxQwGmo5TfRom4++qeI3gY6UdDgBWlea3pvlxggutSJ82M8kYW00HQ3ZY1bCCQUr+kuCeTZm+JdUdJO+2xvvlU4pZW4KOGRsjTrmSrB4+AwsYnGNnQRcUNZJ31o1KwHO6ARsZpXjqWtsO8NFy7dhm7mTqe7o6j64c4d/ocKypbUxEBkzJjCjnG9XlP+xR7MlPKCMaEVxklzeEzbAWIe2dgeumjK3j5lZ+r8GKRLXScv+FGPPTwo9gtQFqlFgABAABJREFUPX2DA7BuAzjG/eb+YhVOU/8Zb6a0kGyiwJCvtF98lkCdVMLsPg46MGzGL3l9qgGJheN1RvHNGxZn1BkrzDWOJx455UqxYm+rUlLT/xsm4T6Inipy6LH5GeyHeDOiDcs8eakF826HU6f2aRA6h8J5Vy2+DJuDlT0xc6d3CiU5GbixHVkXaugOtEGd1UCc2QjMgFLRW0etbDzk6ggWoj3mcskswGs6HB/WSmh4SY1EEVyCAXNrERAOWt+5rtDgsei5Eui9w4TsCVoSOVjQ4vFn5HvozFqmB9JZr6xZ9FeJ9TZjzjtGcfPRSDdjFD4uvcNiHI0+u+f9I6+fTiWaEomFUbRCsLCsGJBIL/F7CI4d22ic5Fhpenhwm9KFm03BvDDd1/pa9BVOJsppBwW6mTbM065cRzyTsAPsYAy4s3g1ms3B2PW2INJELUFDmuju64/N/+o9Ikj9jcvBd486H1bteMpt6ISktdLjTWgWhjg0JiOVZukMYthi7IlwJA5HmVg1tHhDjTJ9135egY5Yk3VVQfww1jSqb1w/s9XS8nEovSPgH0CZaR6xI7lakYYqMLECpn3Ifzreefd9HGFCsehouwALXfDSHVtscOuNt+HJzz+F2267A8vSUgeUjBvo1Dyak8HyPqwMq8agprCSih5Ze9cwWYj5m0B6pG0goSufSVkhflszXrEXwKAkKwBzvfg50cjOfQwaJP3f+JtCo+yBwfYMTeCDMaLBvCoIdOQDiuv0WJtopMbl6WIqRuAWIIYNwaLp2ma7D8eEumJ03Kjnm5cZS9vh+PgIx3Pn9ZaCK9eu4eqVK9gdHsKmCmvAI/c9iGma0DT0MSv/4nowKgizmquS6VIRHEytCJLR7YtAysqurqoKzBlov/TCMzg+vIKydSwaEuHuuPvuO3H64BTm1sDhkCW1lYPdYlPFxA/c5qsgehyFuApVjGi/DxvYs40FgLKRfxmp9l/2+pQDEiE2HetQLrtTFxJUdhzOmCXTfZ0TUwdIA9BHpMphRXoAzdHUapd0lAVsZRSyNLRZmN47+/WUjoaWeXSOoInoW/qVoOF1yKzKtAcFr3wtEI4iDKGp86TLaVcs85xqdYIJyzLOUD5bnZiekuYmtADhEHj9oHZE0XQ1oCh6qMBQVceSCckHh7QegAVAQkwg4E18YWz8WqVnEHAwI2gLWpUiwdFVNaLaYqMSo/clxbsjbgqP5GlcIzXXMwmvhnk1IrrYWaPxWY+W+FAq0FSy2Fhfn9GOFUy1oNQNB/ktQC+ejjL6lbD5kmM3H8ksRNfbIlCLrLhhK2/PyLC3jqnQyW03fEbsGzAcHqTHmGrFvMyoxmdYTZ1SPRwFCCZs5eg9oIn+HXZ/mlLJj5h9kpGqCYCsIjAxetTTlIxQI+qLtFspQF/GfhljD2JTDraS1DH3kv8T2DvaA12PUQcUqcwytl3iX+ROib0SQGSsQQa2RkfQ8qtGrh8AFlWKJNbhgcjUTQp3Dbh29RrefOt1lMK+MzHHilX2hmXueOKRR/G3//bfxnR6i2VZVCFCe0NNVUNRKjrOQQChANiRXmaFHZ8X0wiFx1BrXIulcJtdZx1WDBWryDcE/KKieO5YNeM6YzYRgBUYNmqVEGnQAPwUuCM1b6Myjp2EY18hnZj2QykMkoZVGeX5xTAprOwBTjQQNFJGFEpXFgpYZ1sHdA4+7Qv2tnuc9t7HhOpIk1w9PMa7739EdqAXXL50FZcvX4FVMrQffvghfLfDvXffg3vvupv7uzLQqZBAW2erJAAf9sUl0vZsZWDwpQOT5VkheFHfqGT1wl4Z2m7Bj/70h+gTUAoDvd4c+wcHeOqpp9FdHXKVig57VoNN8wi6w2YG4+2x3XmuOnVto3pt0B65bt55LyUq8GQvbZzTX/T6VAOSJtofvUkLADEbQsYeB54HMSn4ZaZuo4TjhjqZKpUgZ5sNhsB8Pp3liHbXB43NtVQxAZZJZamUF/XQSG4ZoWrPhmsBksow6Jn3BQgQIKeaAUKaU7j6hUQnvdhbSZ8ZwFbFYGoBQ1tCZMtcYFGfDbIiAwSlsegc6R7NsOTKKOyKniTw/E7XXBNHAZQbJd0o8OW8oN6Hcj46jvKTl+EcHfz7FYCKQ9RbCB1JVSeVvqI+CV4cUxm57+4nwV6CHIGgnEdhlswGtQxYRWO2ctDI55z6FoTbJKjqxXA0z7DQJXTOsAmc5LDUH8FkOOHYbraMaJvKRBERHZ9fVbVU7IkiZggR+QqMUNDKqDnWJzQTnApc8n7WJd622r/Chjpf8Ya0SkwJagpzV+mptWC1LA117LHgLiNCj/J1d6YrEOXLYOWTbTzTTVX71TBA1YK1qiDoZYK9ugLfGLeU6TQCjiH2zCMvZsHjXg18Fgm4w5HGtwKoVeeDDa0+fP9jXLx4SXOHmI6Kte69Y7PZwxd+/UuYzmyxzMf52WncOy/adfOK2cXS6Doi8s39nwcACEH1as8jf2/cZ9qSZSTYUmNy4vf0/DzmUvGMRinzYF9FzXRVIHmIgaOTdlyixPIFqiBk4AB9rsIgRIdd6KcFYqhj/6zvLBkVE/jn7mAztYbzN5/HXffcgXcvvIPeGrabDWxTcLg7wm434823LuDOO+/ExY8+xgfvvo/NtMF99z8At4LLl64BXvH4Zx/H2TOnMPcZZkXBz7BJHWLDAdYTWKR11Z8jmCAYYiRP+ot4fMGQmCbxdofZhDdffgdXP7yIaWI/qgDV9919N+65/c7UKLqfZGla65kuXuRzzKrOds/fcbjAZQScBHi1liGOx8p2F+SzD1Bla3r7F7w+1YCEiwXAgAYa5FprtvEOzYObQxlddrOMQ4Qxi4IH3LCsIrh4MW1gdESrkshQaneEFmJBVM2EannabGA9KDLQKcjZR9Ox9f2EMfBe2G+hM9oyj83JHgPsJREVBwYYh8oFdWzuCbTCiHpbTWTkN2KkbMK5R3bQEqxFhYlJsMrIxXT4g4JlI56gb/MQ9a4y4Z4bdsCYiLp6Xk2O5daBKBjg5ISh8TpsqEElyDzojsjrM5qstQLF0JpltOsCN4YOXwbbEaK3yJtHWWwxaQESMI1oMq4jgUApsG6KwtRwTqIwN1ZEUOleo4UFWBlTxDYN5woZ3mJsHsW22h3RFIrZ9ug8yw8LV5OEgLPlekQ6fsI4jFQU6QD9LJrCBcOEqHKJtt9D7Aoo+k0WZAUW9YxDCB6pwArNp4kzMOrXcyXjGbkrtdTkkJ2dI6tFPh5K8VjOqqoeMEd5blttHmmYeMxHp8yTAWGUasYy6JzYSM+MPH4sOKF8nCAP2ir+1RwXL15CmxcO8Yzllh6s9Y57770dd99zJ1rbxcZApKzgIfZcXaeP/7BAaGb5MxNjOvQlgC092ZAAtGttHe/XBqgJzVsArhDbC2yz0ojPvU5MrZgztTmcFYBgo8PmdB9MhovPigAwVliO2t1TSM8ZOBpDYKM0dnTTRtonbXnZ9y7FNW0Ou9kWnD53Bl/9ja/g4/ffZxXltuLt9z7ED37wA3g1fPzRJbKTVrGpBRtjWr9u9rCt+2it4+DgFFABtDDy8ZTUZ4YnTTHJ8C9hm4NwK4bsmeW6PiDs1jhToTPs3fGz536Ga0dHwOYY5k1fXXDffffhzJl97CK48NGl3FYAN1OWWvNSwgbzeXcnm1LrsP/qtZt2MhtLmmltA4gEUP8ESvwLXp9qQAKo0mPlKE18dO+OuqkpCKLPlQE3Lmbsi1pCWibHEaWSnVqNkR920sVyXKuQVnZARrQYrHfWfG+r6D5V1bAEgR+nEr6YTuuiPNcmh8PihgOhwLClWBXB+jSX4lybNSK8IrqyLaI5TeDCkzoNDUCRsjquBcWSaeHVrGIqX/3LHb2aovMOi+FajZ9RajQmgyp0ykkHJyFpVjlIpEmtDPvMtC5q34L5iPWQgCwZFeoxLFE+DwMrDQqWxdUG2dPA524KkFFtGHM5ax7SJRcierFQxBxmtsEw9EsGT4o8l805rwigzaKQrWJZWoraKCrTV5WxN7pSWQQzIzXXmoyQhb6I9Hl1wLxjmXf8jBKCvyiD535zRe8WexJyAlAKICIqDwFzOK0VIAlnnqwSEGJDYKWxILqDqwdJPDNOHRW1HMYNoNPqbM3t0LPr6umTz81BZpIGsulAthbVQUrQY6hlQvyZBUAY/waCVeNKrIEWew5p4KGeS7CaAEFHVJPEJzSMCPWhxx7GG2+/gZdffgnrQZCls//F5z/3FLbbDebdTntETrzJeQfFrmc0gggkCA+molhUy4mR1Z4T0uOZ7Owm7Vizv+FIYlVG2rLLuae9g1G0bxWlskkh29dXeCMrEg3OGJ1HleFoHYBSTgChBBKdvY4miWTZwDC686jgQMEYXE59fbYr3VtvSz4P6Cw765HJYptjuzfhrntYWj3Vim4bbt9qQGu4/NHH2Nvbw6ZWtL6DtxnVt9gWw2FvuH54LZ30AOQA2XIAoACdrkUzuGKFe4DCkro29ABg670ZgVQ0pjNc+fgyXvv5K3CbBUZoR2646Sw+89mH4cWz4gbFUKuYEQV/Ve3j43qBJqnC+N7JJI7OAIHnIeQRLK/X6I5kRlb7EtSW/SqvTzkg4VIucmiLDiNKpWBvXnImTIwvd3D4XmttGKB04EWCQRkcjFa5BkNHQ5YXhsMrFX3mRF0rFXXDNuxmMiZLYz6w0nkyGxytp2vGAmPU9HigOTXHkCWlEW1Fe2QAqJjUFVbXdCIiHKBphFQCCyZBaI/OhjHLhOe6pHPC6CmS32vIXKJHMzPmdh0hhpWjik5+8Mz9AgRXA4yAzyeAVG74DhRGk3OPnh4FQEM0XMoOr5bfqoMyjhXr93nQs6oFLDGmcSVLNgiaSNuUARYro7PuLVkg7qmaYMF9gTdFokYDkK2wgVUlhkuMR8dI4ZuiR+6CBGnURBmaGeZlwflqWNwx94bqW4Q2J3qcdIGbQa2rRb4P7U4cn5gsDFiWjQYL8Ekb4u7wSs1IHAwFQKgFSekz9SZGCB2cEYIEA1kKHk9Hz66vDFlUvCy9w6bKclhwhMNa1GmxbFo/fi73ds6Zsoj/ZNbDTmCFFVfpyThnUWEyGMThmOO5pOYmnISiwuik672jeEwrBrZ7G9x8y0147/3TODo6xPG84z7tHbfccjMeuP9+HC/se1EcbJq19NwDmaJDyBNPhAn5TGJtK5SSFsvGM6i0r5scPReiQGL+2COBcgyZBs4g0B1uUa7OOTJlqpmCYGdqABrHAWg0Rw9mQpHOyAgh0kFxigcoSgwlJsGiEbTOlKfOiOdHtkZsYTEWPMCNLSCWNkT77rprT8DWW8O5U6c4B8otqzj7vGCzmTAvDa0dY7M5g/2t4fq1jiuXL6MttAUFGOWusUEN8ifU/riqtqKkOlrFZ4o5zoHbiXuKAMu9YCoT3vj5W/j4w4+YslP79+4LHnj0Htx6x82cmK2hoQYkI8UnKT/hntrAWPIO+q/YClOpYhDjLFiemVq0v+NMJyvYM7hY2oxf5fWrKU3+d/pyzOjYYaS2A3QwZdKXhQ5IoklGAaT2VbQiH2DJbri63BVNcAwxYRi6mI0QZauskKmiLbWtzVCmCQKlYO8OMTMyjmZBeYf184x8XQAkREUGrA5p3jz/xi2dEA+CAT6mv8agubBQvG51+YTQdgAFMTYoRqGnqeeJ89B0xCkGUBxuTSBNTiCqCTrUk2F0RV09NEaG3jiTJNiM/L+g0EuWwEUkZRaR6HAuSRXCkv7OHDviuYr5wIj3yEw53DoiQmdaiS2dHD0dDCyGlQ0Hly89rzDyHRSaLt7QvAvUhINk7rdaUd4/qkeG8TWl48J5Z5orgKhVNPXF6V4EuqKSgs2pvBisMgJuGp5YTKkgpwHnuRgsmfeukfarPZn1gBipKUU9vUAlO/wn88UIY8RrjZKXUGeUNLQY0hOd3UgRjJw/QL0AzzMKYJOxr4/2aQxujFdR6saBrFyIwCXPQJaZ/sUvt/U/pnQoGYHeEzsOHJPBQheobYroV9dWK957/z0svuD+hx/ArXfcjltuvw3TZoJ7wb333o/z588PgKizsPgqEew+hKsJRMaXhHCfcQADjaTL5cADeOZ9FWq6QoxoUgFHq/lgzbJY0dV0izJtdHQs0qbUacLh0THtYAljEeeUQcbcG5be2aTLxvJ1Mdl8NFp8nQGEbYaxYhaWtsAFUjKlpFR22DmmJWl3UGnDITvOYsWwLUNXd2Zvj5N7+7ChRd/tDlw5vEbmo7Jb+JXLV4HFESnhbmr61mIzyUay/A3uQGuqzuwlgzt0R180jdc9WymE4XUvYG8T2oHnXnwFx62h1VHGXeqEx5/8IppNWOiixj6G/JsNkEI/MvZR/qfaXlDQTq1TNh3lkrOBn/RQFoxX6n5oQzjT7OQ5/Yten2qGhH7Rs2Qy89GypaZKgnC80aSoNQ6DghxgIGN+SGJAxERGGnZ2PWTTsKYom4ahbAy9MQJ3BwpqlsuGPawYjEbENwFKqmZQDCGyohLghOEMUBr3EgZpWRY5eX1A4bW75zcxGmpLGvzM28qweeQolVLKCFCRVHhUFwWLWDMZhSn/Mz0sgVmhGr34iGxJ4YlGDhDhlsLeSBOYjAXUiM1k0HgQBnUYkWIsVQA4bgReh0FN19ZVGaj6HR+RDFyl1xv03ZxN4CLcMVQezpS1rNFJrK2esq+U8RF5qPFd/p6R0u/SWEzFMBUNeOxjL5gZNnUSS9CxmYo6bkqA7MBaANtAxzNtKYStpaK3WYJCfn8x0fRKC5QSUb+WTmsY6UkDqfF1ioK7md9o2j/W5EDgWDrToQla8cl8s+szB7Bcp0cAZxv6SL9BGoZcvtCajGfEv6dz6BD4sdV1d8CtSwCvtYgySx+fEumtWJC0FTau0eA69wFEeoK2dYRfCiPjd99/j421zHDuhnM4OHWAM2fP4OP3L+K+++6jy9LkZ/jY4z2qSkwVEeqZBDkFg2XPHJoABTYw9leKs2lD+zNy/OOIIx39J21PfP9KPBtL0zwZwVIM146uM9UhwLteBxMj16QLQoJkpKPuAJau+zIbZcZhB0RjBrhNtK/XACijmV30PoKTycFuQaScDAzUmhiUIme8PdjDtWtXVSlYsMCxOIBSuXfqBJu2WLDB5SuH2LUFe3vTuCRdTPSNQuX1dmsCXuxgXWsd95h2hteSmDNBiWc10dXLl/DKi6/T1qMn43zbnXfi/gcewG63032LAgP1TtGnBtotwWrHicp1TAFV2Ak2Ae0Gpb1N7FQ/cabdqX/MCqEVK/PLXp9uhkQ50ITvbqGFHEJGOBtDVpqUUtUyvNBJrSr2aZig1vMeYkaxJWViVCoDCxkA+d08D/yMKZF0RFOhc4gWz4xaNSNHfw6kXosNgeMqNdPFVvCfiPIaLKi6viD6Z/TesLQF2RzLHdGTAAaNfJdDL4rKK5Iyp3EQBS3NRykFtbKdPKMWGQcd7FJqAqE4WGEEsFrlrqiBeU3J6WEwm8Ahduo9AfbRgNYoepIkUIl1jxbIZvp9ibfCuThSmAmLlI9lJEBbWOAIxqEIDRra4nDOQYN1Pt0ATxkYr8Fdhs4s421NIrtuJxyMK9plirCiic2z7hxE1dhyvDcNLdN39dbHHloB0y7d1LTZAAA22y1ad8y0oNRTdMiYK8rnIaK+pkwCbQLXrvVLQzgcVUxvFhKgc1YuugNo5ln+G4wFK9agVMYQ3oYlTIMV5yjSAtqLvALpKXpUlsgpFj4zs4qOwrJfDE3Bn0+9DEMLANneWzuO/xZQ884U6/pnKnnNxn2qxuttRPjrcQYwNgu8ePkSLl68mNUJ1DYw1Xf23GncfNON6MvCZlu9ofmcQYevpnzHczeBDu57OTCsGaLVkD1TxcdY4vwsTwbhpDvIR2Lr7wzmMjZkBDwEtNvtBh98+AF/6MEkK+UkcEIyVmcaQDAaa6fFOIXMEFla7a3UJ8UeiGvxEzaODPdgGrFeuwp1M47oP37GEunFydxs9rc8A6ZuyuRU0LHFbtex2y04c/YMFu+4dnyIa7vjXGBzYLKqTswlz0GVfWu9EWNUQzNXS/2BP+Kai3VU094zpphrrdjfO4Wf/vQ5HB0dkZXxOffd0089jc1mQw1K+hH+wxZGYYMGuM5V79rb3YHWEI3rzMjw9QhoO9hluBUUr6OtfaddZ+m7zqd3bE7GbX/h69PNkFiFlZoj4Dk9WZi3TugW0UpJ1S/gGq6k3xcIIQ06+ms4aIyDhi4SXplBLcdVPVBIzZVqqF5V2eGwMqF15yyTMii5GE9EDUHQ1H0E6XAZBkemQPIwFwmnZAQ6aew8cwAR+LzAqnqMgA7R5PxCcOreYNMQnUUzrZyZo2ZtwYqUOhBwlJHFOLoICQIXQpFiR3w+0nHwGgcgMAPBG4A6TWJkKOyMl7vxM+HqvyJ0LyPEdImMriKtLAOMdekS98r4cQOVcD2MdD32DxSFjMoQByP/WgspbgUdYTjDwLpjlB3rM+GOZj11QhaW2CMyMUUuimJ8TcZzDkQO1wudRl01lBJDWEi5MQ++NPTmYkcmDdUSEGHwyignAGUYpUxfBmAbaz0eCO+J7FZfVX7o2VikEwJsYzxrufUAlREZf9JJRtQ8gb02SgARL9HfK6+rmzpTm0ThvQg6sKrMda0nbGLcLuLZ9bzfsCGu82P5nEbJJBAdOANBRfl+SZ1EAlYB5ffe+wAdlk61Od837xbceeeduPnmm7DbHUcYq/tTisTXTILWzKKzhGVJKX8pnqmNarxYdwyNyRpgwplGRTwvx4mBaGGb4EqX9LFH+fcNtWxw6tQedrvjBMkOSNuspnpx2J1ajbjJPKmm5mYaZBfMcrJSqgAJASUCuNpIC9G+Atlt2Mf35h6IPR9BFYZOz8FU27Sd0LzBms74VFE2G7Tdgj4D3h3bLUHL0dJwtFvI3DalhcoAbuspusF+jECWbB6XIGyEAlGtxzhPFMTOxzOee/Z5YGrotuiaDedOn8aj9z+AZbfjHu5DP+RiYYpqxIPByB1ta+bWkP2fYg1jr0CMTFPvGv1O2lL1DsriSKcw9ld5faoBSdLLSSFIPVxKyMEHmquWzW3cqLB27/A4yBnFucZTA4BnKSBZhWHc0Fz6iZKRUq0Vizd0Y8TYeofbpM+hmatGxXhrjYbWTJNBeUrp+KPZleja3jEelcRzQed1OfoU+FH7MFU1C5JMjRFBTzox1qwHE5JrqnU1HQAzDTdbUEqow6PFskDOivYd0T8wFZdDUPQjNsKKDHnv6CpVdOe0TIsGFyeQO48i/Z+qEupoyV4QHjHhBNNOrtSUObxTKd7j3swotgwNRZzD8bhZ4dMjL0zDwKGJAoig1iYlu10KPY8mXycjzsijWhhCVXblFjYQaBR18lUnTy5VS8X9KAcdEW8yCqrUQQc2lS2j5nnWmehpWFSYwKgmHC8MOdzQV4AvovF1BJsABqKkk3I5URUWTGATuC5qWqWDC9dQwFIoVKz5+bzHWg3biWPmizugrqUleqX0LjCKVXgZgFSgQdUN8ePyyXsJOt2QwtoAirrFXIdwC6E2QI89XeUgO1qn+SlWyHC5y65oQKUTWSzO/jPHyw4PP/RIsp+2oso/udZJwQic8JgSrLWVCJu+nc9v6a7uzWwKSAflSI2Q1tu75/wspqZ7gsP83txDUnyZ5SJ477jlpptw4f13ga5S7WD3nHu0izJmRdkQ/+Z+IQLjvugLZqVu6jQeoGPs1/U+S0Y3Ar78TMBQxBiPM8gzPtLXffX7c2+wqeLg7D6mqWKz3WCaDKVsMC9X0JaGZVn499XQ52McH16D+S1aGV3l+hmaDTZJAQzWzxY4wZgX48iLoqAhgqPqwHMvvIL3L3wAlAZ2vHUUq3jokYdw4y03jrbvzlb+2Zywq72AvpvsZclnYAKFllGTWM3O4Giq0wm2mfdIfxe6IoMqV51ni2Xa+JVen2pAEpMcwyzbREQdACDRrzvQVRhQKCxctFCqYoetyhCjyVkXsq+hCAd00C0PFw1nREsBJsDcuRuaVzZiWqUJrADWY9upDDQpy6Bh2cAHgA4aRaKuGR09sxSemj1+HgdRhXo9aO3154S6/gRNLmNbp0IAAqB7Y4S6AjzUflRGU1akXRpNpMwMLtV1NG0CVsZIUTKvh4hqqAt69uQY4tVVdBVDCk1HRWAnKrV5ZENIqChTkaX+J6PW4ry/EKxN2Y7dARQJCDtad9Q6JfW99GFcyMoN2NHTRK5y8+nIVgYyfx7/QM6wCxjrkXqwIAoElc4pMLR5xrLbYW+zQUwwjZw8gTYBM5I5atnTIVrsOyyNCG999Dnh3gmK3ERb6wB4/KwlEAo2iRUsIwjIOSJmGTFFyinmAIXpKxgRmhvQTQ3jZMALeJRrmTgjxVhSTmZ4bfE8gQW3QByIOAdrBgop4hwghc8lOsfGsMSgoEPNEvn5+DxOV12ZCg8VTkcpG5w7dx7Xj17AZlvh3tCWhnlecPNNt+DmW2/H8bzAIRvmg1aHRM3ZTVNnt3VHKRtAQRSFpCfiDbSF54H/NgEm6QByYw3jFjOJTKxqaARCWBp7mIB5rJa7Y5ln3HbLrXjzzdex7KhXWnqEDXzWvUdAgATJAJJ1rQIEUTgQqbTe2EfHfMo1iecW4Jy2oI1dlNHXqJpEnCMHgv0Nu0UGUsMcW8PBmbO4YzuBAVhD6zN8cUzmcCw4vH4Ft56+FdvimHfHuHr5isSftFmRPgdoG8joj0D5xJaNnaLzYybLaHUEoNL5zXPHT595hmMTysJqIu+YNls88NCDmLYbeJ+53jqvBIbaqwZEO0Fg7Of0PRrHkD4OLtuhZ1fCrg27zjEl0jLJD3pfsLQZDozqrV/y+nQDkqDJA6krwumrznSLJg4qZcgcPdgyuTs1JibAIDcMAJg2G6LmZcGyAKWcjBTDsbWIsKORUDfSyjAsC2mtWqMNr2fHO+SDgyI9OsLWXMy3wcqUYscobWXwpM3SFoyOhTUp3CjNZdluS0ARPS8A0sUslVulCuAnOu9BzpcC4BhyRudQMQSrEfW4M8J3hW8moxJGNOaJRPSLVZQTwtFPRuRrxz7mawDoi1rtjyh2+HYbjhIqe4ShqfIHYnHgFRx3T5foacACCA1gMbac3pu8CKPDmOGT1UXhUGQAXPvVFTWmaC2AiAAQSjkxpTiAWUUhQ9CZ1wUmbDZbMVmMYKidcAE1fm6WYZei1A7XtAvMsjU9++MUGf+TTEgHcu+tUDmGg/RcF+0XRArUUzOSER7is0zrFWB2GGpzwJXmXJYFrTUsS4Obxtd3R1s0dRpUgsWZ4LlysnABBn3AwWgCFU6Uj6Wc+O+4v6j6GPtz/dIDUg7FM/3wifeYwUAtwTtvv41XXn4Z586dxcGpPexNE24+dyOe/OyTiPQBwBRwBFJdQUk003KxKyUchqLwpNudAKj3MtJVEUCJfUgwgEhPrpg4nbMOJIsRzy3s7CdFr1EtaDDs7e3h6PAIh9cPsd3fJkPCnjCV61U82cLOx5Ei9fjcaN5WDOhug9monk49xZQecKeM4oRsxtiVGhs6s1hq2uxpXIs6J3MshGG73eLw8Hrqn+iJG6p17HYsZ58qNSloHdevXtW5B5K+MlDX1DvtJbruVfsqmBKMfkeR3WFQPbQ/7oapbnDhvQ/xztsXxLZLueUNt952Hg8+cp+moBUdKed1lkIAa0zVRkpozWbmc4hhkAJW0e/IoVlsGL42ekMFC87yfaaZOfZWTI2NgOAXvT7dgCQXacmFiwe7jiRQV/M3nJFMkVqbkUW8Th40F+therDNmcvPKM5VvRCRUBeToSilLQ1Y2NgnUjHIsjSCGN2GDkj0R5W561F1shKOIaJKS+CQAjzj9yxxwLqpL4DJdvIkWolNNrCHIfoLhOEdvRoA6WV0yAK5q8EDN2RiGJfD5P3EEKlaJsAiP7wCG3kgPVM+ELjMeUNZH191iJSbVi+VEKmuRXns+1Cz3JdrxzWghEVgQH7E3CiCl6Ppq+uAhdGJfRW0OK+rhdYk1tCks5EjWGVm4QllBuVNIpdDFqPcwRnKZXVApIiqVUxibNgbJpythwUhAJkKsLMUzobBiD4OeYIs9pGpMVacBn5mOKxFDocrXHJPZPv81euTTANgq1TIcPbjHaMiLQJHpvDYZXe32w2WMMoqe9dvjfswgW0zlWiuftalJ+j6bOJ6PscQE2b1GNYM4kkgwsv2XMJ1BYF1MgoVnuyqg2mBebfD888+i+PrR/jw6AilGL759d/EQ488jL39fU5x1of2cLTFMygwIW4P0BEB0OrCrCDBrk2yHya9E1wNruQwIz3BUJwgNtJJiOfEdO1UKiJQS22Mzm1PHQevYVsn+NJxfP0Ie3t7yAGa3tk4zbWXywgMahGQXnravNTPoVDsbYDVkhVlI401ntH6eQNkJVw+ocMlMOW9Rz+hqEYTrodBRQUG7O9tcVkAGBZNOA2bqQoQz4A5Tp/aw/HRVXx48WMgUncOpokhMCvwaALHNC08Y3117riUlmfLoMIHonSYVbzx2ju4cukKClitZNofjz7yKE4fnEbrHRUT4Goe2xtQq2xTQVSPQtdBnymb3R2wmqn0BKMrVocjJ5SKs3gE4W+lkeyOZaH0gSL4lcbpF7w+1YDEhXzZErcq6nWUMNgAvLXMpzGqIBjh86d6frQdt4FeO0uywtzy56OyAAhjDvjCCKNbl2ZD1FYj9TWJ7urSpihIgyunWesQ+oXByc6jQpvRFtp8ZRTjc5yCTUY+w0xndNj7iFR6kxcejZLS6HZg6YzIQhtChzlaAaMa+1Xkd8ugq4GPxcydGoMIgWVesPQZtdZUxi8S2pnHYR2mv9jKGegwnrA/MPgqFVcndcMNOLE+PB6RlmW0bg0S2MZwORodL8OYrV2TuafAz6VmDXV+LVWAjGBpMDPDWdnKaJoPDUPvjaJQ26hfASszpjLB+5x7z8ywLAuiWmM+nrHdbOMTk3HjtlDiahldFN07WlvoxMqqdX+u02roYKJzV4pCEZMxPRIl2kBEyjVFteNcDoifAtW4vgR9/FkJ2r2ygo0PgZtxrf7nnKcB66reE3siZrvEnm8p1uO1VsR59exIapBBPbH7MBzsuKP8d+y/AGzA0DUFiOmNTbgiKi4FePm5l/HOO++jVmCZO2669TY88fmn04ZF0IPCs8N1ZkVVMExSMsVFs1QVruaPJa+NS6Nn24cQ1xBdhcfN9ZWovSt9afn417qtATybonYt/AngfXBwgFoqlpm2r2sInU1Vs76AhNCRd4YDvgxWsXsCntDFmJnSrGR5TYRL60P3EXsp2LmFS8g1iTENAH9RYV7O5tJzj/Lb1mecO3uAdy80Bp3d0UsDfEHHAviCo6OrOD4+xJkzp/Hhhx/io48vYe7cbaVUsME8wRuMlW61VgRzC+2/ELxWsURL75imgmKTAEJU5wFHhzs897OXsLRjlMpn1b1ju93g6aee1LkB2qrNQaS8u4SstQb7pmdtUUUWtkRBJ6YMnGqJoXwOoGWLjfF3owCjKAsQzeqKA3V9vn7B61MNSACZBiHQosoWuNpcF04InedZlQVNjEFJ525ujN5lAKPdNDGkDVraQ1fhA1Qo0nY4e4EAcl6O4pUlsvJ4rXHOjWJ5xBwaNk6LaAFALSh1oo7F52xkNeiwVURgiqzhanrjK7tB4+JwHcQhBOxhpMyUwgnaFxn1dFBIZkIdzGMOARh7WEjzAUOpYgUkMrTumTcMJ08mS/1G1ukWZ0vwAIVd2oS8H0t3np/H66R5aa3Bu+a5iFGIfjFR4sacMxTJxWeGEV//ZUHX/Bmie+TPDCPqpTiTaSzTADWHZVqJpX783UghZkQbkWlEcMURqq9apZfht4Oi4hmbzUbglBFcMWCyggnG3ghEQOw1Izq+FMN2bw9Lo96nI3o3xD0hDV2IjgNsu0BE9EjwKJ+KkkFX3r7Hf4eRP+moTfddg53Rvg3w0MQYFjEKsURTKeoOGa3HG3UpRcDI1k+FwIsMYM0qp7g/IXwFLBippxOszaD7k/EAcs3z713rHD7dCor1ZO2a4E3uQ3Msu4bnn30e7WiGbwimvvC5z2EzFelGfKy/K5US/TYA9bLB6joIwEqZFDREKpT3s4iliZ5FWFVLRCBjYiu7ADu3vrOHDILSp43g814NYkxMpCAgBKpw1M0Es4rDwyNoGbQ2PRuxndhvAiBdAMyVNik6i1DAAyjwgFLEpQBNYtdg+QTqIjCJgK13pTBinTGEvQNKrlNRfO433nQj7rzzNnzw4ceY5xnzUWPH0bpB8xlL65jnI+wdHKBZwdXjBbulY7uZ0J19A+FGvaBsgkZPkcFEaGoMpUaKRnvS1PtDOjnzgu1mH6+//RbeuvAuGwR6S9t819134cYbb8I8s4070+OrFglwaZxkcyLeq2EU6VuqQAalhgH4m2pEtD6dMoDoRhsn3kLU3zoDKG3aAKG/yutTDUi4eUv+dy0aMCcDyuC7YKv8eXdXB0tas+hCEge05QFWztPGoY6yV8BGtUSId2AsIXWIRu9wVLROlfSiip8RGfJzAvlzs+oQqSYzjGSAjaDmXFETtQnKR2ofkK1wRI4ZcXjDIGvnMNIcDgly8DBDLVtAnUu90QAF9Un03NMgEJQRtDFFIcelSC2FcFZOXFPQfSITkH1BosfA6ndhSMbH9ZxcEUYMgcrqBJWEog8aPQ58VPbEEDi0IcrSYxXYlOMMp23MKRetdTFg7sxLR+YmkgPeIgUT19lZ3dSVspARzgFXCKMOMB3RUYqj90V7GIg+FhSgssy8TCXvnfs3AKqElnDUqWA3dyzzDHf2J1nmXVYSBDBJ0a0Dqp1Mo26IHgYDtAIjPcf1WxsaOdP4PPgqZcZ1Cl+CEmm2OAvSOQSbWViSz95WBphax7eWAnJX6q8U6VkciDRaZApC4xKvcW2rZ69rXWuXYlP0VTSbqZwUhut3JWCPsw8YxjgDw7vvfYDXfv4mOib0tuDWW27Bo595BN0aNRGt4wRXaeP7bBwn7TRTtnG0XgzwmAA3nEfsb61B6Hvi3PdIj6RsxtSQMJyIlieAatoXsZPF8ntc52Kz3cCniuu7I80TcGQ+xNV07ISTCm1TibgM4SDXTF7eE4AQt49eJtJvtVGxY2DhVOvqLqpNWAKAyq6EkiZS6O4CKWaomy3uu+8BfPDeJbx/4SO0voOZ4+D0nrJcnOpbtxOsTjg8XLA7PsapvX09k6pzZAmIzMhSWc/jwmvzAKV24vzE/Ztz1tNzzzyL48OrqFvaf6ZkC774hafjkCmtv2jNtGcsApyxj0/okjB0RqPB3rDTFkyWjX1ZzDMdGPun1oplnuOkDNuUZ+oXvz7VgKSoMqIUzoThAKfoQQCgs9nUZAYYW3rTX3WJ/BYdjNFAJzQbkILenBEKfFCVuenNFe1NsEKRHcBKle7AdLDBYsAODRJJg5sSBDt8qgjRICAn1WlwWP2gyD8PZImUb27a0MMoVgRiw4FAgekTRrBM6TiiLb17g/UCq2z8xnk+E9u6uwGoKL7q0xInyJBaEV61csmZMhITsjLmmQuO2MoXiu8s9CKkMwtGeeoaztPZKxfpUXqGvB9OhG1Q25I0wlSBRy0+MnrmAwfBVXdGcatSSD7jAL5jxhEFoCWBafSviSGJBqVG3Fc0MRRNukTLWqUC9izwBaV0TAawPUxQzg7vhtmH9qShYbccY1lmbDdVqUXL9TeQsQMIPstU1ZMlGpIZvFcZKq55poe08KUOGn884wEIYdJjGNiVMyhbkxEKlEzUk842dTpamACFFSX3pCX4YboPZpgqheksQVRa0EJkV1ZOu+Q5SaABx/qRRxBDkDWedf5XifQIRXtrTZl2IqwULAsHxIWo29Tsj+9rmZ589qfP4crVa8BUYc3w2COP4sbzN2BuuzxTkVYMgBfMjSmYchT2XNKaFuXxSwnxohx+HXZsaMB01QEgEEAXArvjXNNvB+Cjo4l2CHFdUYXIKsD4PDCVgoppM+F4dwQHB8vlXC0P0TL38bIEnyRGyIsyVXFouI+8BDQxNCyYykZbcvSOieGdtK8KxrzJnsYIhxBT8/2lFpReyaR6gDcK0ruikmnaAB3oc9cqLejLBmYVc3Mc7jpsU7Cd9nF82HB48QpuOnuO1XgaYFqKiewxsggWLITnczMvue97cyWVPBsQFiu4fvEaXvzpc9hDR4M6X3fDHXfdgYcefgi7ZWEBgq+C5jgbuj+TTYhgg9pI7p9aJ7ippYOPgK0LMCVKXQVypvcWUGNY1YFtnhf5Rwhs/Wp1Np9qQNLBqYzh/Fpz1oT3lqkW6joAWS8sx8ecJzJtYFNEWRRAhrw5qGhSZ4NsqiEwjZxiF2UfkWqPbBoj/aqBela2cOlH3Io0LBHBSKYa1GhvMIsBTUrRNMBsgntDiR7txvHrPa9u3UiMm6ebaM511CfH6S1a4SssaTPqtBn55loR5KflhkRqXcgCMbVSMPo8eO9AmVL81lffWyxKPsM9hb4AsN6lqPcEEfEsmpw8aeGFcU1E6aErEOtTMARYn5w8aUXBXeuI/E0I1mLtSy2fMNwSharygNes5nLNs8lQpANcULAvDTF1laPSFY1APRh0LaZIsPcGb+o1kkyYuptq+QMqLbsZ+5str9McDQu6IvZ5Psb+/j62mwnHR0fw3tGWGfO8yx4fBmBZpVdc60js53lvGZDqfRZ7a73PtHezn4TOjssAegnGcgXyeo9cmED60AHE97l6K3Q4lrlhd7wTQ+ViPvnZrL4BJg+OIJoNegKI+MwQD2YrAEV6+b4orwRtgj4w9yTveTBa3TzLIrXF5dAZvU/ThOvXruNnz7wgTVvD2XM34TOPP8lgqg22prlneXqtlcJzqLpGwnSyaEjmBSCjkaBf2YsYcDde0lbIbozjp4AoMbjn58a+ZQO0cd6gHZMg0lSy6/FxhvNnz6HNC+2hbGPavL7AQ0sRawtPjdsIy/j+AHt1swFT1ievgymhGcEs8PaGDmaddgKouQnGpLoDk2Gex5IwqCQjEc/73JkztPEl/DKZpd2y4PrxEU5v9nGwt4f52lVcvnwR9+JuFO/wNnPfmUsrFkxV7PmaupfQvBG8K73jQ6dWywY/e/EFfHzxKralA41pMHPHZx57DAf7B5glV1gPqkzfstoKzTn3zDtUNq9nLo2lr1iSLLRQENqX6IsiplDr28F73C3H8B27S9cpGBmwQvBXeH3KAQngIYqDGIpof44QgEkUBfbwaBKatsamS9m0SQp+Cg21OV26DUUw8ZBHI59wJyCKVVge6mJ4x7LbYZkYFRAcYMVOANqFgESR3cgcmJMODGRK4NBUkiUkX8qJzTZElJ3gKcqfbViTiCjCAVGpTdFs6R1urFgq6iHRuyqYwvAkzddRbBrIOQbClYhyLRuTUUilaMeQKZFaKkrl56ZYzVTq14GsbVe0GM113EK1zUPUFTl7d0XgCXfEngiA6MBTzOWr9aMRYs2+D+ccL0P+LB1z060T7ULLmsDF+hABhpAVihYtwnUPwOeIMkECUYGpwjQNAKByf/WuPL1GIwSoZWvpilEpwpLeio7JHJtig8GzwumnVhA6lQCMwzKLUC+WDtm0doyG1yJKAytbuAc7hDJ9gAJPoKIoSmcrZiMFRonIK7ZVbFqzitYdG6NIdJomRq4dmEbRQIJCof8Vq8EPG9+jw+rRhVkMn748GGrE6TJTJcwQNPOID+AanUnDeU/ThBdffBEXr15k1895wSMPPoy7774HrR9j0d4pa1AUsEp6GbcKK0DJfjCWe42/zQsNHc96/fLatadMICQARYzdKCjo6GriNhx7gUlUzvYIcZ9xz0NPF2eUU13Pnj6FprlJ1Xnee3OUGIPQNTtJZy7saewtt9BT8A5YsKD0VAea0q21Vk0pL+p8askyhCPN8wXuLdpoZ3Ps7oDSZTz/HcVY3ZVVJMVw5vQpRMNBjpdQyhPcOwebDSYU2NLx8ceX+RxARgUqaIgKsOivc2Jv+Sh/51m0vF4+oILdMuMnzzyHXgpaPUY0zjx/9hwefPCh1cHlP1V7Op9jHqWRUo1ZQaaRPxZnVal5rJiUCBYg+8Xj3dVei3aoWEWbZ3RvFJ33lsHJr/r6VAMS7y0Fah1EsEub0yi3HqWOTc5uwnaPTYno6x2LN0QZrnnhZF945geLoq1UlodpMwmRFiFmMyyKqqjKbika6/OM7XaDOG3ryDKMtul6IrInuKJndqUT0Btab5imPeZNu3p+CBBoUfR+z5STlQKrhVHYegFtGJVAw/qv4YzU9Mb9E0I7m1A0yI2WY9XHQ19CRTl0j3QqrvJkyBDR8PKwLm1FqxpFezGzp9Si9ufh62Kjd1itiGZL46VuGH0oWWPdqbvpWV5ZREtGZ826moRJu8Hn0lobUVhi0qJRApqfU6MU1gdArCUZgfis1Nfo+VWr6Es4QomGAUC6kOjv4uDzXeZZqC1AH0F30TC/pnkovTXUMmFbNzicF4Le3lCdDfl6RD+Ky9jVlsAo5EDDT3cxeCwTJPPGGTqxDyJXDT0jHjSit1zPWLoEt0rfYWJ+vdjqu4cmp7vBnSL1ZW5smgaDlQmRAovvXQP12N8K5lbR6Nir8ZzjuqI3ia8WINt/e6IVIIV/MuL6+7qpuH7tOr7/vR+g244i8VLwxS88hU0tODqeKVoUQAgAMUkvVGoI3flcIgWY1yeHEt8X05hTuAyIPYntH+CB98NZI7EfVQUhpqtKSFmrRi0IQLjYIF62BKcQOAVpeTdg/2Afly8dYjNN6EtDm2dYX7GOAjht1cXWaknxPS+0oC08n1Yn6tg67RW7mbJqpkPM0Ooeo3IpKowKTGlFoaMAPEZNoQHJ0ESvnnDoBcC02UNHQXVDNX6ulcrGdscLlmXBdrsHKxt89OEl2reyjOem55MASXsRveXeckQDSmnNPEh9Msdvvn0BF955E6gOtwUAz/cdd96Lm2+9Hc2DYbR8zmNg5QiO0Pn3wboyQ9B09iEA4lmpVKPKDpEKsxVGH+chmh22CKB1JkqJEO6Ecf4LX59qQIK2iBYDThpDE+rkojnkjCuFkEvrBA9zZ6vuGuiaxi0OcWzUdGSqpjhWK+6S3fM6lpaumRG7QU6KqZVqljndddVO/LuskOsJIZAMR4ALNLIW094Ec5W91ZKRYXQv5MBVdZnVpq8rpmSAc7WbDnBiAjJybGvRcOSr05GC9jh6wIShYqVJIVBw0aDGVFbvSmUhZE/Ut7ACiAJMAhN9XsRRHtqbIWRld92O2juHQfEpARCTYBWlEmj11phKw6r0urDZV3TcLWLa4Cf1IvEadPY6by8wGSAuIghViIwU0FAehygXiJQWBaSxgbLRlDu8KUrtwEh2dWyq9AYBflBg3jAp6qm1YrIJjoJ51wjMfCNmw3Ntwzm7e06U9cK25vJXcff8lloH0Mo1+aTuJjQGqp5SOa+V7NCeahZA0fiq501+nw/q2BQkEJSWVafWOP0DaBCMkPkaoCRhN4ICHQBmOGpbnxG9AmBGasqVRlgbWbJjLjBZUG3CC6+8hPfefw+b/Q3moxn33/cgHnjwPhzvjmBNHX6l4VDrDQDQxNlyogzdgJVGaQQzUcVnRanNYIRK6EEAmGevFUmJM82MXD3+/TRNGOlHdd8VGIlZSRwE13ICumtfF9m7U6f2ceHtq+itoTjL2Nnxow4A22kLtMs0mDDYS4OhyWwFw8lnKtwkm1AwTQpa2mg4lo8HPMO1RBARxovVOS7NGSvbAoxxKKYWANaBvc0eJglUAaC1Gfu2xeILjo+OcXjYsd0/wPb0Bh9fvohd+KTQbTnZyWnaAM7qk6JxCON4WbIk3PJMg1UAvnS89vJruH50BbUqKHFgu9ng8ccfxP7ehuMhjLY0B2Kq5J9VgF32WYClq+opGuXJTrXGM1cwuizH9ZFdqbCqwASjn1VfFp7PJUaVrPRLRg3Nr/L6dAMSQNS4cvlmEu+pZW/QwWrhG9ixTFOOgS8T2/n2mKap90WVxKA+h4FjYNLYCMkY/XIk86jQ4Fj4Ap8bsPGMUiJ6I3ai+ChzcvnwadyC2s+IBKY8sa4NYJXgJzBo1y9ZqRmZB+L9/5H3J7HWZdlVMDrmWnufW31lREaVUWbhKtP2bwN+OEFCCCG7QQ+3wUi0LNsSmAYC0aAQWNChZWgh07KQkEBIBiEKUQgw4j0/iiycmbYz01lFRh3xFffec/Zac77GGHOtc9NVmCekF+8/6fAX8d1zz9l77bVmMeaYYyJuTlghMY46JjmrB0YD57q2lC8OBQEYQRTEsSG6hFyrzBZd5Zk09E7Hw8YJbeY0FsgW0YKoEBSL6XA9M9fMGvsI4ALKFm0SI8c9Q8HLCCyGG8IIqwwjwzZ1lBQphaYTyuwlIh0UBBOXsd6uoIOfWWZAiSB8eeRgQ44LRocd7qwVq+TYI5QdFXbpOBECV1kmwOfTvI+ugN4DrTl2tUgfBah1Qe9trCMNTh3dDki/mi3dUOZoKWB15NhwtD+D0uXcx9oTM8ZAKYbeee8TYTkO6mIYM1hmd8HW06OYoLWmSciC+bOCpYCCScTICed9eMzuEICEdu23sUOmrR2ISpZlbfxsZoSI4BTmyDuYHBVAmJwHSgWur67x6f/5GfSNa7iUih/6fb8PS1lx3a9htqBGYE65FRImpz6G+OWaac257+ooN7odBcNHUP+4tsLyRCYS8xVqLw8G82PRtX42xa+sGGrw/FoUoVkJsCgRLAwBEcDpusNhv+eAt0Ulp1KAnohnG7yqyEDcVMqQDhLgWBRsJQduAFsi8wb66KILBfIp2Jht6KPdWOcyZL/MbJYWc98IoXHvw152B07OdrCF3IsIJj9n6yqEpDPFWSq6AY+vrvDw0SPcuXsuRMmQKtruCelQNHN2YskO6PkuRyTiYhWPHl7jK7/2KqI3oRss6d25ewcvvvIKWgd6FFSJK1KmXs9FNtPATs20f6JKgUrVgEdDzhMI6PvF/zKUeY7CefZKIQJVRDXoQeTSu7RuDNnCjnzO7+P1gQ5Iii2Ksh1LoYLqQBzqkXu2ADxFz7gjrPDWA2UuesJlo6UQR0Z2buRV2gzMhiiHbAhsmmNQLUegq7sGEDxHOAxQwIEqykUHvApZkFMepMNjA+OIUgSLzQF6KYCTaEeVoaKDFVQo8YDwPuZDKHIahxxRZut05kaCY7PtK8eJHxtKftrATMA6K7he6WhMvA8Da/HJNbHsGIojAy/jIaJrTkpGyLiGCdWSkQoefL6/jjUD5mTi0Y2s62JnDYmRw1jndWSrajqdEUTO+UUpm4/ok+vjLsE2AEW8kSCnB+nwMrgBxmfDDBYdfriG+SrDToJl0k3KUgCVl5oDPQxRC//JTWoKcFMXJQLeGwwxssQeVDGFlbEUgMvoJzH6yEFlxKfdmN+V8vAYwXIeFDqtOecmA2i+1xWIVEUUY9poSDZbZ7aWgmrUIwmQhA3ngD2OcCfnqZSCCgbNyRYZkDcgZCD3SYzrkQHht00YaMYelmvDv6SjOoK+j/YS92pqzTBg+Po3v46vvfoabDlF+B7PPPUsPvbx78bVtkcLitDNDqwy/n8xdtIcty2PvTgCLDKiQ4lNOuyxT1X7984sNjB5IXmOkoRcrA4cydQ5luDPDUL4sCH899Tn6SAHrBSVgaCZML0RIVkrbSm4f6M13qPOf2ixE12C6zpHCSKQROURHKscXo4UiFkOznJSclq4VtkxQ0eLuRaV54tcOzrh5l3aOPwN+IaTs1PYaoh9JkdZ4g9431CgoXMBbFvD5dUV7t47Vy4iRDXSqhkQ6kDUNsyAeJwT5HC6wFIrXvvWq3jt9ddUtvXBYXrx5Vdw+94TOGwbI4xSSNqFeIEKHAZSqAAl7y3RUte5LiLgJfoJMDEsGTRFyA0mwuhKwI3P2EProFL+cQ54Qx7gt399oAMSpNFI+NLZZgbJ7M75HWlffSAl4xBrM9ZhoKcxTvXXnhomgBja+VCZ7XMPkfOwNQodebSxEXrvJOFlPd0yCzziE0AKd3IWVvmQmUGTPDT4HsYNvfWGKkYfW5oDZjosw5nmvXKWC6/TRiYyu3sCYeTbwAy1rnC1YtIYCFrlsqO7o90wgHogudja2H205wo9SFE2oRbhzgzjaB34ovHvrWM5KhNkU5DJIfKzMchVkZeRxvd4uygbcu0VeiyV82y2BNLByPBmJoqEUw29SQPCDK03qM2Gr6CcuzlJ05aGzQiDNu9DXRKlag2YbdA5OwCViqRQm3AnHSydSU7PHVecRiKJ1aGzUAuWZR0lruSL5GRiwvNc+2oaLqYAvAoCZ3CRe4VraJZkuUnwNEzOUZadQmQUCxvh5vFWATBI10zCZyZMZLNrvEMMR5pkPG4Tfh/XIdu6teZxExjIScbTyULZ4c33jZKanBXPHUMwB35T9xYS7QIQJbD1ji/8yhdx+fgBW657wff9X9+Pk7Mdrrdr3mcJhDRWXEGA1Rx4lsGgzlzaB6NoovPx8NppRohA1Gn7uWcLEGWMZLiRo2a3myFP0XBak2x8FAwhhnqqdhD3W9pfCKVAjMAq1NZmlt1vENXThzPMZ2oomotZuB+RGZWu1Y5sdggNKUwsxf5gcOIsV87S5EQueXv1xt7Ns9V7fl5BJFdMtuJkt2B3smOpzYAWHS02WAVKONwPWMuCpTccWsOj9x4inr2PVDQGph0w2XzGljbC+KIzkQmWOyTwV/HlX/8y/PoxbOcKAR3LScUP/L7v1/NSB6IQkMjAAzHa+Adagpz/w7OdSCIDCqJfVXIarSUdQniYhaQcxBuqvGj3jtY7TB2nmYQTOREH8Pjs/w6vD3hAQuPlco7LskBAAErx2UURAViMunagws3GwU1nlvF4IiG11PFQyjB5OatAxjg6o1OrIvxp45cKK6ztbw6sJmNjaVz0fTLwLrKR8mZEMXRpgUwBt/zOGJwU97kGALkZMu+8ju6DuzckzBk6s0/fJbtvLBOMzab9E8qk+Cs2jO8g4ea3ZeCRmioG1nVhqHWBgW2S4SECW5Y/JnSfUtU3yI7Oab6Q020bI/8lv6fIKVseHZUa4MycyzE3h87PSjpeZnp0vGk8QIcKPtaOQKp1Jmk3uV0MdnXgCnUiIGeOo+uJzI6CHAzPrh8YUhM4Ami9oa5nGCJfhRft4diu94N4V+RFt61h3Z0gY+ji4KiELkVio8HpqZyoQILoVOoPAMwiMyhMRA2speueeY82ghrKYBd9d+BY2yWfX7rMAG/XlAXPAZOZIc/1yr8cPIaRMVYa78I259GeaKaaeWjdR0QyAoYKm0FT0qBifm9+c56xLFtmuzJbU31QZVhuzGRmhDtsP14WvP76m/j0r3xej9Zx78kn8LGPf4yn0wJRVJ6sSdIUQlKMyJ1p8CIwznbguBQrCF2Zfr4yoKYjms6tmg2kLYTWMZ6QN859Bc38MaGwSEXcUCKl8xPlRps+ADRn0FHWSkkFWxBeyR/KPVEgbppzDyowX0AOyVKNXDxtGNdak3DOycGWDxFGu2CuIJZ2rBsDyOiJcgCR+2Oc5bwmfj5tIkMpj2lns1RVa8HZ6SkePnwk8+kiEXNfNL/G+ekdnJ6u2B7t8d577wGaowWwhDe/U/vNTKiajT1mnraoK1gzPHj7PXz205+D1QK3pmTJ8dLLL+HDH35uKKIm+gPkWIU8UnbjPJqI4ZkMo6ZvmR4u9aKKFdlqJgaD0A8OucxmhB4d0RvIM7ThZxjIu5K4b0MXf5vXBzogKYVTNM0VlDQa4qlAx4g45Djy8GaeX+syMkYUZagLBjzFmtsRP2XEs0AiGmYm9U+WS0qVQ7QqQZxVJRAAEurJzXkjI+EV64HHbEcOGmF4GUa2IAMpGsZJ4uMm7F3zaFTfSwdb6zRkrJkqI8iyEjA2tqmMlWq0zIT1vuNMO/zIwCfsmH5MZY7I0eIiz5ohirgYmbGOh5MRfdEaq7TmCSyHgs4GNizOLZyOJBSWUblURvgoaBmfHyrvlWmwkjcySKj49oNE13BM+Co1hyfq2dfsUFIAGHRu+azA3TjmimRp5nq/R93dGaJWHqwZt3DUVcMJe4chNLCxap/ofoyhc/QQBJ5nQIbm+AxYBoFlOA0ANECRQZ2ckZYn75f+68jAao8kKS87TkylzxwFwExXwdnRa/CIIv+cQU0KO9Xdyj2r75zCX8z6zOogn/LSkg+jgFUO2rTHxn6PGdjk/WQgnIbZ1F0Cn0aevzulAHrvsAIsJzt8+ctfwv76IWpdsDXHyy+9gieffFLIQCC7ihAaJWGY51L/7nmfVd0X2YZdqx4z3z86aiKtk/axOlFyj1MMMgMWxm5JPk/UkT6Q15CBw0CHsmSrJCT/Vy1lA3Ldgbqs/E7vqF7Z4aLPLRqHZM7gK7lTCHZM1ZDApR09m8iEodwIJgSpaU86ylpQUMnfS1K+9gw/SyhKZOLGTsoAVOqV1IE5qBMc4r84nrh/C6+9+gawBNwMzR3rumJ/fYUSHaU4SnUEGi4vH4ksmgkg97i7o7cYjznTT0QfiVLPpBGGupzgK1/4IvaX1/BdEV+PPu4T3/NdKKVrOKgC03GOhdbpmOVZkrINEgHDDEEw5AKyaSBJzCO4IErCxGRyYtjSTUJ1QXJfiHiVWiZPptw887/d6wMdkFhCgnMYJZGJyigznYHB0Da29y7rQkTAMbK+dEjJDB4bV/XEREvgIeM6LDTgSZai+S4BWDiisQd70fUQdO6omRlWm4c/jbQyl1r4IFErIS+n0mASK3PktiXWnIFMdDH1FciMqJnXltkY4WgFWiVkiDC4BVaqCIuhEe8+Molsw621zHUArz8Qo/zBZ6ENmicjp+UOZVp+f+udZD5gtCwXZd9DC7bk72Ww6OoUKITFMwNmas/1zccEgzcSjqvNejr0jFOAQ+52GFnmHRMmBoChims0grWSDDxbiZueU5Y3RKDT55V0hsmir8z8l7XisL/G2YWP7I4GG9xjKlWMBNc7LBicJBw+ORLq0ujMctnZtMN+u2ZgHUDO/hkCYAqMzIrUfRWo6w8IjSP4mvc0uU1jgXiAVF5y5JTeJEjyTE5kwgAkE9zWKeiVwoNba2i9o21NpECWCEfZxrJMoPsQqpPdJkw2jpUYcCMAmS/PmHQoiXI+Ez+r5OclYhIqPhzt76VUXF7u8d//+/9UWbBjt674wd/3AyiFba4EcXyW34S+uUtbRQah1Il0FgXxZhhdX5kIHb8yVhqdW0pYch/m9Y8kLAniCng8qJzqwUC1lDICYAP1Unrv6JTnRYiPZDB185HYn4M5e+/Y5ZoD4GDTYebGPRiyPBFiK6s8K5uXKLTBsslOgWGM80DEgc8iYp7NtHuwDMDoYGtli7yLLL2WgvAFvdUbc8ngjtgOuHf7FkrbKBhpBdaA3UnF9WHD/vox7PYdJiFGYmt3R+oCdWfCSxRHJ8ZjlrtqnkMb58Ss4vLqGv/9f34WYRVhezg2GBxPPnkPzz//PPqmTpe8twzAxvrw1Tu5Qkx8aENGx57IqUymfDwskoOzxFYwxlJIo2TsLe/ovvGzFklqxMJ96GB3YDVRC3731wc6IPEgiTDKQB0HGQioUk7NMJFwnIciQQCZ4XNuTTo7G6TNksWSALzF5JlkX1nJDJpGcBxghY3eOrZtj9gKzk/vqN4tboQ6GABDBFu2KgxmapWNns0Lo6XNIglVEFyeHSRFdTs5C6hOahUddLrLsgjNEIQObtoCUzdH8gmSQ1KpE2AArCJT11CAlx0zWbJAojR6TzUbBm8YBwU+pmBxMcMmhxjBzCOvrbeECGNk5oAymXx/d2zeUBvblDnwTtoDwQAmkNYvjrI9DJVBtilzR3BNDO4tc4kBSd/Mom/6X+8dvR1JLnuM783szESozvIX95UjogJWUMuCZd0hjK3C0TZ1CfEzFiMBOiBCq+4veUHk6wDLUuAWsLpSFdiYcfasZY69r3vOaJ5pNCDJ8+QYZkCmGHhA2ikUyJilInJqWEzCcwUof59fGuOoKMCagQINnM5SelYwEWCHB2d5ZHmuSM10KknmZ6k0GMCxwN1NdOzYkfu4sLQWBhzd39x/CfdzPEGiOV3ncUEpFZ/+X5/B66+/heWEU5k//tGP4YXnnoF7Q7VAN1NJ1FAEwRvpH9RUMnW26RqS8zIGweVeGk+QV18FnydieXyHVkw6IMAoPvss7iZiFOB9ZGkybVXyegymwYYpTV4AEbyHQ/NALAW2LjhE4MRslGQjBcpKGXsHI8BSqcA7YFIpdqC71sgWpAJtBhXe+3CoVjhPNm0Zn5vNbqsIPoNCQUmEq1QNWBi8dZgDa6kAluGkA4C74e6dewx6kc0QQKkLUAuurg643m+IZUFddnh8eYXt0LGsRIcyCSPqxW4oq3ndSkodGrBpCDjqUvG1L38Nr779BnwxwLrOVsdHX34B9+/cJtdFVQKmu9r3plRKzyz1SDq6uFxQQsD1yQ7EwevRAwuIWwiXvdQUeMQQ3YTsncm+1lKAnGoffOalVHzbQPDf9vWBDkj4gPQPugyQyJrIA8oougRLNPlrgOppHkBwAyCccskBQX65mYDoMZjLpR53sWisdkbsA5pcYB7YDhsO1wc8eecOSl3hPYOGbO8iRJjTlphV2ohz+L7phBPZTVM0smGk3mgIsiyJtnFOjWD77GYxGZw0S0VOm1lHH0qg0WJcBw9UGS3B0eYsDRNJbsxQKEeibXoOBrVF2jws2RGUa/JbPma9lw6RhoydTLz63lM/IKbzV7dLANBADRolcO7CODFyuHb07aUs5IcEMKYoI3k6qjkHxnoi76uwvh6u/WMTJraE4blNeNjtiL8g5wYDwlyth8f1X+haQWJw0Yjz7Iwwlqi6M3tJYSfvDDCsh0aAMyQVX3p0IVnurxsLP/cgxs9iZF9x9GxnXScPBgZsbXGkCKJAId96PLwuXLoteT1wlKUyODfAvKNiQYItPf9FRpGGmSWA5qlqjGFMeZ/ftsusYHwgcrvyPSmsOASrxnPPbHsG7qUA23bAZz//RbhV9N5QUfAHf+j/gWIdrbURnPa8NkPKiCBLLpAR74LxK0xdaMN3087Z5B5k15F2L9KVshzhIqZnwDb3843unLn79YxpXyKdu9YuZo1J5kKMi8BATKsRaVvqMrsQB6/KZKfKuA59DM9LNQBV2kW00UPLB44s6wFEsIgu0YaHyqI5NDCH5eXQTotg0CsbGFFGN08YtW18K1rDGOsRVrE7vUBf5tiPQwdu707Ry4rwgkNz1N0pOh7h8vFjtO2As9MTBlSmeTkoqLbOM1Vj2NwMMsmvqdgOHV/44pdw6BtKJbJjAZyenOBj3/EdqMsCBJAjOo59A9F22XpLZKZoHRJ9KiNov3kcEgXJJFPlsFpRFYAiQnYF5FEJgYKCv0QYk2xbvv3M/Q6v/78ISAi/Gbbe0IPOKdCBMMHf3IhFgjGmbhZTNFeMM1xa70cHazzd0erq0VWqIEE1SWglXO2WIiTBGLkuwO70lMTRQhgno/JUuTQULKMEhDzZqhGrRJCW6kgbACNaTyY7AOvwTnh/zcwjpFnRJCwlwlSOljZ9/ujMSZ5LZdZZFh74rXdtrswhMbpVch7D9CS6hxD0rMPRYxogJuV9bFz4FEWKuGmoEKbrrLNMFZN4PPQ/yGam4RzRSJYGktDG9nCDHXEjHIn0sP2NBn50KKUXkvOAPo8LK3Gu1M9Q5uMZjI2bSMRFBMIkQivUCzha27CCBjVsGstk5keEZgiRgNw8UCO1b5KIprlOTuJnAZ1hqQuidW1rQezjpjIzw/geEqcxn4O6rXI4HktGQBw9rwzgABL2crhigHBylngAjLUGmNFNrRetr0pLW2sMXCwQaAhUjn0olQFJolxBEq7FlLpPIz0Cq/EfZX43Ju8Jej4l3xaYSYlg6uhEIAsm96QUPoMvfeWr+MY3vq7OmgNeevElvPKRl7D1bLuEnn0Gp+Xo2WWtPcOGxDIwguyiZ+YmDQ8zHLX5jddUTs1En8E5ESlGgm4zwBz3AQXF2hdUzRUPqPeRyAB25Pyobj14ccEy9em64/UfCWQVkGBfY3Ys9ViQIyIgZzrsgL6n6oHkucj9MRKHEbhr3wwtIjl7y6RDayl76t1RyoJiFMtMe0tahsQyrcDKgvX0FF7XgRr2CGDdodWV3XNm2J2dAHDsLx/j8PgRyu1bDGpRUAMit2KsU5YcdeFI61IAPHj4CK9+/VWY9WlrANx/8kN47rkX4W4agImjJDCQfK6KIz5KBmAG2FEAeaNbTZuOXTE+uJi0NZDdTa0ufm6XPTIwoS2gv6WwH0Ywb7X836NkI48wal+MzEzdDoyaYRJUMhvk1GSSGVTuAYBOiK9A2b3q1bAyIvQC1teNX8Zs1IEhhd77OFRdUebZ+SmqBfbbFZZSh0YEXwokgrVRT9a+yXiwaIvQsEDktQ0HwrKG946SQ/QK+FTH5rFpjIz34GPtlF1400RgBmIRwZIMtEbG2QSsD6bhUEAXXId0XnXwcOYjAOQoZSRHEIK8XUOgDrGrnuxZ/Wxkt2lgYLBwLNInyQyBMOzULJnIURrSQPgmbZUZ2COHTSGzOCgQdZRIxdqZ1ZkOdyBhdVHj0igrgwvB4jcMZ5nOMA83CZrqInEGmscFBLMMYCSKxNRGRlnlktA1HXURLLWi1gpymVOIint/oGdj/TCvfSA3abxY7gnwOqK7avc21q9nACaHUIajL/q+Jihd36V21CMmCYZeg9EdE7JXmcgWWFnQAlh2CwzqHtFnkYQJOd8+nZDlfo7R9gsTt8pym9nYDDdKOxmBRsz2SKNZGAP3dL29d3z+c7+Cbbuidkrd4ft/8AdQlopD2wCwBAElL7zvOlAd1/NLWN9MGjQlk5NJdB0JSvC5jkLnkRBV3kUtU5+DZ5vfnS3eJN9TYCyp9UQhG5Ot3DNjD9OxV3URjrKu9hWikg+2LNwTIyDBsFs2zgzXMpEuQxklGiBt1nELcqq38rOyXRraN9CzQRVXQvvZB9fOJCFPO5rBXyA7yHhe+kpuiXt2KBnq7gS1niH8AKj1tlSw4SD4/M8vbqGYYX99wHtvvYu7TzyBgKFWh5mPMw4Q3fHO2UgZ/LJczGf/ra9+Ew9efwtLYbICANE6vu+T34vT0zNcHxrCExnLgFZBhvxiBnIqPCHLOtD+IrVFZ+6Im8SA3QHn819FcEZIX9sM3lM4kUJ0xUL0H/rOsPlZQKUy+vt4fbADktDCughBoLR0C2ZvS2Eu49ktowNPwvCskcpjA2CHioGQeYmA2aLpm7Kk7mgd6lm3cfhzMm86wEBo0nDH9fU1gMCtW7ckoSyVxEgCWBFZr4ojIoW8ZK/nJkhDZumulHWkIyYrVI6/64xmazD5GNQgsaFnUUqBI5U9p9MZ9+IJsB4FKxm42QytOJUyyyQKdninAH9zZqwwJAu56EAmOa6LiJkdIRGB6D4g/xzHPbPcTAMZDJJLxgnQYZIxBt/C2TtAYuBF2URgojezSwSAWO30vgWpaphBIx2HimW6pWPicCx0zlvfhsMrcviuumuKeDELBWwhxB1HaBEJfyYOlGFddjeyvSSwJ7xei55W5LMk+qLVUsZkhFjzXtKFyTglR+dY2fRm9onsfOdCDC2SiTb13lWjJjcrHaMen3aFM6CwPJgmiZgkI+pcO4P8CM57yVZw/nc6aT5oBkNZMtP3aI1DPvKYwzJKFoGjdtm8UIz9MAS2Io5sB+vq777zDr7+ta+Q6+EdTz/9LF566SWKViVaA+1PTCcNGAnGqU0kfglLcGw7t+CJ4NnqIt8bhpCdceOPypQQGJZK0uHMYHW08mf3YC8Y2kiBG+28GSxyynJm1PkzlmdKnSJ5EcFph6UA0icy3QuC/LhSKxFal8wAJqq5gBypHp2dG0oqshOk90SljuyhDmMGHlM+Ia8yZOLn+I788xhJMysM4OsClv47HB1bP2Dd7bBbK66uugjKG6pxeGU7bGiHDeVOQV0WtNjjrctHeEHXyVlWQIsNOZDUpN5qmQ1QeIRNECj40pe+jO6AVfJGLIDz8wt8x3d853TuQeIstAbdY8wrq8ZHYIGBalJPS5jrwvILq6rikmRiYPO8UI2a+8AiBvcuBemGIKCnqKcBkSKgJACHAa1teD+vD3RAEh4jU/PgRqxDwpxdADRoJNptm6OsR5B9WiEQamLTjmqUkYSmBpiPA2Mp0pXXkMGAEd6fWidH9e2ywMPQLd+vakGo9l0xBMTot6bR58VUwojpHIKZdr4vxXy8NTDwUvlCmd0QhCoUistOmcwGS6kglUBs7FrHFVhm+5lBZsYow5ZvorGdZaAIHmccGaoyDNMMU5DtZMYDMIrqNk1KLYQOR2tjZoiW16dM14c30e8e6dBEas9OBzNvcNbSa6g2DRscgsxC87vGGPfMdzIDTdgk7xW836kQrH0peHhJUN4DiI6tHRQoT95Cylu79niAQmXdZ+04uwgKCLNz2IgheuB6f0BKwFO+nutcahkBKY7WJNs7AZeUN46g5SMuQRqlfIwDbcj3sTMspbphNJg59TgdINcuB/Y5Ru07hKgVErz5WVybw4HGLdKB20TBxv5g5DmCCsuLxHS2rNfbeA8gtCGgAItZYXgfQfhAW47c3YIFn/mfn8HD965QFtqbj33kY7h/7x4DwTjeJ/nvR50lmA4xtZPyn5otv4kuFIzfyXOCo/1IO4RZhs32bSVtiWyOwPQIGZpnJZQc9NHRx6N1xNnIVTV1NCYioYTMFfwMZDcCPTJQwtgDpZBI2iWqxVzROMUd4zgjg8oR4EQGdnqmCrICQYJwBiUu7pSCbnOj9kaee6ZKspn8vVrVaaPfKUanfrZbsb8OWAl461is4LRUXKPB1MSwrCc47Dc8eHQp1BlIgcOkDjOJDhiyRDmLYdUMD955gC99+Svc0+Kg9e74ru95Bffu3cJ+c3UrqXSWNtP1PWbT/qgDjrzEgqF/5eQack/pWVsZ9icDvDLWt+OYWcDz1BlU2jxXBv4uKw1AXcoIht/P64MdkGR2pgNdpf0QkYZacLERFi1qHXUE0Bo7VfJwpUEAdRNyi/AAOpZap7EcptdA+VxG+xYlKWHDcHspOPSGulumAQQNf9Xvp96BD4NdRtQeMTfcgBhzs6RehWtmgq3DyAwHI9g1DUs6aUbHPqBTDksyTb8UZ8MKWmPGW7QOgeSLxEiUFpWhUmY4s5Ea2TuPo3kZY2XBoDENsuVTpVFLGf40HnlfibXr1byPvnhyN/rgaZixjZLdLUoXgsqeZQycSoel5+UO88wKCqDukWImoCQNrA6zEetJ5xIqbZDHkTo2zHp7c1F+aPzcKKEeCERzwFkaq9WGky6loIerK4vGEoKbB9lS3TRZIqrFUOqKFoa6O4WpA6RY1s+OlG99EuPyESSfqGbyqfsJZzs2lVOd5yqyxXwcI9bhcyRJQtKYGaqnsOBoG899XZDS/x4+tBBCKF1V2rdIPyipsjHQNBtQfRrOcVP6pgKtkwKs6VxnwDACMJ3BgTa49mX3wTCtdcHjx1f4wue/yHMZgYvzW/j93//9chDzLHJadNE6MADo3keLbTrwLBWVKLBus9tL8fuxmJq86IiPFUreOGXzyWDwUJL8TBKo37h/xtaJeghxC6K6jgw+ywhSstQU5kokXBy6E3ZnKWs3OSxXENgRE+kwMoQY5N4M3I6vDcA4ixiIzbzDFFwMnVE/4m+xDFbGNO8CEuq797ELa2FZdJH0AT+Ha3v37n288+7bsFJw2ALRC3ZlwQF7kTtJurYouDocRAZVp2ZJZROIzJ5oY8COpouvyw6f/V//b1w+eoyyzu6lZVfxvd/3/ehde7BUsCUBqKr0V5tcmUz0kGiH1iBLqQiuTwavEH/LdGYYlPjoqju2GWbIWF3dgko69KyL9jhnc1Xstw23797G+3l9oAMSIp9ZogC8NT3YNHDpZGhkehCCz3Y+x7Eq4izhmBmWypkiLnXA1vucMGqsoef0y/TN48AA6GZI2fptO2DdrfAAqjKHOrKTI1Z7OAJ1yNmPtr9grY7xBHkgwbYYQnDa7EjjHX0EOGzHAq9ztE0GopgIejYOtkWAXGp9HlRXjixPQfyao6QSMWZZDNOQ2Z2xBx4xSXtAzsGQobDkAWAQBXVMiViJJe7pRHRw3IkQDUKiAVYrKtLwk2PDcsCEaj3a+A5gGksGKFDJLGvSBkSWsiaKM5NqBk8DpbGpCFoy0MuPkfH+9uCLH+SAN4RvWNSSyNBqliKo+qtyYDoQ4/7PIDlHHLBzSyhU4ej2nhmaHG06rHTawiOQ02SQ164/Qw5MvzCy6dxPnlkseM6ytXI4h1JAcU4fAYpCOzkgrZP2hEwdSgR6b1hEiitGTYP5DLV+KNNzIIPMiXwNQzw36Y07TG2ZMVBTDjhyjyEDan2jeE7VKj7z6c/i7bffhp1UHFrDd738Eu596P6AqSeHg047hRIzAWBWm4HqDHTzKUSuWzGhsbl3oYGYjgk76PuUNtm4bt57z7IYhByUogGlWpujLou6ZPsrdIYgnaHJY5trjXHGmzUFJUdrNoKJFHPMNn0iNy4eAmpB740V9OPEKj8/eUBjoOPx88FAJQyh1nUFg/qzypYUVNiyoJbgKDE/EjpEsAMSCsRlP+7euS3fS1TIPHDr5AwP37tC2xoWAy5OKh692/Do0SXlGmodT4YBqErxluds2oJSKvbXe/yvz34eKAtgswPu5Zeex/PPPoNojaM0bJJWwwOL5QiRI/vSU9RTZypbfuX/UijPjAHnsA3GQnaW0wMxeEKlVHhr5L8Mra/c3NzTBSytl2EPDXfu3sf7eX2gA5Jp2BPK1IJYMu07wrNAw0M2HKnek2I2COoc8EVORRdUy8NNwapgJKK6GwW9ULJ+mVG93h/M7E7OznHYGgoWmG8cipcTJdWmePPGggPoguPAGSx0OY6sjWcKyKAmp+4SBk16muqHQdgb0ZHDuwCglkUdSQAF0vRbroNcDOEFFUGb3xwo6g8wdiUNElSHsmefDts1QMowr/fIjiW8PEhxoTUcMCCz8ijpANMYZzRuY714bLJcxu/o6fLsSLgMIBFrBDnZJqmAKrUJ5HBzuGA6yrHnDBOtOcoczNKBtOG0kJ1eNp1HgQG96TsLCjpMdevjOSKmoCQ/P9fTgxwP7Pj9qRg61BVNrenJB3Hu4jTc4Rk+8J48qF8iAsHU4hHPwnXffdxrEZysE5OOx1M4DDBUWHSVVlNHg5kZg+e4cZ+p9OooEhAjUTzUlu/uqCH10cj7zGRAa5Z7Dbnnsh1bm0+PrOie82FOe6z1CpUpVF8lIknbgIihDXR5eYlPf+7TwFrgcKxW8UM/+PsRQnjyWuc8FRWXbP5TEnLPs6z1zXbuLLMcowFZnpikcf0+ZhCVe3wE/4UqphmEz4AukQldQp4GBXDH31sVNXrM4DggvoKCpRTqA6AgXkkJFGjmvXtXQpcPUWUxFExuFl0czyLLHHmNIZuVQU2eS0iHA0a/wHtfBtqaCHDavCEIZgaUCqibxk3cr3B4b7hzcTEShGIdiAPu3D7Ba29LNNAddy4u8Ia/hv27j9C3QDlZtbtBWgCg7h51sqQ8AoClLPjil7+Ch+++S7TfMjAseOWVV7DuCiKa1pcBQweFHTsc1ZZxDktlQpzILQm0QonEeUtZu3J0XtI9apONwHYihwYqjtO6liKumdEMF6NmUpUPvW4N5xcX2K07vJ/XBzog6Z11QxRGh703uMoLRR0gScKEpe5HHkFDUdaVi+7SByhFypoimAIpuw5sWx+iW8xkFhl5zR/QASSZiAfz5GSHq6tr9nIP40wHC8wAMw+egfoG4W0ECdkL7ipRRCdxCBDsOtj7QF2Wo8xBQ6MiyIwOEnUxwpJ0xDJRaYDDZbwEDEY6VcKI3Pc0dlVOsLdO5CVbJdU7n8ZvEDUxNUqspO6EzXsdi2LDsCcplwucCrRc66wXu7cZ8BQClJ7G00XQlOppDuBKITXGT8eTgBKpga4j7x0YWc245rkeLu5BD2J3pugobSbXpgy41YU8rGtFMZH86iJtm6oSpKFGRS0FzTg7wse6lElCDKC1RIcyKCGiVErBll1ghtGeC8xgZpDZst/CAFdAlDLktPcqa6r7i76E7Z+AiLRC5xAKSjPTHQFTJmoxpMVTliEdYgilaF08rXzoyjLHzeAmdJ/XyVLODNDmj0ViDulbyGmn+WVQNZ87g5+CjoajL0Exw6vffBVvvfkmlmLY94bv/uh34sXnP4y2MRnKPRzU1p6oZwZiR+gdHUKHKSiGMszktSVPJpGkyMhbzxA4Cppt8iPcXeTEvJ+UhO8qJ9hcs0REMlM4WlZY8miy/Z9zpgZKCZ7n3h3ROxYYoDKug8J9mUMPtM+o/5RlORhtbe8zkCLmrI41Y+kb+n4zDqwEOBk3E5aJSilQH+MdMOaAYZzvDJqIYPhSYF5RyoLuB11pw+npimUpRC7B2TpnF7exbw1YKg77A053JygGXD16hLbvsIuKjJ3ntOjQnqXNSN2n1ht+5fNfRPOOugJmXJfz8wu89OJLyOzNfUMYg5mibjXucQqlDb6jQSh9toynDQKGtAWgJNLGWQmth0cS/2eY0nojX9GBUjK45r4bn5iPzUlYvnf3Lpb1/YUaH+iABLYgsCB6RowLoOivuSYmmjpIIA3+cLQjyNvkGKGsyABEM4TqZ+4Ny7KMDKnWiuYuVnwaY35P8waENloxmBf04KFfYCgpIpPcheFIDSnlkVFqKQUoOyp1aB+7Dql3tukiUvZC5EvdgPfJP9i2AyFuABHSX7HjDco/XYfccQSpSxU1mduolRlyCg0pmw4FS+aTqMjs2sQ7mdyKMRk4ZMhkcI/r97UUtL4dXZ8OsFzVcdaWKBT/WgY0nau3YbRzaFxRdp6BR5m/Ag7XYuBFh3pkxB2jayPXLk/3+G9wn1XN37GglPwszVWo8Y5rW5xdFGiIVlX2JVfpOFAyA2fXWIG3DuzIFVpUquvOa+geafn4TN3RNmrzZLE4kEEUgFL01jgK+rScckYJbB2bUohkl6FD+sVcK99YZkknmToVAQWPJcuRCqCkLLwWBj+1zLW2smDdnaBtByxZ9mkd++trdkSs66x/p0ZFUXKBiTAML66HzYzbJQiYwVeMJGcEx11clTTUfQaCh/2Gz336czj0jqUu2JUdPvHJ7+M+8o2PIgLRuA9rqVQOsnK0TwuQ3LOYa5hjFiL4nQki1Drb0Ll/9RlDj0OIniexdKq49tb0cxP4ke8pgAKDyQO2EbgmwgElE0SMMhmcXRh0ruzo2vbXTC3G+hpQgSFRb0FkeiC0BUspPC+6Tz+azRLOUmxUqbPChM7kHutokUiNzXQi+FkVPgidefqzUDnOONjYUK3Cilp+i8QDbcVyspDT1dgRs+0da7mA9xWIBdfXB9y+fwtWyL27ur7CE+U+PHU9chillqvnYAwDllLw9ptv4xtf+wbqquBCk65ffOkFPP30MxxgZ1WpDM/utG+OnOBbcOQTFGxm0kgiu4KWJDpboqQx9s4oAyv8ym67nsGsaS9Ejj5o8ACWdYFb0C/BcXZ2int37+LR1SXez+sDHZBEHhCVMHKbuVOECTIIVsUhcSIAZVnoKLtmpuiTLDNdwY+uqakp/pO18axFWzH0aNO5aZJrF7GKYjuUdXcPHLaOXVEbJzKRT2EvMa4Do06aHJRZx7ZhGMiNuLnBHZhtZMFptpmZZQCQ7ZcjjL0RDGTCmZsSIqUB+SERIbmDkCELbOGoOb475PtG5lqlK0ID15012vnz/H4aiGEAcTNgGv9/whZgkJklNRvoDUML43P0+V3HhhxHWcGAffMfKI9THbQHRkmMychRSaXYuKAbn6//LlbRpYuBkDPSKztd8hlzXhHbwHNOSV7jPg7MXpxzUBZjx1REjHHhZvP7a0l6tQjJbUN2sSADtxjhhNZk1oqRRicz5kQ4AH5GASHlzKqOEJD8RD5PAMqQZyA60ZER9QDMJapKVCajCmgCbAFsSs3vTk95zpLPIGI5g7hcU5MYr839pUMWMbsD8lnl/7LTKOcP5V6DY5aQ6oLX3nwd3/jGN5XRdzz/wkfwkVc+ir41lUj1zEtlMFULSjmq8cvRz5Za6B8b+yLX6rhbZZwFA0YWBQZrzMco7pXo5CTAZhLgQw/nGI0Si+sITMrvomNnh2Be5FFHBiPY8TutHUjWHbLpc2/Qh8kxViWSBbC16rnJyaV9wczazbJDTTwc75PwL/mHiKI5TMrc9e+lFirI5jpkmD2SL3U0RapNK8lRUtJaQ10X1LqgN0dgj/1+j2U9QbEVvQdab0CtWE5XXF0e8Nqbb+KFl19CHPZSuE0MQTycRHkKbddvfOnruHzvGlGocwIYrFR8/Du+E2Wp2BqFNANcQwj5pu1LAr+NgCWf39HJRSq25ggAyzNrJhI+xt+Zyrb53zyM22gjHjQIHWo+X/mlSj7VU/efwLIsmMMOfufXBzogyUwS2Y+PtLMiDhWyyXvPzKwAUTHaroIzZWpNhUYd9Ww5cxuHIgDAfRholrJ1ULX5qURpilznAXVlqL01xIn4CyBhj9Grvg+z1TTqnB8DIIvECAUu0TuWOqFSEQ10nTOIyfk6BTnYyYcRyuuDxRAMYmYOISVHxtjYGoYQ3JkZcQkUz8y0IIeaEW2gkcuZIzLz6IDmAsVwfMwiygisEtHISzg+WmlsMrOPyEyYN58Z7lJWUjSHEddzSZsKIDkVGQ3eJNxqTgo4/TPLODygU1UUwBC7Mh3s3DdD02WUuU3GfUKjmdElEkNCbJZNhFqpTLEUEqJrTacl762PztH03n12o4Tj24MlLcY4MwCfQUUKY43UNhdKqJG+qpYZpBjGucjW7oFsWV6eIcm6oyymNSf3RYZVf1/AEo15qI0ZgBtciri2EO0M3X92ax2fmWLTDM7bz2Qgn5/fWAdqiM61ymtkAuNjzc0qvvylr+DhoyuWfmvgu7/rO3F2cYrtcJgZZ967VP8icDSmYe5jng8bmhzZQZVDOwMMLFLu/fg1uTcZBNscpaDzYfmcE8H1ifCOBzy35zgv3HfBOVOW4oZTz2QuFJAJxpAaX9YRLCHELUHAjF04Lv4Iz664R5YhYIhboiAxWM7c3AfB34OIZxKEM3DyfhSECckusBGgjZEMBli2iwRL2SS8GrBUlEakI22MWcGyLjgcqCu1+Yb1YodlDXTfcGjsQDs9O8PDR1d4483X9f0zSerG55ydSQC74trm+OrXv4qGA6yyUaNtDXdv38JHP/pRDBE4s4F4ZrnRVJLjWZxBdtrPTMhyFhBRjUyvlKw5z0T3NnhCGWNGBMpS2DTigVo0G8vETcREts0ctiyDq3d+cQut9dE997u9PtABSXZEmOA4iGBlEOejFhQvw/h7dA2/43RYDuuC7Fi2WHXkXByqs5pgsGSCG2vJHUJcilQPg3GRHsxhY8mhuwOFWcOh7XB6uiCvMtvq1sIMKwXepkOsA/a2ELkwnasyBMoH92FF0i7nRjNbuAFLRXiK0wTCm2C4KThFtIaGIEWTEBLbiRjGMzcgDVuSpgKowFIXJoZWpmjOQCJ8IhJwHLcuWrFBksskLLwjJ5FyMifm9+q5jP72iAE5ciGKSk1p7ERgTWdb6uQK5ZrEMZci4c38/Q4qIyYvJcm9GC2xHj51IhSBDDLY6BrI75oZUDphBihy/Ef7nG3byuigZ5s8neyKMYOFRqgPB6uAAAErIb5w8ioSXYvRvgkrGDmSui3oeERgOw6QgRtkuOMG3mMjiHAFhTPLhwNW2IXlI1u1MXLeYJq7kyVNPocOYFcWeRVXFl5Rajp3ISIxr3M48FzvwZ2K6XWPnfwoMR4lFJmEaF+bGR4/foxPf/Yz8MKg+87tW/j4yy/r+eVvZqCde14t3YNkixH8ZUzpCjZ7T6Klrg8xhvrlD8x+c3CSAUUGC8clzxjnlw9h8rAwgzDLJIznL5MGljOYWHRxehLrc/dBXjUruLy6wunZGYdF5vkSwkjQyI5sCZSdBwJlJE0wzqrKZMIKOYNJArWQ8JZswOAvSReFNqQMhINt0yo3K0nShkMx2vJEpGEYeiSIQi6QAWWpWHYL4pLJ7mE7wGrBsgB9c8AdLZyBmAOPHz9Gdhs5ulA/hkQAhrBuD+C9197EV7/yZdSq93V2zP2BP/gHsDtZ0Q8HJqPiwmXZCnakOOucgcQRH7l1dI4cPNPogzuXQVZrCuQzqVOwVvR9gUA0yiUENFHeWeIv4sOVIp7OQs7Mfr/H8y+8iLLseBL8/wYBCdCGBcxMJtvihhiLMVIbrXHhQ+OCAlHadOnKLI1g1joxEq9SjolJQHqQJABlmyPba10oTIhN3tG3DeHniMx0wEh3SwdSispF88CW7NzpfdRrj2FK/aJqhrrFkfMGSkz+ROQJkEMsVqUUOrN7myktIEZ2ZkODnBhda7fIdxliUfDC1gQZe46jzlkxQBC1dNHtMupX8NQzXzOj8TAgBzVlJJ7ua3QjZE1JxmY40SB7PA1l5JkrFe4NBTlJJ1/8HPfAbHqSU6sctJj8G2ajvGbelcNqJcSppSOR0SXwdISCeEo68xlSZbXAG9Bb8lYgp9hniceg0kxu44ChKqjQtSowNI0ab06+lI9zgKGfMlcdyc9Wdhv6d8gRJht/bHhMiJ+fYrnGTl7ADJTI4zrm9uTnVwNSfZgtuYGoMzsGaOianHCRDH4EdW+SZEup+DTK1MzoTaXOb3PWPFMT/5g8JIwgDmYoni2j+RkxAlQA2O12+PSnP4d3Hz5izXwDvuNj34l7H3oS+60NW5DZjuVMhAJxJoR8GNgFWMrRmqojKg+z9o73I5XmtEcK6I4ThHlPE/Eo0mPip+VBAKynpvRRMIL53T3LncZRpSFdjtnJxX1uGbSDooKvvvkGTi9uIUrVlOHJgcnSmHEDDLvFtnq1nStI4FRgkWKz7ItEYEA0T/snlUSIttURmEHPMB0wgNGFGJrPI+CBJaCjIL8uFcu6oiVqvTjWkwWGhijAo8vH2O/3uHN2ijevL4fdXHYrYAWXjx8y7SwxEFSHAiWEgh3H6ckJfvWLv47Lq2ssSx1S+mfnp3j5lVewDcHLIDICIhrEOJRIy5hQnblODxCAGfd8VydoImYwcriWZRmB8SQ/Y8wkhZLLicjKfsvUJ9/JtMl7AOtuh9u37qiz0bAd6f38Tq8PdEDCIbhO+J9p3hCdAgw5k8ZHdKhsJ+zGA/OYkTEj7enUrKQTDCDkVtMJhw6pWnJLJdfEvREezEOgh1HXZVxHyCCHDjVKSq9PUaOcNwFlAQVVnUHyQtpongGRrrEeEbt8OOgYB3QM3/IsryTrXBmQyliGJFcWeNEBL3NjOcCTXGcBKI1pHYTQjsFPKXOOS7YfZqUzDV86W653Z0YKHmLK3E9HmC25yKqpUeI/O6lgqVgoFdC0PFB2lXtG5vRGpwamQ0ijW5h6sjPgeB9K8h+gnS5WuTZFzwQZFB0VnmTUEz6ewUBmY8zMZulDzqiIqGbBDFYTgvNyTZ0cvUnQra7cszoLcw0wgtcMUz2YNSdkm+/JVZnXjXk+jlCgRIfS6bgIkCyNStpc95MQ9HCgSNiYZ6MAbDWWanAXqsYOJRx1CfEiS4ZXuu6BTGE65/EnMLhH2Z0U3LwzuMqfHT27vN7D4YD//j8/DRin0u7Kgu//5CeZ1faGQJb+uBeSUzVOia59CvjN70SeY8uACJLl1nAFy8LHcdBBdDEVo8OO7hMY3+sxnfZIBDKgzch2lIbnOQ9ohl8GqxmeKpjmntK5toI333obzz3zDNfY5xlIgiVtbqIqllseAw3JQAxEuo+J/t4l1CY7n/YzBd/Gtkhjl/fuRHWyjAmEyqlEE3oIGbfUGWIZuBiFCHOfnJ2c8h7c0XvHYdvj3hNP4LW338b+0LA/7DU/ynD56CH219dYT1clGD7kIrIfuVrB4eqAX/v8l2g3FDS7N7z44iu4c+8uie9GsnthC6RCkOSNxdRnySNwhJ4V2CCl3jjXSvzyjA4XcvR7DvrEvjWkyjiOuERjErcpsDbOunriySexrCtS7PP9hSMf8IDEvSFsgYvwhkiyuWn+UU5IoSF2Vy1eG8ykIQKkEqd0LIJtoTSEQEaFjKx1mEVW7b1JL4COfhw6ZEZFZ09+hDbPODQ+DlW+NxEa5peBFswAkimf+gelFkXbwI0BW4r5ScrU4DUIli80AK7wOA95iRhRNSPtI0dBnFlQqJM7YGlYpqEO5Ph3esUeeZ8i45ZR5R3BYFWnUBddvNQMEHOKZCrMzkBhEYGz9RDhtI/Dl4B8LeS7RB4QC1jVuG51vWSnRDojGsZFV+jDqOdzIfKyjIPfdXBnrfrIkFquv6kbIUmwdBzugYxpqgyrLVWE66mRAjkhgMaC62QDZVmWglV7MtuI14VHeinqvAh2do168PCJ2sdiQg+EEXk70yVFZkMjOMkyRiBRlMwre7BVnpNZM0rSGiMDBZF7s9xmDEYShUYmYsrIms5jqUV7V98vw4wcpgnOfsls3JH3zeeRZVGqcc7xCPnKxJ/BGQahmYY3gMJz+Ktf/ALefPMNlGpo24aPffQjeOqZp3E4XA9Ek9fDgZWZnDDf8IGOZJCtO8IIRFSqSDsDUGyOJa5UjxhLi3TENwJqYzxcwrXWoVEO875d76tWxQ8LSqvruR4HMxbZjk8HFZjjDfgxBWtdEAFsl9e4e+sWFnNslmg0bvwJMCg0lTrp6GRXzJDD/CwAtxxaarQRDpVRNEsn10z2xvJ+1XmUpaQZrHYGk/nQkb8HdcIErKp8JFQiPFBXw+npqXgrBYGG1q5xdvsWWgRqsJy7LJwGfb1vePjwEk9dfAi9b6raJlmXT3xddvjcp38Fb775AMvJDq1cItyxrhXf/T3fqU5FnqPuAYJdKVwpbpj2QQZmZWhKzT02OhiFLM/ux8Bh21CWqiGpc295tPHAXMNaeQxSv0RlHSj4V1NAhOH27VsMlvgmqc7+7q8PdEDCGK6KzOXD6I6MSTBfwMA5Hs5afNbTzUfkW+vCw18rrAeVWfW7NfVLdBhrJcSViqq1rIhI8iDAKZ4FsZCdjcJ2qNYoasNN0RT1GtoRNJ+RpxnGeHU6g+S7SGsk0QEz8QMmrDmSn0iOiQ59ZLkhz25+NmHuUnhtSQY2S+JS6O8MVfX/pKiZxeBq4KgkBOCm9aEvZdst5HOE0PA7MMixxYrKWpAXlLNRAAQ5NQYh0uIoFb03HXMZlwhmvcie+iqPXEZmNnbMQJFiImz67qnNkPZLh9QdwDKCjQzQupkCDX2enL4VmxygjsGPye9Pw2OlglFh8jwmigJkp4eCW8wCHUxPJVwwGY1Rdg9QiVdwdQA5UCtxm+xMGpNt8xHyYY7rGJ0VGaiNUJaqvR1FVbsjFCIz787vKUVlr4SzbNwCd4dlqckYVIcReo6UE8wZUyo7piHNp5OBcvrXAlitao92lOSUaE1ToyYzd3ajYThRlro69td7/MqnP0vCbQC7ZcUf+IN/AC02ch6GZcoAi50RKQlflOiMa8R8/vk04ij6M727QgrHCv5vjo7P38mlzOGXR88m4RY0lsqyLdQy9EyET9cT6kKaGYSSNraQ8ojY+GF+1tXjxzhcXuPuxS3a2I2lZoz9jfE7tVKm3dxkix3ejehl97F/EskczrzknuE7JoKhsu38CjrQnKStJAKlzJ9n+zIgVVUWc4fScJ6xIEn87PRMSBQXZn844M7FHSwqdVxfXePO7TtYdyuuDwe8+c67ePrZZ2BoQigVVEEB5tbxK5/7Atw6qlp9LRo+9KGn8cKHn8ECQ0s5hURuSiY+mFF05dlKoi+DaZ6XLuSRelXcawWBnHnj2j9RMG25xM6SL0fEN7knqeDN/Vh0rmold/L0/A5OT0/5iOqCHupAeh+v8ru/5f+HX7YAqMyUnMO8HB09NnQ0eOlw60jTzezSxNgPtkL2BsDZ4+2dTi3kxCT+xJIGCY0zOs2csCK8AlEBp2JpEvcN3PsBtgFeXl2jd8DdEFGBhOHKlDuGk/eBzhppJo0M8Anxjzkpnu1hgIquwzkDGB0emZUzgEk4WYc3YhA0cxqq9zhKXuWAXM5OmSlcI+8d4qlwf+Znp5GMRKIipvNBOnBmO+4mzYGCm23J5cZ1ZAClOINBhWrOAfFJDMihblF4v2S6A4NmL+Y7P8cVqArudocpYxuVCzPxkLTPVP4pebC1T4b8tA6+e8C7thsw1gP578619h5o28bPAIBSuVQ+l82daqW8R6JjW2s4xsbMgNb1OTd4EDRk7hKg8gzU0pHMdYkk5n5bueN4gFbKaeeJS+cW+sxa0gcRBodNDhG5QTM740+ydOgz29L98B9yBvhMOOF6gsDZxZDlQllunVHuHwZ+vXe03ucHpxkRJ2sGotn+2YczsuioEXjtG6/i1W+8iqVyb77w/Mfw3HPPofXGslKWWIF5hTG5GMd7JOQweBGh7HJGANkFk0TO4VDHvca8h/QeEQN+j7DhQAIZizMQr4WKzan6efzKa/dgsuExkdMwz1gZGGXOYOAVwNtvvgND4Pz0HL6FgjHN08LxXC2d90wClRCmRkZBomi8D1h2H/HReXbHqGSe3XShxDMTLhjQQuNCVKJx8M/uKc7GzRZWQK3kRMYKdsuKQfI1w8nFLXjdIagshffefoBbt87Y8dgdbetY6oqyLAgH3nv7HYQmxxfZUQQF3kqpePXV1/Haq6/Dlg0eG6gu7njx+Rdw9/Y9bJuCGP3PRChNZH6UAtN+Ip85n/HQ5pG9beGDO9d11i1VvmHonrM5KwLkznHC8rDIA6ErRpI2Ca0Lwkj0ffLJ+ygLgYJUK36/rw80QmLqnWp9LiwQA22IVFYUzD0Td2UHsGGEm34vNDq5ShXVBodhOsquWiqz8phGBWksXCgCUQOi74zSrw4H7NYVy2ooQhuYeebwIk1Q5G8jtRACFVYLepPRyeAC3IbhNlrj+DMdSGVbHs7NHAa3Y4h3lpYsaAxqrcNhF/EVRttZCD2qOauAdVEDNDE5+RDZUYPRUTDyI61l1tBzv7p3yjs7ENFVhABm7ivlymMnLB0X3iZLM97aaCFOV0fDRuiXo+cXZHmOn+vz2hDMgGUv04dnG+ngxADMphKtEZE6g9/kG7kHkzqjY5/chvzOimVJPRqH6R/KOdEBlELovygYCDNEIYFs8nW4V+q6IGSYPGbgxgTeR3dVYivEgWVwzKRiOrN3jHq1HLx+Ps/ZbCtN5I6wcB8OryCDnMw5udYzGJ6R5lKYZFiEhg1yjEO3PhA+d9r2UkzqwD7QkDynifJQwA9zH+R+hz4oFNT2oZYiIdCQ7L8Dwaz5K1/5Cq72e/RaUJaCT3z3d8JM5aBEvxBYbAa4ZZFGhBOVzeAkxlWQtDrEAwEF2grXBNUwuyUK2b2TUzbaPfUcQ77J8uzaQCMzEMuprDHOR5ovJRJHZzU5bxkADhJ5Yi+erdAOr45f/dKv4tbt2zi7uBCyWgZiw7NDrtGyLJiI8rSttRhGm5IVwEgMz3Kz3g0EE0UrhagKABJjRX5XkJ2l1zyjnGCdYnATFaNe35E8QQZ3OhPFDObAyekpg7Ogvbx8eI3TdYelLNi3LvK/4eT0DJeXV3jn7bfZ1DDuT2fGHaXs8Btf+RquLjfUxeHguInd7gTf8fGPIzvVbkgMZLAOcdpG1pEDGo+eYygQGc+dparQWQwE2lh/BaeDRG9CVzrcm4aAKjAXOl7MYFV6KgYcGks/d+7cOTpjie6+P+zjAx2QeO+IpWApO6IH0eG+IXX2s5/fo90g1iSymlk1eQZQZqvMRRuneb+BKOTOMDkEZgk0FK7x7kARCsKjWMFDVox119YblnUdxLwUGGPWWoersFIpVezq2LE5dnoOcZOTDkNFoi0jtUS2jKyS10/5ZN7PJO6le00jA20ktrpAbbc+om+IcJny8tCh5YMhypBOKkEcivlwm46ARdlukVNxDfxbjurTI4NTSSg5MuM+jiJwGryFzzoPf6I0+e8GIQFFWdjNACH5NBlQcc1l7NUeaFawVCIZgmsEkcYMfIEBi46x3yIN50EFGHR2kSFDgQ+Je1w7AzlD42AnVK5/d2C23RpnDBG7M5zUZQAUNevmEXLiWTOHHKQKBKN9PgP2uRYGvTduuK2BAHW1ljMjcxy1gtxAD1JvB+LXDOXgkgTNiQJ4d+zWFQhg686hb6UgmrLEluqdR1eUn62zxzbjBaX4uL68l0SObqBXwaAwyxlmwMMHD/FrX/oSjXkUPPP0U3j5Iy/w2SmA4j0EcrLtKAUGeVoFRRC5gp6SIQCTgLlHMlg33ZuuxFOvJxHDTIbmrBs+uwye9Xfaf5alqCFqN/dOwAaIGO7whcFHchASCUv0wiP1OZg7Xx82vPbGG/jOj38HTk522LbD7HgZ66GAy5TYjMOi0isKHI1EzgCKLVjF5Wg3ZAQUYKhMndOQWZ6Jm/vADB4smVRUWJTRsRaZWLCuMSbmFtnlstth24heFBScnZ4zEW0OR8G+B05PLnB2eobDw0cqHwJlXVCXgoePHjB4LFUNEBOV2j++wje++jWU6DBjMOMdeOLDT+NDz34YB0bcSO0piNCbKGIpVXNx6vB1c++nfcx4xZjUSufF54+5ptoXqbfEZ0w6AcxhZeGsP4PKnRhJSZYAt+54+ZVXUNZKO54dnoUS9+/n9cEOSEy5WzKI3WBYkFi3iTTJ6Czl3hMGZGYKUJHTDapZZ+2e8FUodaTRSmXALA8cGzGfIkjAMHDcG5kBOnaLhvYl3KbDbEcEquFq5QiOiY1ZOx4wLATVGSXLE+Y1HAUeal++uSVMsGs60BjdGyxJ0MAtVtG2pqmkyYIHqrLZRF9HO5+cWLGZqeoyUEz8GaRBYTkt24mnjTQZ3Ly8DDrmsChgksOQEswKqjLHHN0flm2VALkcbGPj+O0yFAqR1yV9GXYZ0d0TBZoOeHSXYDpjfYK6VWJcDQB+nmXQF7pvE9mYz7h5V+nKRuY4Oidk6FLKmgS1GXfe3HsBb11dXnkFQv8g1yb4IAPbYZ9iBia8z6MOJQTK4B4AQ1I91HZoI16fz8NNLl1oVARgy/g9BI10REyeRSYPxiAKWSJDUddbGb8fPgMPDnfE2B/zn9mFNw7SQIL86Lvna94XZQJOTnb4wq/8Kt595yFsWYHN8fKLL+P2+TkO/ZB8dZ7GMKSOT07JDiMhvPUjmwEb6zpAAZtlyVHyHJcsdMMSUcUR2hbs7sv9AnLGyJmYgUooKEAcJRDHQf1w9qYcycXd6iMQUBjN/VDATouy4p233sTV9TVe+egr8AL4ELuz8e0Fk4dg4mKw1b6mIeH3FCJKabtjSOMDQ+beaXHK8ZohbSYDw8h9B6oXV5utxkVk6BJc/1JYGoFsawZSmTSaGU5PThRkcW7Mfttgyw5npxd49PAaV9fXaK1hrRxkeHV5jcurS5yf3hrXhmBg8dbrr+GNb73KUQk6S+7A93/v92PdneB6O2hdQFuLtEFCFeEjwQywxJZ8sXl+bZxVbkW7YU8y0E1RS3iWQH0k4BmgJlLWDUIvFbwUw9YD63qGs7M78J5egr4pgcb38/pABySBAKp6unPBisG7MrQO1LViSF9FINutrBrC2a7ZWoctVYlugYcmbQawLKzFkSi4wAwDCeGAsw2BAisVJSfxQuS7mGWPs7NT7K/3uLy6xJkIPwDnS4QVLEsB5bHZYVKtzGd6w1TOAIQqnoExtRKZeesaZiA7nPywbrkeN2MGDC5AfqU2HWu1DLyS1GWmTMltfDcy+9JnUYLfj4wfhKCA9+E+MsC8v5z0q6RlGLQ0xrwsG61/qUaLIJKUWUT0IoKojtJwVBkc2KhxxliIGHBmtv7lOuQlkkfEfdQ1pyWRgDQFOdxRG4XrYQNMkdGfDoVOtswgGPM+uSoKvMMRmeHF7PJhFVGOXIQL7vGu7LzM+wIUeAY5VVrDOF5fZNCrNQvQeSMd6QyIQzcTBtjCWjp5TlMobpIqWcZw53j7yY1gNsUYJlRepBOhYqvWQuVZ1x7KTC7XOR35USiIdLgMGmZZBWMt7DdxMvhsO1Lcb7/f43Of+wL3TDhOT8/wiU98AuEb0JpIpHSkVgIdHX07YF1XKZaWgXpkkDwKvUff6z6DvN/qlc6BwU6KgClo1NnH0V6+gZqMgAxIRdQy0DahQemAK0vVCfeHgmeEusTG0tKmllLwxltv4PTsBPefuKfWVqHKUNk76Bih/W+hgDyfRgb1pVBdw4CUHeCpBdJRFrD0vIjvM7HTqakEzLJYtQI4Ebx6dDbzHGduBiWI+VwcLGNEVBwODaVUrOvKzhSruL7eo/WO9eQUHgXWWRo/W3eI7ujbhnbYA6fnI2Dluhf8+q//Gi73j1GWhSVdD9x/4h4++rGPiR8GDsQM6bMouF1UboY6JtMWj6DfMBoYIs+unn8g1DHI8irHm8Q4I+OZQlzCnKmU9Wer4oBBCD47K7fuePrpp7CsJ1yH4739W2/l3/L1gQ5IAIf37Sir8PH3sKzX5YY+yvpGll0RRjZydUN4wf7qwOgXgXUBWqN4DMdXs1MGUJAerK95sL7fLeu2oB5JZhUoIwK+3u+xnuywxtSFyHp1MRrzAbdVHsg0mjBiAQUx/aPUKgEGSumkTYFHGudiYL2vz7LTMABmw8gNYz7gbsBMOggG9M6fe2SmpeBFS88WVwYnFC7q0ywY65gRM8yANDkzG0m4/DhjLdAlc7TouPZUVsyOAIPpuSjSr0fD8eL4vrvWiMFflu6KxJoyS5wj5wEK3R3zTFIdklBpF4jg4DrzuunoejSRm+UYy8waR+auWjgH9HHSqCmDgQUFuLK0ANfETXIVehpohNCZhloEv3co69HP5YSzNOZ9BkvIoE17oNZCEigGs0ImX/wDn4Y7jT9lfsQNKAVNMHXWlNnKrDPZ9HdgCaQr6zYHzA8MCBSYrutO6EnJkJzaGLlnEIPrkx0XNkiX+cpSaBnt2Imy3HiXc5ZKopzrsuILv/J5vP72ayhLxeGwx/d99yfw1JP3cb1/iJwSXcFyITITLQWX11c4P68DlUhHKVLS3E8RkhoI6pkcISbHr8llS6QsYJajCo7ONMZjHI6M68TnlN1uUU3ICrsz0oHpcqkDksEIYnSlVDMhcEL6euDN197A0x96CnVdsL/mdHPFlUjBwvkcFLyhC9WiI7VxnQpwxatBGNuTfQZaieCEbNDguegZJu8quTJUl5U9jgxxZGdExC4K1EJ6VK65OVTXJcfl7PwU7z56B3UJ9G2PLfa4df8Otq++ip07zDtOFoOFY9sfcHl5jTt3gSjU+VnrisePHuMLn/tVloMLCdEA8LGXP4bTsx0OhwOvw4jk1JqlL1BTKDKFmncd3oEixGgEc3aUcE57n8FJlqNHYnaU5LR2hDxnUgXAgx01kZ1yMJyeneH+/SdkB9KvZYAMIN5fl80HOyCJuAlbp+Ec2aqDtdlZvnAokxInY2tpBpUxitxkBnHd+hhexgPDrLr15DHUcdAI7wJDlj4STaH2BRX8DL117OTFuXk6Iic1llkfnfXedBTpDDGyABOnZGSsygR7qg6O8QWBGhgEtyjTsJGAGQi1JdNvmJwBAytEio/RkXtwSmsoes8OHajMMe7B0ggflzCOCK+pIIWb7xmTazFzWZN8+ihj6fO77nkEMFYRdUhl6eNtrKNBPJA0iklwG+sBGJKUGLNLSD/MgK/UOpCfIh5SMWaM3knKzVbemRtNxkfycQwrwikXTn0ADUeT8zYA3vdIJKeqlXcxE4HXMgIV2biMgM47s3fftmHEXNnVEf6uJbIj/kjy5XjNE2HKoxfjn0RTuBR93GtqhWSJio4lk4Zv+7zOYNr0bjPNoYpQtwfQOh0fBbdc5MeCpplDJDoWqsCqpbx7imbxVYXY5Y4DVLocyeFco6zTX19f45f/x/9Qp4jhdLfi//qBT2Jr1yTUy4NHKUKF6OiWugJhePedBzg9PcXJyQnFEfO7tdAMtFhyGUtiM2T/drQkbRCAqWOiTrEUQjTpVxS1mqeEvot0Gfm8+/DYIxgtCthoT4CwUHlRFxw8M0spg3R/dbnhwXsP8Yf+0KfQt44xmsBkAzNI484a+4VFEu6ZjsldSyGzpPTH0MphQCmGrxxeIkUpqTADm4IymgzGXDK9IeQjpo3KFmBlicH9UpcK7AEUw7pUnJ6ttIfFgO6IuMadO2ewCrTecHV9ifOTBUutuL4+4L33LvHscwumgOYJvvjFz+Hd9x6jnlQgDoA7zs9O8YlPfCeiNyzFRF4ncTn9FmwimUkKZpCtROjo+RH1pCI37/t4dMcMZrLzLvdFDj+Et0Gczf3iPVVyUw23onfH3Tt3sFt3RIxV3p6yDTjiLv7Orw90QBIe2DaKyORhM0EHqjzCoIWtFVBWa2bM4qzAQcIRxZUcy24nlKGTDBuzp58zY3LYUlAAp5QR0Ax0IUPuzP5kpHoEdjowE0JmFwUhTmXIltmzDyQkHfgohQ9fooF8Gf1GqPMn5ZdpZLo7uvkR272PzA6uOq4V2FKm89b3FluGQ7bsNMmgOSS1NBANkzEKTJktIIPB7DAAMJ0ZreGRoaCjSTs8kGY/9qGZlRu/R0GZKZhIkpyFZuqMmCARGAwkhobPjlCCRHryc32U/Uxp3GhfVCaSWRif2byXWitaCzquAZlK6FpGMpDlrgwyDTlVOuvGu7pKMp1GAR4UPwP5PsVmhmnhKBGowNBHUCgHQEqUR44f4mARZWije8ZbBpYJB1PLZcDAmnEzAklPiD5RCwywL8/GjOs0ZiADbnd1d2mvaJOTxV/GvCWATqeEoaWjwayL55C+SIcixHAEt+UosE9jns/AWILj85niX9949Vt46+13sCwLeuv4jo9+FB968klshw0p8Da4PphBgplht9vhNioeX10CBlys0+SOoAQZ1GFoqqQgchjGvf1WpRwir0ogtBc5DiKdL78j9C28tBmYzzPGB9VdImWZfaS9AdSFAbbpWtoRwKzi7XffxLo7xb37T2A7SGQNECmTZ6xqL0Xk980kZlCzZRuLzgpRX8oitOgKcqFsMbsoVXrRXioqdw/FZ2ZYY8XS/sLUvWap+DyfRa5HERq0LDmfrOBkXVHdgG6IXnD16DFO10Ukd8P1tsft26fAruCwHfDw8pLHxR3LsuB63/CZz34BKOzeCu/ozfHMS8/giaeepF6OHn7ovmpJeXy/cS98QLTJpmDEYEMQ8DjAG0hmIluFa59lv0nzCJbSMbmA3IMptKgymS2IAhwODefn5+yydCJ9Ju5VVenIjgbg/k6vD3RAsnlgybZaOcL01NlCyR3f0VtXt4pjWVZJEjs6HKWuw1GWWgcju3Tq8SXfIXCkARIBd8JyqUpabUnXgj5UXxVZRuBw2LDainq+wr2pFyh0vbjRIgc5ruyaycFjdF5ltO71LdX5VPNFl7iNNpjH2Izu7B5yhHi/GQxIWMiyLn2cEWEY5nAgnMJpBUbimnOgFHpgqVQ6TedN5VaBtkf1Yg6oY5C0qlicLY3hszRCJ5GtbEAKhfFpZ817JJp6v9CsERBmgJKKkaH2ZIyW6dnWSTSt5YXq+8fsB2UZw+CJyOwAYLoiU4ujAdBKTO4ADRbXJhVWlaFYgwU1cGDMbNe6AEm4VbBVreDsdId1rXLghrrW4cyKFV5Q70DvKObKzGKshw+CIPcvGkY7ZwayzJYZlA3SclBie2bxZXQ5DEXY/A6Jt4W+7zdzIyaKwsGYFJRLI1u+Tfyp1IKyGPrex+ePCL3yVPgAfYJdBHG8P2ScAY1BSGc84fsQNywdYcBx2Dp+9dd/FVeHS5wsO6zrgu/5nk8qO+QZzAzbQCi7DOPOVt51V3FRzuDhaK1hWRc5c/3uWJHp/bOsPJEU/f0xkqfvgPYc0c1x4mZgdLQOo4Sb6yL0KM8sitRwFaRmoJMdQThKCtKxL2vF66+/jtt3bmNZV/TGTqswZeymwFswprGuKrl2nRUrY1gjEtmQqFMpOWyQztjh49mZdG3GEEUzNQ0wGO+BsScz8cERauuWeGWub8Hc4PzbxYClAA2OGh0XJ6uSVAoYPnjnIZ559mWsywmu+x4NJH6iFvRuePD4EXrfmCjA8Btf+wa+9fobwBIazmhYlgUvvvwyTs9OcegHLnbYDRDT5EtKokusMTHZ7T1jW8yBo5g0AIQ6H5OhFkrwiDJl4hFwtbC7yldKtowF37JS9NMKOXzNAxcXt3Dn7h1+b+FOjAyU8vq/LZD+7V4f6ICEB6Kjt0lSpCvONjAawOx4yPbaFDwDgEo5QUb9MoIFdCJdiEipBRZdgY+WO5xwuJWjA59vSCOnjW8FvtHYvfveu7h75zZ6kNBaKtt1MzPs3gaajjxAEUBhdmzI2nHeMwMF13UrRZ5wnps4NIX6IwGEVYT1I+ehtQGGdkCiLiGn05HlhUAJok05VCn6Mf9kvibnItsGNStizMPJ4XSBvPSpHaHfDwdHAGBk4dnHGtFVJw5w6rONZw5g6lIgEZdQdK+ZEgnRZhKVBzevu5D7k8FqGrF0Rabs1SBHDQbCXY4yyYuJWFmKtIGiRBwWl6C0o0dH947FKvkIChAx4FcGw4dtG6W0LNlZYSmwZDYSRAaXYmhtU2Cwcf1AODjLux4B62mUYvCkADBggc6RAojeu1qjR6SI5OhEclLUHu3Ods2h/ZPpdv4qkodQYDY5Ja0dcDhcIWJD9wNygivgOByucX19Tb2VUFCDZEdkKUxoz2iFnPfKQCo7W7rQiT7aWLsHie4AXnvjDXz5K7+BUk/Qo+HZZ5/D0888LafrI4AxWd5BCldLOBEooC5EdUhr6+N65KHnnj1yJpnNEq3Mmv8x+ZiBfjkuRWDK0ecHDbn5gVIFUPM84MYzmV07JBeXb3telkmAvj/bWV/95tfxyU9+EmstcA2JzGerjaRmqQADC5VOdQ+DWyPbytlRBcu6UNYekPRAl53VgNJBYpezPkJWIKdJJFecL9nWYiKNyAbkZGBE7sH5GKxworspabl95w5aAIWtOXjvvUu88tFb2O12uH5s6BuAsgB1gceG9957Byw106Z9+ctfIRdvYYDmHrh75xY+/l0fx+abeDK0W1WBboksIaocMzglaa9m11Qmbfx3+bmU+c3zId8x1L21zxAYBO9QwMaS9Tx/5LXw8/ZXe7zw3As4qYtQTCBKDNQuu1PHSIXf5fWBDkiGtoNT2jY5FQkvJ5s61TUX8QqyWwAIbNsGIHC6qyhW1XnQU+CTB7NTLK018TJC5MWjzcse8220aR0TRrsT8j89PYXXBfttw+myjCmg1B5R+QTS6Cj8zC6eiYVKSzCVIaahggiMmW1zNDfXyOq8vryeWgD3Qo2VFB0SKtA72+AGlHuUXyaE667pkwOJAKDALztkBulK8vgOIMmsxzonw7gaRvttXnPC2PyPDMASQYkR0bv4JrVUZWGT05Dia3nYGC9W/VWZ/JjkXI6D7KJ7HIkSyQCPtCUXOTN1D2QbjcnIRvcR/JpQkd6dBFrdhwHZ8UiSqQOLLaOdMR3FbreSQItggxKOicV1noeAAhag9UBtHW3b0A8HXq4Bbqnmy3tonZloBhEj4GUkc9Shw1ZYzJR7rk8GcnIsBiC7wQaxGInCHbXbWhkGDuAyvvHa63j04CHWXdUzM2W9FYfDAe+88w7uP/EEgzqfZdRM9Vhym04oef/NXeRNEXsNoLheR+rs5MCwYoYv/fqX8ejxJaxUNK948ZVXsJ7u0Dqn+hYYciKBC13yEfDO7YER1N5EiY5h9LHLjv69R0eSMMn7KkqVRdA0hvXJNzMFCLyHnFtDRzTazI/QlvxfojGp58G9MbWA5MWZlA2uD1DLgjfefANXh2vcf/Iez7BiiwxKA+B5ENep98a3HD3zONo7tGUxzgOP8AwSEKkFRNS3yuZ0D3XE6PsV/jC5iVH+QnLgIlBcz62wPELyt8ociLHvARKBPQIXt24jQ2CzgsePHmEBcGrAg27omyPccHF2jqtHj3D1+DH2+2ucnpzinfce4zd+45so5QSOPZ+xdzz3wgu4uHVbZUwbtzu4eZZoLWiTxn2KC6PAONHG5GzcQOAS7bVUc53+rGtfRCepnE0Z8pkZaIdKQpXIR+sNt84vcOvigknyKLPPwDdLkEeyKL/j6wMdkFQRQK2Uo0XXswyW6OpCWLttfXZrKHp3d/TDhuura5TzinXdASicXdPV2utBddQiZ4RAXSqiN0auNQmMgbCA90bCT9yso5diWNeKQ5e0sbGkgTT0IXjAQT6LS8wnHFGSCyBW+NHMDBLiBBNn1wAmMTcrd3EklBDKQtxd8sNV18N6JTMSfVcwkTB9l/sUPPOgdDDVEl05nA1fZYWTMnvo75GdRXRSsyPIxloPYlVCqzBdgE00AzTMIYc70bECTzKqCV0Z6wTdey5IZhLzHYwrHHUpaB0SNZvdC7mGub+S+DfGcmfXlGBf7x3hyk5sQt8jk5NxKArYMhMkh0SzS4oh3BDoI7gqVTNqVLKZk2CTWArs9w3Q9FB3x3bYJr8DILeoioys/hsPZow0ycmHKTP+AocZVvEzOM9plrOGEYIRoi4k5TJLs4H6jfIJU0YoZh0GthTDN7/5TZRiuLfeUUAegLGVfVl2uP/kh3B2foYxMj6Sj8R1bK3BjIrCtVS0mO9rzjOcRtQW3mv+XgTJ8peX1/jCr3x+1OPPTs/xwksvYfNGETzPwZc2eEGBAveGqoCVAxsZ4GaYloPNxvyq4fgn0Rn6ea5ZSBvINZHWgiiBjffnZ+usmaNtLvlw4IbCsZwYwOC/q6soSc1ZCrgRbH5bAJrDIdd1wVe/8hu4fes2bt26jdbZrppJWcYSRJHy96UaGjaQpXSWIb5WHHGGEr3N4Yi5x8a5Hoc5r1fZf8l1n/fN5ZzeMRGpFIk0cQKLEhGSNHVmh7hkRSKdAcd+v8dihtu7Hd7wQN8aDocNF6eneNsD1w8fY7/f49bt2/jWa9/C2+++O0p6rmTi49/xEdSlYH/YEG5DUwoKSCLvNib6nnyRgAQz9cZjs0ZSvd9EzRQHhkoypajMCydcng0MxwFpqWOP5MC+w9bw/NNPY11X5WHkjzTtVwMbEbJK8X5eH+iApEdnGQLZnSIDZ0CpGi7EoQQ8mGANHqCWQMWCO7fv4daFYzt0vb+jLjk8SUEGx4UpI+af67JKVldwWWpfBBU7E873TgicMGJD7wecnj4BABqSlBOFj0pNnu1YkCN29OD0yXTmIR6LlWUYigKSKPvYODZaY1m2cYyu39YGfF1Vh+TWxTh4AMbfpQNxORcEG3jSGbMrJ/kKNh3ZUQRPdISfu0iBEN5EpCsoWAbalcSt5LuMI5k1HaSkOL+fOhvZDcKfT2l2QvL596nGmE7MkLLtgsZDRDcZz8wgo9PguzkePXgAd8ed23cnyoPK+1cwMgPIyhbdpcJVTmNWVofDMM8WRMNSqshhNgJa7l86994yQnRUGBupJPhmBrSWe5JlyMN2jS996VexKNBprWE7HFCXBbuTE6ICne3jtU45ckQm9kcdS8aJuoRnpS+jpDp5Sq13DtPSerfecehUo62C3XvjOrXWcHJ6inVZqE67rHh0eYloDbYsJO/CODYeRDLCAw8ePMA3v/VNnJ+f4XTdIQI4bAfAWKIqxkBhWbVuck7ZfVMAbIdNtfCKpS643tjlcr0dsKsVX/iVX8HDB++grjtsbcOzzz+PpQQePHwXh9YAd6xVYyZ6HxwwAEpuaBeWHVuBl2VBM6M4l8qgZvz9EYj3Pte+5uRnPpto4hhVBvmdm/vIIk413wAzZZ6fDBIYrBRLDlrBuu4GUpWibUUaIlYwunWSd8TuOpZT1lpxOFzjK1/5Er7nk5/EUisR5whEtAxRhx1BojNmgITdCG76IFofeV8OuwsNbGydWfumACKI1I2PKwXeOvdHgaah20hCrBYFnbJXVoDO8vtSj7Q1ZHvcJ5pgYMkNlfLoJ7fPYEswaOuGq+truAHLrRPgNdpE75171gyHwzUO+wO8AV/64lexbXvURXa9bbj35JP42Me/A603DXIVuuaGsogSAAY/zR3VSHotafeFRmXmMJBNA3II4HHDR6oh595hQJoBaMo2+LB7tFVcm1olHO+BW+cXuH379iwBGThgMtL+M3Cui6HYHu/n9YEOSGZNLREG1eeziR82HBsAiJ3DhQUHlbHUnpyMguYN3TvRgpKG1gHryJH1jAVoTJMLQNKnQELthxSAMsTojABsENu6Ozt1rE6URS1xtSzI2Qou2d1R73PqM/CwiJsAEHZuDqhslLVxLRZGh0wfdDxurkj42sayHbeIRbKqA4A6bkzvoQHJzS6ovBhnynjWI4EM3dlCSNl8A2CFI8tZ0glyOBPaBg1aD8yWRmSmwwFYDq6HFzrVZVgoudBIBV2VC1AmWgQZQcHR/ItAb1OeG2Ek56GgC5UJMyy7gsPhgK2voGuQOFNIkjootJdE3RQ0Gw13oyuDMHh3g3US2U5PToafsaCxKRFYCpn8IZLfdmiIE1f2ouCxO4qC5VCQetg2/NqvfRHQ/kyki/Y6A03/LeB8tX9GKluq1HFkzJIU7CIymhXpg7hQLxr6UtUOnr8vBCxrVcUM9+/dw+n5OVp3rLsVqzgiBhskVgN1Xa6uHsHgeP21b+Hx46txzXScdDjum7ZClhcx7jlr8R6Tn9Mk6MZk0fBrv/4VlHVBmMO94d6Td/G1r38VfTvAzLCuCyxmdx/LocmtmRlmts1ivIdjB3qfLdLLsohTxE4mnkEGkMuyoNSK1jjrZNmtM+uUfk62ttZCe1LUIZbdhcevlDHg883vLtg2Bi5LZVdLqQophOatyzoCU4qXrfjK134Dh8M1Xn7lJcxetEmSDQVfpWQLfNpoln3TNvQjJGYgGUKT0bi/zDFmwaRuRtWa9nB1ToKD7TDt2bcn5wb5ARp3StgrWNe4qxF4scmFQUytC9G1qgSv8y6ve8M1HPV0J39j8Ea5iLosuD4c8PDRJZb1HXz5N74CoCOHnkYxfOKTn8C6FPh+E/d8GedsDtCbZo1IqM9yGKB2eAUBhUgmAho5McmtTNp17nN/ZhOBs8S5FBuDXdNSFnAPZxC0bRvu3rtPKQv5VZctAxgsjYnRRzNgf7fXBzog6Q3YzNF7oJbAWgtStRRpeMcY62RP5wA6G060WKXsdO964FJ3dSiAYRbVO2HdIpVLKDIPBKcvdsK9MBu17fAOM409LwX7wwHNG1ZbkfAnyUMxobLKThjWgEXSkg2P3gcMVnQN2fUBT4cyI9aCJJQCJQMHCIpHlh/UtpjrJCMJ5OeVI25B8hSS88KGjlJiokLB783XaIfWv2d7LammJcMwBm4KrsxnuSthawDjgBYFY6mr0DszqKrMDoAyqON7UX1fvinVVAMqP+j4uT4XVmBlRfcFvZyiXtwFCrlE9RxYD3tO3fAcLd4HF8eEzrhacJOkEpo8aiG0yNgVcOiBs5MdWtvgvTGQirk23h29NaJnVtC2DpwUoFb0EQz5yLh3647PI/cU2BWVWQ85G1kGVNYVyfuZwUhC16P7ipG2jpKJ72MoxUdQx8fF4CBK3oPsllxa7qVSSNi7e/s21rNTyucHp3ZHdlqEpp0GRd/IjyhYasHtWxewAC4vL8cEVD5rEp9TV6IO56T10/yZiOA4+HAcWsO2UXn54YNLPHz0CFYLtm3D+a0LVDM8evBgtHavC83nGKY5UmyuYTUmKWPGUf69yMyDjxYpRpW2K5EW7l0GxzEQq2JlBvoFVMuM6TQhmxFmR2qaKbzG42ABrHWBWcGyW2GlYGtNpS7DUitOTncjiEQ4uysArMsOu2WHpS743Gc+g3t3b8O943q/V5w5SZLeuyZZs8TVtk32TFwwD+pnmEi7Vo7ONkna1Wh/aq1AZ6cSDHj88AFOTnY4PzvnfMhaxeXRgL0SWiuI+MnOkSTb53camHSw64Tb2JD8pkx8gCgqNVfDnYsLvPPgXVjltR3aAee3zgAjanu93+NCAwabOx48fIi333oPV48foK7iv8BwdusCH/nYR3F1fSk0sCLQYHXh3nFgUQC5ZAMFOlz7N43ZaDZIdASMjUanJ1iOO9atye65NPeUxIhhI3OuG5DlrDpKeW1rODs7H2q7LMMp+VDiSxusZ/l/omTzsz/7s/gn/+Sf4POf/zzOzs7wh/7QH8Lf/tt/G9/1Xd813nN9fY2/8Bf+Av7RP/pH2O/3+NEf/VH8vb/39/DMM8+M93z1q1/FT/zET+Df/bt/h1u3buHHf/zH8bM/+7NYlt9bfNR6YK0mpVOgW1BQRtGvu8Obo9QdCdXGnuumeioUpcNEKxWiUSRG072j9w3Jt0Aho9+LTyfmgVogZ9GRxCLXQCUzkpZYmQ/sW8Pj6z3WHXUlWBd39K0J4koDVOCr6ofONrLh4gezXvU5CT0VOe7eOlAq6rKiZ81Z2QCgDe5z42UZi72waQiTn0AFR4IuKnEcfTc5LjaGNbFEQ3JsrSsMdMZj+Jn0XaJDugYZQIXKJsxmS60Yc1aylmkhQp2QnoiRMbHszWsXXjQCptnlI36DkJwsTCVZE3YUMIVpP6x4/mPfidtPP4/t7M7glSx6VqkjQNhUgxiDbBaoEwtNJD5B09kG2/s2sprWDVZPUNCwVsCQgQv/WVftF3k9TtopI5vu4SA4ZkDvzHK54FiWBXc/9CEcelfZsCP6bAevo5PGSWBNxLHqOQOawKzgDTOAS0nrbgvLCL3DS4FbQSsQ/yWGAyUK6ehhKFZx7/Y5nn76KbTDfqhTEpWqcFsQdeXIhroiRieEygEeKLXi7t17WJUAPHz4HjYlBoy1GCgTZs4jQAK0hyNKaNIuqMRpC5oDb771trqlgEDFs889jxbOAE/AzuaucqdsUJ6zPKZyfMnMSV/hPfVbdGYQKjVnedCF3soZiNeRSECP5CoZ0B1bivyZq8VTCWlhyrFt5IlkaSizmyt9xjxfGnro1MuIkskEsKhjAppKDBiurvb45je/iftPPoH/5y/9EtEQBSLFiOzUwYMxwH0EG4fDAaF9XZaKbWtYlulQa4kh05DKuzz0RHFK4UiBk5MTZNdQMbaj1nXh9S8FpSxEjWrF4bCpRDrJ9HW3YyLYCwwVS6loHiKPU9DtsB3A7qsN2/4a6I5bJyveE//D24bLR+/i1vkCxkyzdbbuVvje8dbrb+HrX/saFlzNsSDh+I6PvIgn7p4h2gFrXRHRcVA51Y1D6q4PfAZbciVNZNEgF4o8xz54ZaVU1J0QdqH6KOTUsKuMyWjvG5D7qjeE0SbmOQe6kruA6IDwcGyb4/T8Ak8++YRsHaM460yuQgTcPAwR5MS8n9fvKQL4D//hP+Anf/In8UM/9ENoreEv/+W/jB/5kR/B5z73OVxcXAAA/vyf//P45//8n+Mf/+N/jLt37+Knfuqn8Cf/5J/Ef/7P/5m32Dv+xJ/4E3j22WfxX/7Lf8Grr76KP/2n/zTWdcXf+lt/6/dyOUiJXELfhL2XZJkLaGKdNtiK5Fl2qUjWcBIFm6t3utTRhUFUZENyAVwbgDlXAD0/Yzq+RDkGeS14sET1xunZGQ7bhhQ0iiZkgRHOiFoJN8doPSXEqEFLYFthysCH/q55qEYKOioFM7WWQbozoTrNp+Hgi66GjITckCYEQT8zjKwyiWZmVZouaWR5MwSfpEXRuyBaheKmDLkYGeNygvn5bjTmiWJJ80sZjQKIcMCCTZvaA4g6rjyfxxgTkKWBNPQdszMr95NIthFs1e1uQAk8fO897L3irfYNbB5Y1x15HiF4O4MilCGWV4wcEPVka3pvjjNQ2XA9gQvSth0z296aGO8s32T73XY4sE1cQm/MzimCVyQeBiNoXs2YQckDn52d4fu+//sRuxMiEmYw+FB8ranj4JS9NjDYyqwqnA6+pdqrtG02Z/bXvaMH51n0APYR2MJxiEDrhq13NHWa9R7YdyJKmwKQ93rHHp2cKu8M5nrDo/0l4uEl3r26RtldofUVV48eYF0qdssOyCzWG+6cnzLoa3sGJAh2IuX5iyROkxjrFP4RkkDEZOskMz+63OPxHmg4QaDh4vY5Tk9vsawWif0ZondEFf07gkMQDJkT4iiBJYLlMQLz1judtdAMU5Ge9iwdj2IHrd0Q0pNdKSmkZ6ZUQfON9N+qDtI+eH5ez1MK5DmOPkq3OwQ9TxB5ntyWUAffDFL2ezr4+3fuQo1xtLuFJVdD46yUSGE0cg+a2tNhBm8H9AY0b/A2Bcq6upgibQ6U/KVdBbP05L/kyI6Jhhq6iTQPlqPGGUeWv6EpuOSrVKtYayUKeCTdsCwL927b0A4bCsgbycTs0DZ8+de/hLu3bsHiGtWAtm1wd+yWFf36gG988xt4fPUYZSf7GDxjJ6XgW1/9CgIaQdH5eWVZaI0rR5aEM5BdlgVLTVR+w25ZGXyFuk6FaC4nRLDCHWWpqHVB746dSd4iYpTJzYzqq3XaTwbxgtLCYVgGEu8RePKpDxE9PGxMEGW/q7g7oX0yyNJ4f6/fU0DyL//lv7zx3//wH/5DPP300/jlX/5l/JE/8kfw3nvv4R/8g3+AX/iFX8Af+2N/DADw8z//8/ie7/ke/Nf/+l/xwz/8w/hX/+pf4XOf+xz+zb/5N3jmmWfwAz/wA/gbf+Nv4C/+xb+Iv/pX/yp2u937vyAJgo3JqhHozcA6Pg30erIoyubh7kI0ODCPhEn+voiVBqDoIUWBg7/fR9QYR07ZtDHojMl6LuitMRtWr7hCexLoqmE77CHlJgyWdz4yOUQzEtdKzF5/V5aT2TuvxTVCfsJiWeszD6BBrYwcUx3B1ke4nI3KQwAo3x0h4hIzfqJAU4tDphVlwOGA0ktltwrSHKpzZvlDRgPSYrBUIRUPJCFt1ZpLIiYe03Ab0a9MUTNQyss4Ls9oewCIQZrNUkwE4d1jaDkNcMBEVmawtVTD9eVjXLXAg60zv1gWltMy+0irb8voQlqWFVakTyKthForqspfFqzRe29HLXoFsIpDY5u57gqwiqUshNiV+ZOrU1UOAJJPxUdAFdN0dFeXV/jm17+BjqK1B6wmGXzW5QHHWkTQjMCuLnTyMKzLMjgRKYwU4jYs9RRhBTsHPArOiqEb0IuhQ51WHvCs/xeSVLfWcHn5WM6CSMVagOoOXD3GO2+/je2w4SMvP49qhquHD3C+Avfv3cPZ7kQBdydiIkT0peefwdnFOVG74N4/bBsVWEM6KlGwbRQq70KXtuZonSPUL/cbXvnENQ7bRml+A85OTrAuJKS2tjFI685JrZLnh9OOULF21vd7a6N7pet8ZOKQU1SLHC1LVrRTjKNINtUIKSyLNIIcqCaBvdSQUViylDI0eAB2GxoK0FKJNRVbMbptYNlXV/QvRvRPdm6UOYqN0a3vvvce7ty5Q2TbxPfwDrPdSARyzlImZQYFItkBl6ikB1qwFDOQWWNgwinutC2JDnHzqpyeHL4gKkmb4CgoqHUhIqDkLYHiZJQ1JYElqGK97bdhjZPcfzhcD5SmbQ3XV3u0CFjVbC4Y3nvvAU5PTlELg00EW4p3peLagMPhwATXNuGxjnVX0b3ha9/4Ou+jLEJzbcyuSU5KOIOpIu0UQF15zoF/qRieWWdy4IpR7j47qBJZq0VBVu/YrQteePF57C7O9dwwGitSE6aKKLz1wHpyiqeefgatZ1AvVA9p4wVo5T/uR1b5d379f8Uhee+99wAATzzBrpFf/uVfxrZt+ON//I+P93z3d383XnrpJfzSL/0SfviHfxi/9Eu/hO/7vu+7UcL50R/9UfzET/wEPvvZz+IHf/AHf9P37Pd77PeTpfvgwQMAQO8G9zoMb28N2/VBBpPODZ1COgYbbbEWzhp7F4wvsTQPznJZjcast8a2SbWjwdQVdSRMFoKy039k+aO7oks9itY2wPjZ+8MBh/2GWMsge3mng8kNRR+fbbmZYVRlBSRhZaXOdeAzq4IBAcfWD0RqOpBzKNgRQEIUAjd4A8AxIbjIwDKbbM57LqtNFAa0T97Iys/gkLXKqpiL76+1Hum6CLUJIIoPmNb0+5nZJjUucqx6sDPnWKchfzf0eyNDGqmhDsgI+Hw8uxzVnW3HSW5DXQEwi+vW0XzD6e4E2+GAx/sDrg7X2GLWZo/h92KmoLegKGuBUea9yvFEMDq2ElhUFqmlcF0jUNcT3L5zh5oSGSwGV3x0vCiYnq3J+T4hGEGULoOub33rW3QIpYwsXWnQKL/QePP3bwwsjAy2DShJ7E7BJV2TNt+hbUBhLb95AILN0wkckw3d6dDz94st2IMOe1cMdy8uEKdtdNbcurgALs6wrCv2jSrKVWUhAgKGq63h8PBytJumAQ4DWiOvotSKk7MThEHqsCYkVV0FAFzoyUAEjAF+VfCKFJ+TPamFuiBIEnk6sNaw1DnpdyceR9eoiDH2QXYEYWg6k64SzfEZJ9eqSOJeBNHesT/sUVXyHu3L7kTy4PDWtR+D5WXgBjk+RAaO1nD5+IoO2fg9aUtzbwGG6/0Bl1eXeOL+Pe4DFAbHMAVoVQPjMlHxYWdGiXQeV9o8lUpcqqzUGMr1TFKs7C1mmdi9I8cYkMDMAM27K1i1QWSnnVVpTeJsEY7eyHfKxDYsHT8xrJw+XKziZHeK5WSH/uiBCPxEeKJAKJ+xFbgYbl+c4+GDd5mYKJFiCS5w984d3LqlLhUlRiO5hgZmbo02oVTR0EyluFCARRJ1b22W+l0Cm+mz2uwqZEJYb/DDzk7v4OyUCGPafET6xokyhQPb1vHCKy/CloU2IG2J5AlgnNTsIHoKK0wkj43k7/D63w5I3B1/7s/9OfzhP/yH8b3f+70AgG9961vY7Xa4d+/ejfc+88wzNIh6z3Ewkj/Pn/1Wr5/92Z/FX/trf+03XwMoHJZBwLIso0UtlUtpbHl468KHF8WwdxIEo2DUeh182AdIzMr00HRYJ6pBJ1lLnfXhYJTYNHEAtaBFYiqCii0Fqzr22wZgZd0U4GbUcC1TZhqAWPPibcjouw5nqu8NAqYxovWgoWYAFbx0N3RvqLLUFFByHIaOBAaiQ8fYhxR5HxEulUIDzLK2LgG5o+Crp2R4SEzL5eyjoZeinv6jDoSWpEIabxez7DgrS1wmEaXMslKCOncDkRVlWOOSBKXLICINkdYqoUVC/CrLVdCJOvfY6dkJnnz6Q7h47gKHHthAGWkGjTFk0sGvG/dm4ga1w54cASE+XKeGvh2G1oRHH59jZWHGFsp0LbCprp/KrwgaoRUkuvnoJjLu80oj0BGIQoh5UxaVfAT61UlGZRlAMyy0J0PZ3loXErSFkHgElpqZK8bv0/hPI5VBSI4sWJZFAnjSTkkyJ4CoFd0DqavCcsxE37a2IWA4Uauqd3J2GJSwHLtYHYmHy5lme3L3NLKT6N0ViJoVtnbmtYR+T4FzVQsu1N2xZkAN1u93K+v/7XBAdvss64KlLnROqyBvtYVn4JOaDokMMO4sWNaV5aaez50rthSW9nbLiqUuYyLyBS4mslCL4HrutZwFE0pa+Lv8u2pAka5RrQXFHa9963X82q/+OvYZoAOc2xKZ2xe8+dbbuLh1jrPzM5aU1BG01gUtZG+1r01BJsBumpDT5dYxImjhqmqPHYOcdM7zMRHY6cBFcpfOj+V7swQswny4k9cAJkCjoYE3xpIvslU/zXEZpXhk0No7rx9Tn4gEzoZtO5AWIF0qi4BbhxfuIfdAXRYczGB1AcLx1JNPo2CBtw0ONkeOzsZh06WX5Say7USTaUuK4mLaWkpCOPkiIfJ8BjBadaJThZypWnD/3n2syw45bmUktpFkawBG5eGTkxPcu3ePxOIiJdweSkAZAGXHH5+vujXfZ5vN/3ZA8pM/+ZP4zGc+g//0n/7T/+5HvO/XX/pLfwk/8zM/M/77wYMHePHFF0GOgoPmLcmoJOiMrFkHsnsfg/U8HDUkSBWBlPriIRjuGens+dhnqyTrkHVEkHT4InxC5LUjzCqnlZrgtt26IvOEHnSiGa3CEqnLOiwPX044NSTr3KliiCz5atx2YU998iPGfI9qgDOSz6w3I+jUPyHIIKqnhKRC/BvmCcxC2AVB42nVEBXiZMREO7LEI52HHpTkDg+2uGUG6R0auj5Y46FAEcjARJ8LyDnx30sksmISZ6OWTEFyY44CNiQKlL/NxbaBohQYqKExkQWg1kC7eoS3vvllbMstRFnRbUFrzEqPkZwWgfPzW7h9+w7MoQ6BwNkZy5DunQ5FXjyAQeTOaa3hgeurA66v9jKyNEB1WQgFg9lKrvHgI+cnWqArLG4xWwaff/7D6MvCILEkCwKDh1QLnzBCmbO4R0TASCJ1kWEXBcKjo+sIRfBIdAYMnEGYfXPNkopABDvWUCo2l1R77+iHhuwKiGxj1KPqzpbXAuARHoMsCe6hks9g8F90gjPodEL5CWMzwGZQns85zNA3nsFEE81YnSiVHBMAKFnGirmv3KfhNojDEw47MDtvrY0unERRDCzZ9Z7XlcGcAqTCbpO0Y2aFnRdjv3KPb1tTSzXtRK1VJTjaFwZ96jY0cZmS/FmLgnYGHtUKlmXFdtjgZWGpKeZzTqT26vIajy8v8eyzz5F86Wy5JZdGM1ByDeWaUok3RulYSYDZsONjxEc+P1o7uDfAIfXQGAkLIjKsHURrjBI4/79JOC+CSAPXtIzvyK442FEZPjA6p9L5F5UpHQ63wHq66tzx59vGEt5ux065Ugz71hCloKy0cMu6cD8CODs9xa1bd1jKMUO0jjAmEuMahPQkz2V0HGqdHAHTsDuA15ZK2RUQATpgnm3g6i4L0QCC1/vkE/e1lnJZEFn7iC9lAfQI3H/iPpa6CAlnIDSCJO3fbLLIkhoM/2en/f7UT/0UfvEXfxH/8T/+R7zwwgvj75999lkcDge8++67N1CS1157Dc8+++x4z3/7b//txue99tpr42e/1evk5AQnJye/xU9UT+8ZkujwVGZ/0EEuBfBCWDVcrGB3RKmC9QIh6cFsRwSyp1qw7TDAgJmmrkaXVLwPODEj9dDfceBQleANW6f2h0u0baPeBDCy5NGJ4kHDv5BvUOQsAQh6BDDaBo2EMzl32SoK2bD1ZARG9GLMKuogpUJRLSNdK6mpUIlcwGGuklWA0GhWWYzQc2YY3Vk3ZQbIoK2F66gw+IKZWoJD351dLypnZDcGUsm2otSUQk7ImI408ZMUOqMAmQ1DR22Doxpnhu0GGa6ZnfpoMy5ofbb8lQhEu8bh4R4Pr17Ha2+8hXcv93jzrcfYusPXBYdtj4tbF7i62sOw4MknnsRz9+/j4tY5Tk4WADT4qXlBlCvDGD6nUndYlh1u3X0CV5fX1KGpE2Eb5DO1HQ+jPLQraKKyc6pUwNHZUtlZlqyIgbiMgLsaUQV35GRVlg5DUKsNxKesuxG6ZzCQ5Zup6uhY6zJKRlkOOjMbMG4G/aXqu5B7dlHrvRxxwsdzFejs8loz0+0NOYk7s+/uLFOE9Fi60yG5+BjbtqE7sElLIgDsO3klbCZhcOvuOR0evbfRFZWaDqndwLNkqCXUqJZnTqmO7EF2dq1L1TWJiKiArS6L9roNgjsz7DJIiEnMtyxzVGbvViZ3IAPvDD566wOdNL2H12vw1kZLby0Vh/0BB4nrZZCZnXoRgUePHqNYxa2LW/ycWjRuwpEFBzohQ/fkNWEgrpYmyTEy+iw6po4GKzXcT4YFZsdzq+SQDfo5LUpXtxivN1ceCjDUMmvlRsDD5CtUboijdYfKaHKyrgSuMNHY7RYKDSIAB/rhgL7tsZRCLahi2FrHyQn5Va013F7WQdJ96qmn4OhoSSg2oHnHkurdFkL55z7AWEMlIsdBixDznsmbz1bz3ro6bJgsAJoc7I77Tz2J3ckZeVER0pdhA4ZVoJSVDRQg4ff+E0+MoN97kKqpYHP4rmNkRUmopX/8XV6/p4AkIvDTP/3T+Kf/9J/i3//7f4+PfOQjN37++3//78e6rvi3//bf4sd+7McAAF/4whfw1a9+FZ/61KcAAJ/61KfwN//m38Trr7+Op59+GgDwr//1v8adO3fwiU984vdyOTBbuJHgsCokJAeDGQ9jLsyijRRgOy67YHqGhFiE8Tc9SFOZJCkVARvRd8IOVlb9FQ+r96AioN5HuLiIMc7Mx3vg4aMrnJzewi3iqHQiUcQvmN8fKV9vXSRF0MFElkZ4YGBAUTlqTPYtgVID0RK08JGhsb9dGyeNOn0Aeg8ZTN77jIQH4AEzQ3fAnbN7IlEMTw5K5uvM1JOXkMFe1IrW2zAu2YrXtxj7LDPQUgLNgVKcGZ3wwJQmriUrljEQH8VEAPJ6AWgOBRTN57j4ri6YIeYFBjYhBzoybCvYoePJO6d44qm7+O+f+y945/EVbGUnhveG1jruX9zB808/jbPqsMNDEKxLVV1D2My8mhQorVRYPQOWEzz17HN48PAhogA7kWQjHG5sp2vhMxsE9PuUzGfWaeg90JpaEhF4dHWN/9f/+B9ECQQfm4i5nkhIKWztDELdtS6A5P3NqHWxrut0dkaOzFLV2ZGKs2b6XbWQyji5PiOyJJPdDRrH0HsXcsNzVwtRQFNgk0EZ2y+bjnjKZ2fpLVUmmaUtS5W+hMNskbMTtlcLdmY4L1VlJRHdHdLCSdVjlw2wwfeiEi67jiydhicaJSdamPmnFD1UakxyepIHU5+DgRADJpdTTeGz1h0tKNgHM2zNEUqGLALbNZOCFhRqhBERqcWwq+zKQARKV5u8AVBpO4JE5lrZCrqenuBwOAzhsgzMk6D67sOHeOvdd/HCCy8OPZWMGl2haqLE0LrIECpRYZkIMbvaZvkE8/wXJZXQSAxUPlvLgIxTeD0MMB/dlCZDlt1L3bU3hRQBLAOmcNxwpRYAqsjDJsRKk9YhXRyfSV0thbYvS+L6887FBd59+11YMWyHjbyeCGmIAFEqdmvB+cX5sPNEfWg3tz5JqrRZuZYYHZERAW9ZOm1I3lKX6OewswCy9M1SbJFUf3KGDM8+8+FZkte1RCf3qDg5e+zKBG5dXOD09Dy7xmFjDU2VaMoAFHUUmikpgmE/uIm/8+v3FJD85E/+JH7hF34B/+yf/TPcvn17cD7u3r2Ls7Mz3L17F3/2z/5Z/MzP/AyeeOIJ3LlzBz/90z+NT33qU/jhH/5hAMCP/MiP4BOf+AT+1J/6U/g7f+fv4Fvf+hb+yl/5K/jJn/zJ3wYF+e1f3QuaG8qYNKiuBwW7mwcWHQzDohoyYB0TutOb04EBMVv0ULCgilhKyCungWZNrJYFY2gc8kFVBMi1YA0NiN4AL+gOrCcXKPUMrmKFuQ4aYtQ/i5xM1uiYZUHoRGHdTnBnZmxNWX4K0yTTntBzDFQjS1kI4NCa+uJtqCqaQfLzuSQxstVR27fMpFNaGkh1DJTU8GAL72j90nsP1mS6iG7Vqk3daVCqmQSUgLLQAJsVrMuCZRFK5Qp5vLNspOAme+gJvtggXWWJKoR2ifwzAjhI9IeCcuLsRJbs2GJn1XD7zhn2DjQL2FrRTfDuQm2Spnbbs7Md+naF8MaumsykrCNnztTgc49O5j0F7xrcG8x2o+rK4DhUiuvqWunT0aVxAIXLMkPM7LNHx8PHj4HsPijAEkVTe3PiJ59fBix87Oqoye+HuCopFljLWL9EEWenD8+SEjKgzFLjYhXLssLdcbI7QVkyK9RZNRM5MJEfle4GKoiMeZHdZVYKdruV5+1o7/ZOfYueKECinMr+I4SmqOTK4Yl8R60VVupAz2yU17ifiLiSE5ZnkZoXzDDTU/MrC1rbUMs6EJCa961y65D3NnVvhM4rgFpn96Ef3Xd2DgFAXfPsTWQIvTMo8FBZm1c1kSjyDGoxLEvF0x9+Fq+//ga+/vVvoEZyhFRSDcfDhw9wdn6Ci/NTuDeVgDIBmXY0EdfEuByBRYfOFcSMzjo9k6LEhoRN/V74sLvj881GB1228ZpryJ54DaEgoei+oaweuWbJKVHgkfYeuZ5Chvinz+A5Aq1tsO4oVrFFdsQZvDlO15Xf5xRwy93Wt4bD9R5rWXBxdoazs3O02JAQzqLMqSvwCxQFUjORS+5LeFOZH4DEEy33pdYDSg4Y0yYRnskXu2Uann7qaZydruS/KOwnAgMmL8auUCsFV81x5+69EbToA6ePGFGKyvtJ1lYgnkKRv9vr9xSQ/P2///cBAH/0j/7RG3//8z//8/gzf+bPAAD+7t/9uyil4Md+7MduCKPlq9aKX/zFX8RP/MRP4FOf+hQuLi7w4z/+4/jrf/2v/14uBQDw8Nqx9I7dQpIQ3JlJi7y3dQesY6mr2nypVUKOARDNpA2hGQ3aEAZCoAWsyfYOXKu1d5EscQTERdGAsgCa6xAGELaMrCPQcdWucH3dcX0IPL5asJ6vOPczlCJnByEAMTUG2EKq4EJ8yN600TodfV12LJMgD3cBKiectAMzp1or9oe9etiJTqwLZY57mcqlgRjkr71EvlzKjekd17qMTK+0OuatmA5yOl6DIGZXhhsJO84yAIL3tB10CHpoIjNr4t0d5kCflNYBUg1hOIRGc2MYksiy21E2FUcHwmCDjzH0EIAprVxyJLlmPih+25Q1NiPhtW0d9YQBa44GiLri81/8PD781A9hATSbxIfRKJEt2MPmIkCxqwrH9dVjLZrDpLzIsuMC1orVeaPMlTOBAscDF5diqAZYdETQaez3e9SlSOtMerwWMDgWSY8XixlAy6AN7oVgslx199T6AcasDffR1pqZX0q5Kz6BmWEzwPY04tf7a5I2S0HL+r9+LzkLOZWXKJwP8m8gCX8OWxfJZNM55swNHxyCI6Oua2WbrePq6hqvv/4mDq2pBGt48okncHHrHFaqkFa2LxMVwEB+SCxvYx2yHMGzqHKX5qcsywo/+tmQcDc7Ckjo3zJ4ShVXvjeVdbmLPSgMN0iOrbBTTMqspYp3go6rq0vAHEuhbH3AcH56ht16QsJv3xDe8dbb7+DR48cs17r4VKANefjeI7Rtw3MffoF7J0JCcVr3OCozJcJRlsEN8WLozSX3LkQrS30RqFYHUpClPiZAE3UOS7wMmhnGRCeRGW8OTv4zABnAMmAeCqK6RjMbliXF7XoiOe6whUkK91FaDiWCfcNJNcTmaAa0vqFtG+7cujOCJRP6e7Ke4PGhAaXg9OQEy7LgcDhgt9o8V0fTt5u+ZwyzE7HY1YoLM3bHIThGIpGb3NsxOR1Q8DATNJ7xZSl47rln4K3J1kzNGc9nmKrZAdy+fRe3bt+ZvEnZ2cHTTFsWs5tKq8DSL/4PcEhutFv+Nq/T01P83M/9HH7u537ut33Pyy+/jH/xL/7F7+Wrf8vXZStYyoor52EwAAVd0usYh6JEHbLJHtpgEiaqVrCWOmphFNhxnCRZC4y+V5tZeJGhJCTNDcABYmTtd3c6/JSIjsC+P8I+Nmy1o653cF1WPIwTPHn3Pg5Xj3D16CHe+NZraPvHuHV2gReffxGHQka2VWpTkJtHZ9NztocTskc4al0mIxuVzI3oQC+IesYgIsipsC1Fwhidj0wZGKUSC0Ju6MkrMZJXO4W5VgMq25QEbXa2N8MxJqEuFeba6Emy7AVoXMtD61iXVVa8oHQNUivraCOEMmvrgb2E5Koky90d7bCJMEZExYxwKo7qmREUF9udrDAjwsDEvQzHlt9lbuILVDmoGGu/3zqwK0PaOVrDUldl4J0BJjY8OOxxcbJi84ZditQF9XBSzKzIEQccjgVLLHj86JpBqEtFNMnKRoeUaBSRucC2dex2FEnLPHWtFWtZ1NAh5jzboUaAxRg2xpmm+e58VkH8L9ES1/NMZVQozJ5y0DRKjkBqHWRUQ/idmRKp0MaOtFxrdacVzf6BgiFklhuOFBF0fTbr8EnwJeTp3eEdsIXqtVmOnMhZruMsleQsmQcPHuHBg0eIKgXfZcGT9Qkctg2ITUgJO55SyyfXtBhtTpYjhmMYqKD+9JksyJ8iBRjpX6h/g5Jl5pl9HndeUCtJ6pyyT9l9RcfK37/2Dfv9Na6urvDw0SO89+67CNCGQOtfDDg/O8dzTz2Je3fu4PbFLSwny7iOjP45ebrgzTfewu1bt3FysuMZrxLXsg7rcx+NGSmRUBaGEyuSuecz1sQUzY1pkQGIwTSbysIHN8RKIAVZBiEWSiZyWB8/gfvEyUUpo1yPG88EgUEIRlCHxgwcfOcBgN/vENqoU0b0gqKIcB9daim2t6w7tA6Wxbam5Klia8BTT38Iu0WBKKVwyZnJtQ6g1N2wbaYgO9VQZ2CW090TbbLBL3SjjfDehWDxvFchne6OJ+7fx61bt5C6SYDOiM6HlQJbF7QI7PfX+Mjzr2B3skPrTaVsPlqLBEAZOHUN6RxdburOmb2cv/PrAz3L5tqBhZEHZpsoyywA5jREFFhUljossFtIzmN5s+AAw1JNmSadHVuAM0hhjXVRO6J3EpHOKrMyVybT+HWKIunMSNDquP/MsxTwycgxRccCODs5xZ0PPYNnX/k4FvPRsrrJgJFcWFGtaC4KH/yyEK3o6lVPkpupng/QQCeTfGaeIvqqa2epK+WzMcseKreOKDszyoSpAZaaonccrq+5UXtHLG2w7auY1Zz/w2yk1gUowCY48/yMEHldV5yenLKkJhjYvVNSel35PM3UhumcOSKHWBV0DDheRN5BClOZe/HsAPERoByur8a6BES8VeCgHhEUM83PKBRG88CHX3wBD65/DRcXtxEBXF9f4mJHZeCPf+8n0eoZ3tt39G2H891OzyPEJ2JLb4nKALEAgYrWKq6uDkLKeG/TYHLNIoDdegpEQfb9Z+YGM4xBiPU4wzYsIrlmXf0AUQFD61psZkhyGD1SB0bdLoVkuGI2Wvymy4F4sgao1RsRLD20RKnkSCCSsVFkjvV3KWyIm9K74OfMwhSoeEL3rKuKBwGhTiYDGUD0YThNw+ay/TMCaI2zmWhAC05OT7BvByACJ7sTBri5f+SGFkjxWMgrDGzXtlnOzGy0qwRUk1NmWh9MzoVwIzkylnlNpF8TapeDMyOSQ0AV5zyjbPfc8rCS01Arijt2pWA5P8MT9+7icw8f4J133xOJWAFO73j06CHeffN1vPT883j5xRfgm9CY0K4K7rE333oL27bh/v37w6kPRMSzRAghQJoMjAC8zuwcwffLTskQylBNaGmU4cwQ1TjlWM9iKcAYgFgy4BRWV0zBqHPwnfF5u0QUyV2xgbxBZzJfYYGiTiYfKIeeVwCmzsxSKsp6BrOHQgT53sOB06bXZUel1u7o24alVhRwGjHRO+4qRwj9CSAULIPo4xiKd7QeRT8HEvm1sVdgUMCfr9kSr81GX6ay+RP3nxBJWF0y7ioBMStgh12gRaDuVty5d4tnWV8wpnwza5XGCmCa+eYhMcp8pnh/rw90QHLvQ0/g5PRMMxe4lq1t0zEJIi76c11WbmyjjPG2bZoBoMhThMnefEBepijcDHLAs1uDkHlyRwJYKsVgmAqIO5BSx+Ch05ZJdGVkNlZwdnaOkx1r6711RBisVpS64NCvsSzayEIy6pKTFgUXAwoCthFJlzpJUQgf0uVNtb1SK673Tddgg22f/f0errq04PHWkGPuTUFKlALvxm4iJLFKx8MoPlWU0TtEnKwMMjh8DTAUdCxscStSFK0LrFS0PDS1wJW197WqZVKBZmCgIUPjJCBSo9xgKUJNmFksa8cWO/TDhgM2OWMgM/4MCtwMFByVQzLgY9/5ndhH4De++g3sdivKuuLuvdt4+OgxvAEnJxe0sT0hWQZZJ0hHopY8yJCUlSXDrWEpO0rDGw1vLVVBxYJqdexDgh0MoqoNu8nn1KkUHM6Dcdhfawy49mAxQd5Ha5XoQzrD0EocZeoA1WeHMo0c5Wj1QxofcQoGUjL8jV4sPxRXVOOh1lNlsGBbN4OQSOR5vAxMGjwdSzBsIIhyrCehFR5QPFGQ1hq2raN1x7KuuHPvLi6vrljWXFKFNxVNyQHyoSHiQHQF8H1kyPw+te8HkIMjE/qGykcjs3fuOQSAor2QZQhdew7v5N91dGgeksirzKRjIDdMzPihBcBSF+yWHa4fXyG6NokCcqrsLrh39y5u3b8LFzJgA8niOj9+eIk333gLzz7zLNZ1leBZPmwFmOPZ6zTXsRsZNI9gJdeljad4BKRoz6fcP0YylQFEItIu3t1EYfIKaMetipOWWjm8ayWoGEJpWabOdWfAKzKnnPzkMrHOahHo0RneV+1vAO+89wD37j6JZd0hrhscFAeMUhFwleY7ZdrXkfFpr/O/3LgGs3lAyR+4Z7IDKAOVtAGpEp4pghnPvyl5TWQSqDg/O8UT959iUiMk0YJqtg1EOApmR86Hn/sw6roMkvl4EDqJWT4iB0v+MlgWJHJfR1fn7/b6QAckd85PsNstmriY5KQduvcBxUOOqqKM0eD52E7XqmjZeGZsbl1TxtjdUUt2heS5mdn4oiPogt7CONOjIcYhMnVAbI2y0CRumdQ51ZbYHdfXV9jvrzVfhLyBvm3YX1+jrAv5ygXwQ0PrDc3ZEldrxbZtIiORs5ItdlVJtHsXUlGGTgcNHjMmd07irPp5leHcnG06pSafweRgKcw1DH0nrF+NKrlp9HJJD/0KScoC1JcerIEWTem8PDCzMpWesowU+QxrobBWbzQoVthlIri2N7ZtpohVLSyJ9MZstqodFXBcXV5iMarxbocD5cx3OzTvOBxYdlrXRZwWEJVyH+UWKwUfevIp/PqXvo5SSA49WXfA6Ya4foQltpH15HyJ1JWBNCmkiwpvAfgBsIrWrnB+djKyU8vsS9o6pv3pvSmLyexIwQJxBkQwWzSQg1HLglpiZL7ZlZokYPI0lNGnwTl63gga7kCS+1znQOQ/Ef4GUoeME+Qgk3gp8T1mTgWjLVuZZ6AMPldOJM7avwcA43BAmDQqFcBwztQyguaShDubpYceLl5LYL8d8M5b76J74PadOygFuHPrHKenp0AEu+6EZLHTyga6ou0wOmGGkQaQWijQfRR1sYSQkTAbP5+6F+I4lAwwugKLgHcbKC2/JjijJREROeKRO8cMgFLNuW8dvhE1oNy5ymqFnTgwx/VhzxKis0xRIjkZHd/6+qs4Oz/D7Tt3OMjvCI3MMQjzOhRwBUQiZfuoe0a33CscgFpGeY4L6iozAz3Xq8QISjJRgn4l9/Jkm2RiqoTy27gV6dSZvPj4rdxbDIRt/n4ygC1LXNSNcXe0vuGwXYNNBUSU9pd7iuTtdnB/DNMIh1JY8uvesFsrlsWEfGlNMIMmAjMTqU4EqCb/Ra8x1Vq/3TTpmiXVo/dFcmr45r51fOjZ53B+cnajU5O2mWgWW8UXDqGtK+7ce2Im6QBMCNhA5PM8mxA1KHnLe1MA9X5eH+iApIZjgSMaHbCJc1EHnKRlULkgmaFrXZCj51kbnpuQh21KbJvROOy0VIOsI4cPmYYFk0hUzLDTwTTYaCPcrVRZZNQ663DFbCiywmk0l3XF7uSEDxaMtLtPAaNUaGzNj4hvNBQV1FkYXQURKjnYKG0UzHk+Hhw/jwhECzmNmMhPCvNE6ADmEyBiYxHwrY9Ifds2rOsKciacQjoutcytMdEIIi63b98CrODyek8FUsF8phopDINQxs6AJBpvmCWo5ajjIfOyNPYGwzqcZN8aDBXn924z01X3UOsd3Yk2tFOKTe1WlsQGERIugaxAg+OZD93HyZLdKoa+P+BjL72I5555Ct2v5FxVZhbRmlLinILaMYX3IoD94TH2V9c4XDe8fH5Hzr8MB7UsLAFufUMsQEcHCgbnIPclyW5FwxYZLJ2fXwA2Z67UuqAuCza1Dffooy0yRE4evCFuUpRiOBy2YWxCzjSvf/A6QmVNGSwXxyNU8rOSypVFnAmelVrZmrvWEwU2idokrA0E1slTyn2NdIRca5ZWMe9HdqBETiM2RFzj8jFRx8tHj0Zr7K4UnJyekujbG2Cuc26Dd5SmBC6bk6TyLEUkEKEAMofDCVYU7cDUKSExNs8QTl1hpQ4EgM0RMcTVzMooR2apJHfo2NOFZ7MAWErBybri6rApcRNy14F1DTx+9wEevfsQTz3xFE5OltH1Ey3w6quvYvMNr3z4IwgAS2bthYFa8aM9gjS3M3MnkRhsOBDMNcj6kV2IdewjvjVgSCfKdWP5ShwUdRElSpDihhx5QESS15jByew0QSh5zNBe5cnB21KwRnsCDbo0oJQhCRFmQCVBFSqRLXXBvXv3UCKwWkWNIntCDktdDPvrhsvLS5ydn8qWYXClAqbJyBUlOKXeLEu2WeLSetY8G6Ey+oqMMV2oJzDFJ3MMRnZjPfX005qm7gPpMMnJW2FnWYj7cef2HQaOR/sP+UyDBNkI8lPycSWMU2HjrPcjBPV3en2gA5LT3QnOTk6kbEi3sZ7s2Ptvin2d8BezKsL31ZhF0IFnJFcnNCzHXWulsI8wslm3U2xdslaez0nRYSS5UsGHrjdLLTkgKeRocyS3Z2ttJQnJXTwBcEoqPyMzEG7OnRyiLTY6J0o4dgvhMlPkv1ajholOJW2GgpQAtm2P7XpDeODs7BxlWYbSX147NV6YISzLgrZdKyikgdt6x53796aRNEMU6T+40CnVRgcaZSwdnJycMFOONOg2jAVGb3sdxL7mqbxYNBIAWtssD8xswZCGHEezLDSUjMsBUddmeW3m+GO/9e4qCQLdHA8ePsJTd+7gzdffgEXgvcOG01dexvnpOZr5yHKH7osDUdPGJguf37ltG/q2R9sa3n33PXz048sguqFIzMnIV4JQrR6O3pl1IeW/qViEda3kjMiG7E52w8gXEDYrpcC0RhV1lBjLWnTbDAzNCmo1rLsd2knXeeHPMJ4lyzZpJDPL835z+GSy8tkhItSysjRpy4Jl2aEuK7p3tVCL8Nl9/q47vLNGX7aN5YFIR8fzPtq5zaRwKsJ2Z1fO5fU1utFhbdfXJPwF0HrgpRdexroaDjGDPCvJtUlelIjJBfpTKI6cGisq3M9LFR/FCkzqrLvdCVIiv3dOTq6rdE+6w40sg+O0uNYUrItxv5R+Z3dekQ0y0EHQXgWsNzx1/x4ePXyE84tbWHYVaB07VPSt4ckPPYnT83OsRo4B9Mxff/11PH58iVc+8grWkxVb4/C7VZm0O+1idtgkX2Bkzjx8w1aNGSqYjmwOufRBiK51GQ57tAgriLF0jAposnOKjWlarz6TRE8UJkInPM82Ly4wnWza8pzbYjC2KptR6mMopgW23uAFOL9zgbPzMxgM23bAo0cPUMqCWqggTvkDfkeB4bDvaocOlCXlFah1Qn8xuXwIY6Lrk5SNcMSBZFcA1HJqTU0FGPsVRo5UKDCg4KPjw88+j1u3b2OTHZPkCs+yONelrshOnXv37mNdFqLxIxOd/DTG+gpAM8M2BeHDxnN938/rAx2Q7JZl6iRk/3VMNcCpaDebjrrA7WIYEXHRIhYFlAERNlXXTiOU/IdabDjqrDua2MwWUoLVQ7JgF8sYHCdvbYWELWqKTP0BGhwQXvPUNwix/FLuftaZYVQp9MY7qypfhYbnKW7l/ylijpBgkEn8TLDCerKovqtpt6BSKRSMsDOBUyu3wx6+v4ZvG9rhgM0CJ+dniGjSQRI5NpnkMibHRgsADhvnk5gp2wS49phtaAZF3uJjOMgvGM+ldVVBguNb85CLNZ+fQbSiC3lQ90zvSOXL4Uy1ZKmumd0YgcDhsCng5T38wPd9El/9ym/gcH2NEsDl5R6vvf42YjEs60pCmxwx90hF6xu1H2pV9wqN4MXFLay7hh6VfAXH4G/8f8j7027JkiNJDBQ1s3vd3xpr7htyAVBYClVdy7A4JLvJr/MD+EvnzJAccqbnnGaf7maTVQ2gsCaA3PfIjO295+7XzHQ+iKhdjxp2ob7mKe9THYl4L9yv32umpioqIlrrgYPrtB5SMpoXqa2VtXgT6LEQLYIgRfamRC+CvMjNHODXZNq3BjGuvYwyTQhCYqtPCQuLp5Oz1AyK7y5kq+k+Ur69kuRq3ev5+crvSgmp0HCNh/AVD4kUslhtJfXS68I2YQaVbb2Lw9FFolYlGYiKlYyUOprTj6TXisPNDn2pmEoe5OgOtkn3+wWHwx7wQolqwkDIspDV1hpKFsIB0FZgoquwd6rdSpmQSszM4WFrKSFPbCOWXADQl8hyQZrWUDxIyVgLo1yy+F2OkrhHSs4omXsxGTSJuFK1BmC328Fbw2baYpMLvv7oc6lsEsqUcPf2PTz44iv8+E9/jJMT+opIV4gvvnqAbx5+je99/3u4e+cWDrVi8pnQvfZHLonmjb0r0U/DMZa1oFBnPkK4pcCZ0bW3aF63JpCuwisrkei9jv3T9Wx7q8oh0sqd0ZBOFiyKdWba/ysJ1BKvefiX6MsYEvLg8axxMrkNzyM4WyW1HnBzdYWbmx1yKfBCfuJSD3Cj6i5NPEPQGxJot+A5oy4HTtidZ5hQinHQR2suUEcltSVzflVOpsnYgPVwfV5bf5zwjlFHtbb6zkSP9sUXX0SoD83IK8lK2IbZGwxLrSjzCe7cukO+ozyiiPh1eNIZ6tofKqy6N2QrokAo8nYM6fIfe32rExL3BkMB45C66F0+/qoyApqLnDhaNW5AHgmdr6xvkHQFSDaFME+DGNFsTWSLfqSvxFG9b08RQE1BW0hNwNVN8qqxYbp08itKg+TwvqCLDJnRdSVJOnF6KBCVVuYMYKkeCT/Wb8/WRRAGo7/avI6sNidN40WjzLE3Kkqiki7km3TfIg7nsilI3bFJCakYatcUFR1S0S5y17A/x/gzCH6md4NTcjqSJ91/3RiY+BCAepdqIvPgCUrVSohE56HclWDOZVp7w5KxQnwX/jsG0qlk1FqH70OtcZ0MkDkXNISNuOGNN97AG2+8OapVF4kLyce/dTMcDntMZVIFL5UJG9cMvsSVkVLBofajcQh8mHkuvEZvlKl3BqwpF0HXfM4Ak7VeScQM18Rbty5JtvOO5bBHkR/MYTlg6Q0npxuhS22gSEF2ZRKjysf5YbGW97s9jpn/KWXkDuz2e3qrzFTRLL2PJC5De7BLmXBYVDOrlaqEn8P8uEdaX5PChIRdJSE9ksuUyK2Ychn8L3LKoGeccPP0BskdN4+f4nB9g6mbFBg2yMzJgE8//wxT5p7IKYy2XDNp8rinYXiXNcwuWdY4hQ54GgetFbV8WlOClJFTRmuacZUnbLZblaqaHKxExOU4u9lwGqu742xD/6KSEjbzzMTI1vZNKQtSpyV8MqD1PeZkODnd4OF+h94WTGVmgrDdYrM5RckJ02YCkuPB14/w8cef4HvvvIVXXnyeKJ6B9wkZVXuq+8IZLs570GtDa5zMXUpBbx27ZQ+PdZmidWryLWrjmmMuTyTD5sEJJF/DFVRyZoxsvSnRi9Ysk9MMF69MYRdRZJTRMvQi7yiQY5HU4kuY0HvTeAMI5Yl4pGK0Z7Se0avjsDRkm9CudyjpgJIMUynoqEiZHhDuFZ4mCi+M3kVmHJ4IEdUNkNhA51pnaxbFkMzRWqLqqy+6Vnlp5YTVNTwhLSLQF7ZcaMKIYV1wcXGB84tzxBgN1/NKWuscWULxwNX1Fd55/U0gpVW67FwDrvgaBn9R8j3j6wLjeI/WAMucL/dPeH2rE5LmHUvj4TGgO4/bIzfTLKmWrQSyMcxpZIbyCxGhcxCClUL3XgenhHBY/Bn8REGWAYwo8NpRAhCVKiWNdWTFZgk5iEBCKgYi4AM0QVidB/mtOzBpEbt0+iklRCs64O2oSYgEyWQNGGhE61WuqKuZVNDEcjLQuNJXghdcVWBSgOqoyWXOlpAdJNWZaHaBXARi1MfbkJQ5Pk3LOKVRYeVcxk/Y4xdMGPfcxBnQBNSUuAlG8ilJXMz48Ea4Od4znlPqXeZVvLc5b0ailkoZKAD/j+/ffeKY98MODkpOS5khEROh+kLeRwew3Wz1PInKwDm3IpK2bBm1qR9b0qqk0H1xb5i3E8KKOczYaAOfETe3IyR5TJqtOzbTjLNbZyjbLcaQRlVSTTNUUiY0HVymsA53DwBiReViSGJM0A4EarQtGt+TdAYiTLVyOnYuJMQmGKf3av/R78TkqWGolR4KdTkgEk8zWmuHF8vqnUMENFpDvZHAnadQdnXOqTk/p2ninTvoteLJ46e4vrlGrSQEllKw2WwwzTNzfDimxPZEyRm73Z5rJMv3xfj35PhyYTd3ybOTEEV5SWjfIbMKrkvVNHByBBSKeIguC1umrQG9Y7/vqDc3cP3eUzwa7Qne8z4S+yyrgSz0Lxsr4N4aytkG/mgHc8e83eD0/AwOx8effgLX897tbvD48WPM2w32dcH7H32oljIR4gpyk1LOVJloDZhQ2/3hwOJGbcbt6RaAlFLRpklMPCMRMG+yWqCaDC5Ok6r8AC1Typw95IA7f89AzhCSipTeUGbG8w4mFSTGEkGJat7iZ5bUDqT/DFJG6fKaMbbIq6zZkzuqy/cJGWiGfugw71i8MekoHblkoeFVJOoCN8bJZrQ4mLab4e9C11+dYeJ/rIIDKRmxTk0OL6GURmqC1jo226S4k1Wj8pxTLYEXX3ppFMDJTO02jowwE4qRiFpvt2d4/v7zastxdZHHY2DaoBaYEZUMUclaAHP/mGbzhPHbH3t9qxOSqD55z2yFQaBg5RWUgKknruo4C4KGRpVDvAboLaJVQ+JVVAMdFsQcD0laX4lzwMAjEOgAAooEpilaAoTFkxCXZJkyVxNEh6psPUhIfaiDIvLH9FJLlC97D/KmyKqg30qLhawA8ey943fOXmATEOPC+dJUCmNyYuD8CVajRpaWgXK2LtIuOWRMmJzKma4KBWYMMEoOLLwA4rkgYUxMVcnU1SdnS+4I4j+qfMgMh9qTSvimxJkfSlBSkKp6kMgwDrc8mqgJltdDDymvrR1bWfgcEFUQfgGH7pimQtltDnMqoQA5JquuCVdXUEwAUipK/pRkAZjla+MwHBapao4Y8ND3dl2blYxFVVw4/OoCYInozn63w8nJCaZpGgl1hw2las4T8uxHkDj3kwl25QZocij1cThxCrQ9I0s1Lf6kxNKNvJkpFXRVUykm7EKyddMQRWB4WgA0WAQMvW0QKhkzQsljK+vemrMVB3BP9Vax6k/Yf19U9fKe8t+cbk8JuUM27FpFOSdW5eAHeeOAy83Jduwd711zq6BihoducWCbjGRzkWDZyqiD7wQ9h6oPTIUBPooR8k4ycthw67mmQAiTrfcwBWrItRGk9ZLi2skzyinhenF88fAhzB27ww6tL3j19Zdx99ZtmCfsbnb41S9+ibv37uOd772DZECNgYKgD05KREiWZYFltrUsBT+or3fdI16wFdYbJ2mTgF8wTOEgp2ozlA39k2qtqFVocKjqfJRSw/a+pEyyrAGWhKihwc04LA5Cylun86zidoyFgDGxWlJVuyShLnQuzVqvtTeUaWZygo40F9gh4979+2jNcXN1QxUfgEN1tJqQC2AF2vchKSbva3844FArLss0UGxCMIyT0S4yOLx2tUGIfFAoEO8KGgG6w8GZWDlrqm9Xgsq+CQyGzVxwcX42kOmh8OodtVPxOaUCJMP+cIO33vkeTzWP1nkcDlTXres+is5nz79AV4c/1Hq4/KOvb3dC4glznkawhjlc5NN+VNU7HOiSebWGBiUwBWMRmJQKAUm3cAQ0ESWhakfsa7itKhUF5OOXi7qFlGj27QpQJi5F7fAMIHHxqHXKjdeopZ9nav7djghZxiSFMCerPxpC8Q2YsLZRTZEgJaOiQIEUDHLOSGWCe3AZ9D0c47Dhm6qnizDy0fuayQOGbHnkrMNBUD9WAyITMfVYpRSVNRONlSgFgESsSDrUIoj8u8NhSgZjcikn1SrxyhhBHFDC4itiZU5TsBzMeugg07YzVwKiyoKHRIyJx4CKu6+oEtSGCbkykDSjBwiJQAOAlNWqs8FZKiUPPoxZTCm2UZmoK4XmBvc8rLejOuYUUmMbx/ldpzIDnnB9s8edu/eRS1nfV4dGrKF4VkzKxVEZqCNErA7SqLw5PNIPJjgrGtiPODNGt1l3HMsBh2Mqoi0XPzPNFrF1nbnBPY1DJAlB4eGb+e/7uv9SYrsAqsi7Dq+sZxZrr7WG7dmp9gyfPaXD/N5dirZSCpaloVUijDB+x1Yr9suCfa047A447Pc47A9ECqBDNZwyU8K82WC73WKatoNMfDIVJa0cCho+Ga7qF/B1X4/Cg3FtoGeRkRtgoBljSuE+zHt7aAcsuz3OL85x+9YtPHr8GPvra3z6ySd48YXn0bzj5ukVfv/ue7g4v8B33/kupjIjWccsN2Ekw3zEd2htHs+QDr4cqBi+NnCiRXVZRpHhQhpW2bAKgh7GgUS5MhxzFkLgjt4mhOGW9zDA5MYKhVaX8iqlrqRyAsAku9aqFjuUlPc1zlhCaoyLrXdYnrFJQUbvKJuEVFi4Ms6r53yLfAzvndyR7nj85Al+/9v35Q7LtjdhM+0X54iSkjIuzy80GNMGSjo4GggE3la+FqjyGkilBwdECU+y4R0V97gIZZtywtl2g20pKlgZAVavKRbItTf0Zjg9PcPdu3cxSMNmIrVGjBJK3dfijrEgSNg8L4OKwMRwwT/l9a1OSEqQw4KYaYZsGT01dDSEi10s/vAzGLB6j0qD2fL6h/5N+DwgUBMdriEJ62S2h+lLtHEAEaNGjWZCNRyWfDyuBGeaK9Ot1jraUlF3e8KdZ6fsB2rTRTVI+EuZcnc0i0Xh6wE6JGqcnBrwM+Ve4tKYMyFqITsUapMJJUQ12wdBlklBoBMQQgVkksr0bWHKnvM0As3xKypqACsSE4cYMAhpXT9PQhp0O5nkZCeyof5+VNk8laNfyeARaBAi4w/Vyqg1FCRjFL2HFT7Gc82DQMr+dm/OKtHIYB/VAVQVJGi0+6JnlpBLQk8kqKXEVl0kZilnzPMsrxTDfv+Q1bERjejNMeUNik3obZHiqREpMyFqIMcJTvffN157DZu5YJo3+ObhE3z19UNspoLn7t/Fycl2BMHwUkhHB3MkeIFERGXpQ2mwJpLJXdNWuRYAyKFUa72ucu0gqkYymgst/3NmuzGXCEmhNiCXhpdgsB5KIQjyzgy6ZVJgZeISk51NRUnuK4ITXICcsubXJOyWA/ZLRd8fVFXTj6a2hsOy4LAneZvXU5U8A0gZU8mYpwkn2y19PXx1Gu2947BULK3j5uFjHOoj+RE1nJ2eYLvdYrvd4OLiHKcnJ0IW+5DJmypRxpQ1NnlvazzSwYW0hvPeyWVKk+PkZIO6HHC23eD84idYlgW7WnF2do57d+7hy2++wccffIw7t+/gRz/8AWCUwQfhizVQyMC11mV85u7oSS3pQI6Y6aI4YFNRImBDKUhyMBPt3hxdqh3vbJskESSZxAA5c9ZLz2pfeCRFNmKJD7TV1KoQUlnyaOm7kns6JTOxROcsszFuwphM+CC321EbXAm4O7qRh5aywfKEVjtOz87w3MsvYHezQ2sVu916pmzmCYfdDYfsXV1jhmFngXCs6ALdqDONBi1m63DdJrdBWFbwJIldyE9PWMUTgZRNExI6bl1eBhtyJOYJGGh9xOOld7z4/Is8jyQD5m1IIxFCi6KDBQODq1BM3SO+fyBRhqAs/LHXtzohGVJUp3SupAy0CoPkbnHotCAuGTz1YfLFuS9NjGAdbscoQfdhBmUy8uFzY0skDkNWNQFqsc1Bhrliuf6MAD/Qiy49v/r4cGDaTCSXKYGiodnqIYIA+pNSA6EB/FQMifOooDRnp+SEUiYdIn1U9TzcbWWbC6UYn6RkLpaTuxaahW5GvheGQeSl3NZ1r9aNFglbkb1zvMwcKcUn6JAWipkHStCfOfTjnRkHn21HYTDVYyOsUPJxa4GFm48gN4Kb3iaLvNj6qtdnWsb7VdKEGs8VANDopGrkteSUOYEV9IYIInRI/YIs2R24vr7Go0dPCIcfKnIuODk5YfADq2ImzmtFnHL46/i4ZjPjzJ6ScfvFFzBvZnz++Zf4/NPP4Uic/trYHqqtoru8NcSNsYkweDw39ttXx0fY2iseKid3uHhRHfpeoyrusvs/RqxU1arvnNLKywilUzjKDr5G/Nu0JnG8JyayrnMWCXhIp+5yeW36v4rdzQ121zfY7Xa4ub7GfnfA/uaGSUOrKJuZh8FYXUCeCuZpg9NpxnZzG9tpwulmJhIzFeSpcJ+KF+Peh+EU1NsP+aNLcbQsFbvdDXaHHW6ub/DVVw/w4Ycf4vzsHPfu38Pde3cxTxNR3YHuQdWw1mYpq3LB41kcJfqjMuHnTtPE5DUbTmG4P8+YNif48qsH+Pjjz/D88y/gnbfeRhLCXI4Qp7j2kKJCB/iKzLGAWVEzG4Mqx3OFo0xFS3dF1MIfoyuxZhI5ISaP+1EyNFRpKvZ8pjM3UcZJXhcdyQtSkCjN1qJSa6gpaerhduwOkub7WINQEhPJuAAOGl8uC6Xe3IYDtTjDOe7dv4uUMj7/5Ev86he/HgUqekXOQK/A4eYaE5y2+CkpTjGhOjas9NF6iX1ibOWlMhRMMJrYee/IiNlYoORfMr3NLPdhXYpLcWMurxB91+5AyhOn+oY7tvN5CbBDZGaRMIXXy9jXR0XxKCA9lKd//PWtTkiAWEyAJVb70E3UbMyxmGLvpuHFwd5jziRS9XAEjJuYsyq09RA7PoB54xkEji1f4j1SWnu9AR4El6V6BQqGb0PW4uNCwtpfzYD1BGtxgKVReUZfFFqobDOsTqWjarI8NkUsGH77PtopQFGQ0WHdmjLtPoihaQS/o0MI8b4kVvkzk4Mx7k+QhK1TWgbv494AQUKsDLKmjYB0BFdjVEXPvAKGXXGhATOunhfQ91XiMqrnQGcwiJ7jbUe/U7/rsa46aBmu729pJXwm2k1rTgGxpFA/dUjVxHUzJrlCbS8Dal/bdpSVFs3TiIPBBlnVksmdNwYrRuLAgLm/2dEa/bBg3sxSgAiGbg3b7UZVa6LEeiRIhMWz2bCrj561GfvMPp5JHCqx5tcEoxwlFzA64JotumcMtgZTssk9XGuHx8RioTLkCXDxLIcD9tdXOOwPWFrFzWGP60PFfn/A4bCgtYalLliWhhi9sLSqz3SkWtGWigRDmQwnJye4uLjAyy+/gO1mw+8/xRA9yS9V6TvWVl+2VQpvZvDmaCDHocOGAVR4voSa4zhZ2G5nnJ6dwH11gd7vb/DJR5/gow8+wIfvvY9XX30Vzz93H5t5ZtBHVMura6djjVfeZXiu2Vdjv46KKCEXJlBmCdkmfPzJZ/j400/w9tvv4OUXXhRvrY3D/7gNbbaqz5icViBlHcpRefGbE+2MxFQwflTYR/EBUHWubRNrAfquMVOnmQ9FmoFE8XWsQrR6q4o93pneJ5Gf2SaKgi+ldcqy57Vo5D5nwdlaR9jn54GUGixzIrUjI9u6PwwYyAvX/4Rbdy85UkOSbzcbtgvhxj0nqI1rSDZhWSqSrXy/NcLqvLFI7dpa8EKxJmJsYiWXPMnLCjg5OUF0AiIkJov8MZquCR2G88s7OL+4NdyQGVWJJEVsbs627Uh6E5GWUaS4+Gi2xonQ3/yx17c6IYnJlskokeudGXsGlOE5cl49Q0I5ERstj15sh7VAOWwQMQ3rBgmb6CBgxiYAMBZKStO6AGUalIUm8F+yTTJN09j40xQzXXj9EUwGkc2MhlE5AUJMDI6S1wXLdWFsyQRxUVVuKdPRnJEYdhRVLldlcGhCQZJy0rDBIGJGpWTqG/ZhRta6XA1FdgrZZiAdca+SQeTZjiSzNFcQiOmsjhWIMH1mk58FN9zaOwUC99BSN0i3HzwPX90DFQzcsc7hUG42SK+6J+S4Jh2yPiDogJH7UNmsSUwXCZjqLUeaZnFbABRDrkIMAn41JTOqZpJlnJ9t8ORpKD7owGoKGNnISbACNJCo7SLnegdsWttdioyI3HqRf8zzz93F1fU1Ts7OMGmQXMkZZpkHtg6agjR4MGYYFv+tdyoh+opSRNsuAZzpJAlltAihe56MXIwq19iokKOlEYdmTgW9Nex2O+z3B9xcX+PhN1/j6ukV9vsd2mGPMMtzM1QHq7vEBIi+Lwk2ZeTTDXKZcHp2itPTM5ydnFDVlQw5YVTbgQL2Hm0+W9E7J3HXwYM0IYnjkMZhYAmjBQcHcqFXypglJQ5NJGCs+Du8kUjZRMDdTgXvvP0dvP3md/DNw4d47w/v4euvvsQLzz+P559/HvP5KYp31OWA0cpzHB1KqrLBZEmlNUJOHihbNkOvHX/48EM8ePiAycjLL7PNYWFToH2vNZbEDYtxHA6jfDlO4owhPR88o1CnWRA1uVYs2pQmxCgb2Vxm4r75SK7gIXvv66gJj4MuI6HDpaLMQmyaKndrvP5sJIJaXUiATWux4nJTNXE0TIheTv0IkXUU3cdQUVLJpGI4YShlelXSn4CziwvkMnPNxmGeJjgqnl5foVmTbFeJhopjQ0yDXkUF/O9I4WgYyLiqVpQZcp7YvlG8RCbPbpoSbp1fAPBRmHt3oJETw33PxPlwqHjt1m22xyyQTIxYEgVIkirHB6q1xlTnokenk5xQQ8f/WT35f/b6VickUT3G4c5emI8+P4ML2wcR+IqmOUZPjJPROTSrlIRQObnJXXPgdRhJTpDywsxnhTU5rdOAZzTaAXGPhEgk2Tg4w7nVmHOAmkwHTBUI16RY5PzeNlCf4MHov8GhbGOWBwLtiaTIhDb0cWibQfAgq+8iqePK7o+DXW1q1/U6yObX9Qa2MfqI7uPgYaV5lJV3cSfSauk8PFIQnBYfaNGzTzz+m1HZmw/0w23dQTGO+xgpGcXcWB9Y2wa2zj+CKookyaYdX4GzFeRCZBi05firJKa3hp6VXOpfppSGEVuZJngytEqJ6v7QR+IYRmk6U1ihJTL0U6EHQl0a0ok4BgqqCCMigyo83sN5MwM4ww//5E9wfusWHj19gl/9/rd47v5zHDGAxCnMAylJ6x7RegV4KARqdWy7n0tG7Q2TlaEI672pvSDOR2IplQKR7EGABQ+OMuHp0xt8/NFH+Pyzz5DMcH5+gZPTE9x97h4mQeRFpVlKGbBE4ug0q3I1TJtp7M80VHJMDOCcAYSQ44oE7X68xg3m7QhZEGJp1J71WI82A4NQTP+VoF23TBlztFSGsZ7HgeFjRRmAsDd3TUm9vDjHj378Q1w9ucJnn36Kzz/7HPdfeAHPv/Aczs7PqAAbCOVKxI9WMRQbuiaKE6VrKJbQe8avfvkbPL054J3vfxf37tzj4MUBU0Rr8IiTMYo0Fn8k1Qsd037nZzK2mDksr6iSukljbTYXfyHKax2qZgkZkGpPbVbjNPLh5ApgzA3zIwRbzyeJ91fBOOU63HMhWhkBgIWGpAcefCXGhaxAHIhy7IfF6TJLhKivsSKkf8DgcFjKKGXCYVnQqlORlTOQC26WhsfXe9y9dYHmC/rSAOOkaYeBds4KVwbd7+DUqCDLBljH8ViFKEIjBuWccHZyiujzcbgoeWce2YkRomoOnJ6d4+7dO5T8G8RN0TOCEmDDGmcituoZwJ/lTqaUFIt9XMMfe32rE5KQIPIw5G0IMy3XYRZcCoPUEQN+l21vbDpL6M4DqbU+5sKMain4I4KtgoU/DsJ4EBZOsYRG469DgdDR4Q1S78jWWJra+C4w8TeOq3n4CqG7ricfu4vyPWL2QlgLI60qCldylGDs+9o4e4nMgIcbeTXrERx8Dt5TDPg/Ep4ggXJicsI6FG9dnOo/KLwdXbMIggZbeTl9tcm2Uc2s/I5nk3K5Prama9EtTFKruKSqulbzlc0e/JggRIepk+k7YhwdXF1UZ3TAWCHlYnDwIKe6g7B2WPR7bGajqRkHYslrAYbaOg61Y38ADodFlUTwj2gAVluVwRYPoNYbkptcig3wjqzkDwi0CqitY1awmCaSZd97/z3cff55fPLZF/j0iy9xenaBs7Mzcazy0ToW52ooqzKSyIZhVw/gGblq9pinRNVRMwC9q7/Ox1X0cwAwa0OyT4lyxc9/8fdIZvjOm2/idDsj6yBKOVqVNJPrmvLMdmuGW8Kkhr6KOpjRI6TVjt3NDo8efYOrp4/x5PFD7HY7HPYH1OqYpnnwD6JHPxXu/ZwMJ5sZZ2fnOD07Q96erATrkpHyxOq8hftzQjIpC7KUHGZ0bOUKGgqRpG1vDnhrY05K9s4DzIBbt27hZLvFo28e4r333senn3yM1994Ay+/8jKmEgMOGVta70S6ugEqkHJKRAZA4uX+6Q3e/d17+PqbR/izf/HnODk7RV0W8gsSCzm21IR4dhUEsY07AHBYXtjAs87jPsmRiKkIIQeuj70bKKflREMyxZehTPNjxHN1+Y2oEUVCkODhLuRT99lyHJ20je8Y6hAOeeQ+JldC/LD9IaqswceC2g3OTBZdahK2lYTahDpFrX10Qy6U2sf7T7MBN00xXgErgXt+cSzVoVoYjoaYjebOZwYLtdmz3DZ9/IjdLAL7MBNkOcN/s50Kgk+aOr9j7X20obq+1+Gw4NVX3kCeMg0dEe8fbZqOjgYkItohdGAxRiJxCCPcY/6TFKXoY63+sde3OiEhhM62DBAeFVnVavQM6dXRtWnNTDMyopcfLplih3RQXqcDrFgZplFRlfSmEc1qocSmMZ0/rqSiy02w5MK+M+SLEbMqnEPtxpj4WDkOwG3MdHCEkkfJSGIfPlAE7htDaN2zpmvGwRfkJ8YYShFzZjtkIAUA3LL09xiBMw5ybg4SHBlos9ojrMBCurYeahjclki2eLgllJKGmyKgLPsoAQoZWiRcxxcSxOPgdYwZN3ApNohsAWFAdkRi6338/nF/PGe1cgT7cnS2DzZ6RE5XstI7YDmhGOf9mKtVZWwX0twroaMjI6PMNFoLi+3unS261rE7LDgsTZUjr5noVCfKNRINwzzPKvKo8GneaFmu5NVtZczzeTKV2h/2uH37Np5cPcX/+//zrzHPW2zOzvC7d/+A73//ezg/PUNICaw3uK/qsvHSOkFrgGbeZDWi3TB+P2YB8ecrM9+ODt8oltF9rI/9zR59qXjplZdxcrLBnMswSTO1WDhtlZLdUgpgaQSwCNZuHUgZ17sdfv3LX+Ozjz7BzdNrVD/I8XRGzhnzvMHJ6SxCqgzeJOG83h1gaqtYi6nTDtrbJJppSZWRc8Zms8F2s8VcJmznGdNUMG/yGIY4bWeSJJMh5QmTZZSUkOSU7JYxR3vFHT4Hd8mwmbfYnpzi4vISH3/6CX737rv46MMP8Z033sCrL7+CPCcs9aB9yzUH2DAJo0GZ4bBb8Muf/xqPr5/iL/7qL3F+ccGxDc3QzAErA7NJPdpMkKEdZw7BIVQPyFHcJBv/LjhUZahoYiTG+oyifRWoMqDWaxxmmkjtsjRgi0A8L1/J1GtxkEYcMcUSomNCQI6m30YSs69sqRkc0zzznFCVE/u0ydzPWlKrj5hO0iHu6jRyTUY9oAGRKoJefOE5fPXVF0h5AwLivBe9VTx+/Bh3b13CRYIPczQHzw1O3JWlhMj13ek0G67Fz7RLwAS0ax3lBGw2E+Z5Rgy5dBmYJSSCMJpaXmvHNG9x685d7OoyHpaFqSZc7uAOax0Na5KJQMrEleJfsW3fokVm+Z+HD0kurFKjL9n6eugbgOY11EiCYqGAbxryxuzPioywiI2jFL5HkytgEPbEchikI2rT9RKq0buRIyE4rAy51PpALCckc2rqvSF1U0Jhw98CvhKyhrTUjNAdon+/9hFtZSnBDOTOqJ+bVbGbiRPhTQudI9x1RAhOjosU9Kf/DvY2sAaAkSSMawPQuNFztDAEb5oIoAHd52IjeYmZMQgEyJwzh0ay5AOxIMJIiJcKlY7Rae1RYfF+NjAoBhyfxgY6aiUBgmltVOwuSNySlESdwWwqM3KmmgNGbtKUgFUejfE5RYS8IIX2rkq/ZEyJ0uunN09xWCqCRgHwc/I0SXKXZJQGtgIdmMqEdjjAjLbxvTtQELjTIFXmXJQ8MmA+evQELzz3PPzHf4oPPvoI9bBgdzjg17/8NX70ox/j9PSU640yC97HoyTDgNHWm4SWIBln5GA9dAz01IiR6SEj5wBMQDeFz0qHEwAcdnvU/R7ffPU1Tl56Cafnp2qpGGIT51yQBxFRvIhY9gPBYxLz85/9Bl989iXu3L2Dd95+Cxe3L3FyssX2ZIOS0sj9o0/qTuLkWBNqeXWRg707ltpxdX2D3X6PQ22oS8WyVCy1Yn844Opqj6unSjx7BWdC8bTaLXvcLAf0NOFk3uD89BwXm4LtZoOT7RbT6QlOTk+x3Z5gKsNfmXtvyji7uMS955/D1dVTfPLxZ3j/gw/x4Ucf48033+D01kkk2srDjNB6guWCp4+e4mf/6adABv6v/+V/iYvLC1wf9pK7mhzrg7OAZwqL3misiNSx2+2wPdnCSmHsioiQVAn7GkcG1y6tLQ8BGaMVOMjlKRrKUMxxzarSXbD12C1SSHrvQLTfsb7CQDGWJcTl6r2Oz96A7rhUc60owG6/x9cPvsH19Q1urq6w293A0TFPGZvtBrfuXuDy8hLbky36vnIo4mGPVolWecqYNrN8kwxnmy2KJ6AbzyatVUsJX37+Gd7+zquoaueET1PvdG0GWHN5xGyUdT8ojqmjtD43xMRgYMoJm+0JC0kp9Kgq6gO9gjNZ7Q149dVXxIFkfO2ucSY82LA+Hn/mTzqZ+4o4uyseAkihovqnoSPAtzwhqa3B93tMZavMNA4THl5wBRsDADK+3fGMedCQkCm7z4KqoUOtN0cMHIsoFi0A12II5IKLioHaBS/GvggkI4hAcRAnuQ0SdCBsTqdLHnA8XGOOC4HFAYcKmQk1UfR1Y/UM1AIyHstrphuVhTsloD2gcAuuCQDdI/IIjiqNQF2O/mZFYpK8E0xJkK2yzwQE7DpGgOvfIKoNdxQlU4hERBuua2LzP/xcWJLr6sB6xMOI4KffTmG3psCFlXQZiU0CgCzy7riPTOassCfK55+VAjjCMChlvlfM/+HZK65FEvyaDEttePrkGtc3O8G1usvJQLc8JqZh4AY9j5ISxwXowVG27kdrQpWKklmuNSVG3fH06TVefvll5GnCf/iP/xGbeYP9fsEvfvULfO9738Oty1ugt4mkmPKyoK01URNztVyEaPW0Io+RSM/bDYmJfrT6lZyy8DcgOwpWlPPy9m3cu3sPn33yKR59+QC37tzF+eUt3Lp7D7dvneLs5ARF/ABXcdBVpnYX6VxtxN47lpsDa7rQH5gAAQAASURBVHZLKNOM87MznJ+dokSbFEzilkrL9O5tEJh5jhn3YwemDe/hxpgYtLF3eT3L0oZpVRzi65d2LIc99vWA690Ou8pAX5eKw/VTPH78BF99+SUe73ZovWN7eopbp6e4vLjA+dkZTs7OcXF5C/M8oZRT3L51G/efewFfPniAjz/5BO++9z6aGV577TV0byhTGtLRZBkPvnqAv/3bn2KzmfHnf/anODs9W2c1RRzC2godCMPRvosE/+RkS6RZVvsACx8LVE5k/p58jGLobVXzpcHNCC8ZV7IQKLPrb/tAU7vaMuEQPWJcXGMkNVh5Z7yu1f23R+tJv5nLJNfthmwJu90eX335Fb588Ahff/M16rKgtQWtVQ3yk1tqAm7fuY3X33gdL734IiOhpaGSTCb3WPDzLs5vIVlBQtG346DVZobD7gYWHCrEEFeRjtUi6onoayCEDu1LxeBkGM86uIzjLqaEk+0WIQcnau+D4JwVO1tzWM64vLxAzqaiGrzmRD4QAJjH9GWdACa0f7RiomjEEV8kPI3+mSQk0/YM280Et4ze5ENQWBUAa9bdhq8BBsxESZTc5ADNbOHvLLIeN8vIk7JxO+IeaLMgOZpzE4bPRpIe380lk1y3mpnBgwDbuwBAjs3LMKBHMhqsfF8XVA+pLBBBPlseiiC+TBbJQlb4hXnFHrK0NXEhHMpkJylzJ1GRGyQO21CZ8D34linlleMSnx7wrNmQ2bmshcfkR3CzpUgsYvggCAfjCL2ITbzeP2D0zbUp2J5gRQbEv03DXjo+7zhxHK6oes8mBOAZeBR9RagUeBAMdlNP26NtgRGwALYQQ40TjyCVqOwcV1fXeHp1PZ4bv5vageC99YitXc8NgLeOZTmgmNEnwn18TyJLUgmBQb93QE7ldEr0hkcPv8HLL72An/zkR/j5z3+BnGdcXe/wuz+8hx/96Ic4O+Wwtt4q2mKS8K7sehJF1yqpJEMu3Euhaoq9wDEC+n45FA1qMWnJcrgXlTl//Zd/ga/e+AofffgJPvniC3zw6adYasNUHGfbE1yenguqp8qAf67oGsBn27zj+uYGAPDZRx/j4w8+wNnJCS4vb+H84hxnd+7g4uICJ9sNticTcjJMeYKXFtuI68logNjl62OdY95D/u+N82gIkRvKxHEAvbWjewRMU8EWZ7i8zcSQyhomv7UxmandNUm24usvvsBXX32FLz77DPtGVVEpBZMOjnt37mLabvHCCy+g9Y6Hjx/jNQPmzQYxvySnDT79+DP83d/+HS4vz/CXf/EXHCO/UH4NkYSHikaFyLFDMoChsOEa6DoQ+/g9SkAzGtrgL5B/wvtI1R3kqxH7Ue3gJBNGJZEJSWTYNJLhYjbsEdiG9xHXgvQ6CMmKAypTnlHUjYSZHwwrhoKMx988xJdfPsAXXz3Aw4dPAHecnZ7i8tYZnnvuPkopePrkCT7++GM8ePgNPv/iG3zx4DHefvMpvvvOO9huZrYxwb0aCR7csdluGY86kFrjeArFmd1+D+SEYhDvpMJbqKWI8qXOlWZClSOYFMXa3jqQiLBQ+msCEzm/KquVHfkBC+KGddwD0GrD2a3bmDcc1YAj1NL0j1qvR8q5pjPgaI6UqcBTK8vNlUjRqPG4PffHXt/qhOStN7+H7ckW1aiOWVrH0snvaD3MiQi7JgfQO0pKWBYxmq3Dm8sH46CZCw21rhbJJoJmFmExpYS2VC1ywJeFGawl/VyZI4ClLpo1kUeLqLnmE8CB1NE6ELOc3bDCdR5SL0OU9KPVoISBVQnvxWjbRCQAjg5ksqUtTc/83eCYrL71CPdLfrIcO/M6bj4qZ94/oSVB1EsrASssiQfWFweoiFU08D9KYoCBRHUR0aJi40ZYSbS81gZLE8KUaoX/V/JXP/47bSKVv4OABWBwQ0oOfowuOe49AHSSE2HiAMHXCsFttDFCEmdi4VvIpSVXfXJ1gydXT5WExFA8R9W6NRFHrfNeBZnVwTVmzkMgLn+eMlzeKNaJyuRSYJXrssMBHVLoQFsqvvryK7z5xndglvDLX/8Gk21x9eQJfvbTn+IHP/ge7ty5TSmhPCtM8LbFOjtKOLJg5MXaSPZWBYSPYYdmCVNZw00kxlkmeu4dZZ7x4ksv47nnXsCPWsfTq6d4+M1DPHr4AI8ePsRhvwe642S7xenpKU5PKeUtJWPebjDPG3Q4lsMBu90OXz94jKdPHxOhWBY8uXqCB08e4+bDjwDvSF4xGbCZJpydnOLi9i2cnJ2hbE9Qpo3IwORV5ZQwgYVGAlvF3VUU2FgwABiIS57GPoZg6yAdFsF3y2GB5YRN2mJWX9674/blhVpdRAha6+i1Yvf0MT758EP8+3/zb/D10yukzQnOzs9wejrDveK1V1/F7Vu3UZcFv3n3V/j64Td4/e3v4O233gR6x83hwOQZSqRzKKCO9poHrdRH8klCaRQslclXkheIN7S66FpFNu2AIEY0SXmt97EXOTGZ5ohOyHYkedzqUcTwZ8LDRpwN5RBvN2ONAUhWEBwQOFDAxN6CEyPRRzguf/zRx/j4k49RlwVXV1e4/9w9vPHG67h/7z6RC2Oce/nFF/HO22/jy6++ws9++Wt8+tkX+O1vP0Kvhj/9wXex3W4GeZvzELnXp80GlhO6H0gozRnq2ajttxD5mgsgS/wOQ/I1MR4IbG8wSFIvUn1KJNIGYp2MQ/wmS9jOmxEzYyQB3NHRUCyKBvJsXn31ZZRiaH1Bb7YWoUo6Ugeg4Yt0n1hl/RjrBmNGXLTjiuWVy+r/tKTkW52QfPnF15i3W+zhgNj2LWekXOA5+m0JJW0xpYQpcWDV5tRohuSN2asqvTFjw1dJ7iGSh1ywqP/WWtf4cMnvGr0esiyyW6XRUfy8LuFayMVTa8WuLlCXAeFI2HuHa7OT5KrPFmt56Pc7kFIhHHZ0eMbwraEtBxiAmPXA9XMYxrCpaCwFcz0H/ybY8UkwqxsQwcMi+xXaYgmt1yGzbTGzRxCEK5BHZRx935X7ojZK7wpU/M6CRPj9REhDMillou2GYUlttjq7plKG98ixNPu43RRo2arCYUIXPXBLK7piFkPnyI/JCMgy+DNKxtxWMqzecjksqK1iaQ3X11d8L7QhfcaQiIfiQAZbam84DLUvQ4XUGufaNOfk1SwEJ+SQo+rUocCWWAzx6+jV8c3XX+OVl18BzPDb3/4OORccrm/w7q/fxdvvvI3L25daQy7kLqo3tYQwlhL7/VCQ4kWTGNi7Vpx62zm+Y9zXICsCkBeFliy2OWOebuPy4gL91ZfRasVy2AHdUUpBDHMrJTxwgDGPSNyV11+nYqzWisNhh9odu0PDvlH6WA832F9d47Dbk5vxyceoraNZgYP3s+RMFCglzCYOkGCnnGnL72rz0g3TxIXCkIC608K8d8dUqOKZpjxS5ykX5MKEn4hAw9IOA+5+8vgxdtc3aDc3uHl6jU0pONue4Nbzz+P2c/eQzPHFl1/iN7/6NS7PL1ESfSR+8md/hnvPPS8iNf1xcrQ6wP1FUmqgkUCrdewL9DVJCDfS2JOlFMQQiTBJzADXP/idB4TvmnCemKSZU53jveueudBDrv34rB7GduKG5VJguTBOGND6SsCMAooxRe0ZHcI5GbInqSqpGnv//ffx3u9/j+YsIn/ykx/hxRdfQs4Fy1KJPIqYWXuF94bLWxf4q7/8c/zs53+PD/7wKT754COczxN+8hc/xlLrM1yKlBLOz7fYbre42V0P9DyZIaWOQ3PsDwu2JydY6oLEwWbkiGnuSxIKclyHde+yatCeVpsy4k8yw3beyHYi1HnqFgiFdQEpvTdstye4UBtSbyQFKP/bxvoQFwck28fmX1WfIfmNMK2Zb+Pq/xkkJK98//uYt1sscCy1YV8rrvd7XF9f42Z3GD4iXiuKMrjZOLwpG5CbD6gpmw0vhpGVJ8OSCzwlNCuoBlgu6B6EOkPOhm0pOCkb3Dkt2EyZ80NyGj3vgPot3rN17OuCQ+UU0mrAAsBKRmscBgUHZiP5Fd7Qa0U9HIDWUSsrwMOyMICpbUQBRvDsy1qhDwRC8H6vKFNGr+I8FBsJCVzktJw57wEA2ftyIo2DV38P2GBQN/UZR8LSV05KkzdIyZl+CMPLwEdSZsjr5NcY863Dr3cNRQQhSnRDDLeb54wwpOMr+uBpuCQGugNBv0xKwuVxNUEK1VG8DOq1J6jiYPXYm6DQtA6L65XsfAOGdDilhM+//hqW2LJYWhNxGYPomly9YHlzmL4vbJ1HJKkB/x0zL4aZnNZp1notdcGhVUDDtEK9kW3lp9VlwZMnj/HaG2/AzfCHd3+Pkie0/YKP3/8Im+13cXK6QSi0LAjTPdpCSiiRhKIAeaKh3KiKzcQnWrlazPKeJRQPiXhYpFsk2kyhu/MwyvkMvVKZUvUZvXYRJ9cee6sHJQJKRJMjb2ZWjidCCISsxYDF2hY6aJYJh95Ql8Y5NocDE5r9HrvrG1xdXeH65hrXVzseJEZkoNYqJ1U68jZVkN6pjCipyBsi+A0daSojYV4J5S4uRgd7AMDhsEetC7Y54/6dO3juhXt4vmwxn57julc8efIUDx9f4eb6BttpAy8Tllbx7m/fRa3Aq6+/JiPDphYciBKDlutwJtmtdfRShnowOhGAWmsiWccgTG8Ln5mHh1EaKrhu5DelKEq6HznM6uxLka5CxVvMVAKmSbHFHbWte7KjIxcmv2uskOJG3hoEin0gvyyCGBWnacbv3v0Qf//zX6G3ivOLGX/1l3+Ju/fvYFkq3CtSor8HUdQETzzSe+vYzBP+xZ//BP3g+OiDD/Dr3/wGL7z2Au7eu4vaF3HX+P9ySTg52eLm+prt1JTQraKa4/ziHA++eYRbt++AHjnBvQNSJG4GTCaPo87dEApPxqooaBWGMzko01zGsEOuwYW3Jiea84Hut7UBLz33InLZYlkO6G5AIPSBKuuem9ZlJC2KljC5K7cghDuL5YF0RRx9Bt7+z7++1QnJw6c3OO0J05xxsplx+/YtbKYtYgJsESEvA5gN2EyZ7pTgBuySOLVacbXbY6lVlawWJAx7B5besFsa3SN3tOU+LJzwiN6wLHt4PQBXjclDW9DrgRBcrUjDKdXgufBwmTJa2aCb4ZATqifwKJPzbCqY0bEtGVNO2JaMzekFCoBtSpgKvwuntcrzQAfW0h3VTYGR7aPWG5YYOoWEBJolWW+ywmb1QNb4woy6r8ql6OGOSZ0OHJqr3ZFRnTN5iqyrYU4FFFQNV5o0ecryXDAhPUE8bmito/Z1iGGWQVBrDVfXO0xzRikFovSoSihx19CN1d2QdVuSG2lAxUBvRJlySH81u4TnpZxqn9k8R9b74pMa2L6JltSxs2dUvb2RUFpbxVIdbk2bXL9hoFkT1uqTfIiO2ioObYGVAlSqA1KXx4eQntab3C6V0DkVDQATW0cHNPmUhn6aAIsAVYnsffPVl3j99Vdwspnxq1/+Gs/fuoeT01M8+Oxz3Lp7G9vNBudn5+i1ItRMOSlZ9bVtNXhJxpZfJG6WVg7A8TA4AAMh+odExeD0EPhMmFyeQr3DCxPAWok49d44VbYFGgQEAZc3g+2JSa3X3h1FCUAGkx/X4L+Tk1NeZzdAsuJowQH0dklImHLhIeskgi8KvNE6XJYDls5rOxwOqPuFqMey4LCvuNnt8OjxIzy6vubE4MOC1isLhs52XZAyL05P8eprLwO94vblBQyObx59jaunj3GrFGzmGXZyipOXX8bF976L5597HqfbEzy93uPTTz/Dz3/+a/zh9+/jrbffwiuvvICT81kHNGXCbNsyMaKnxurBAlstDbKtlgWh1bY8j7Wo04/ASmtsdSnJJMdmnWPTXUwPk8RV5GAxpaiU8pXsOsceBUhKskjeWEQthwNRUgfM1tlBdPBVyzAnTJbxySef4ac//SmWZcHtO7fwN3/zF7h16xLLshf4w9KxRhs6s+3TtceWxv34zvffxjcPH+Lxw8f4+5//Ev/yX/032E5bHHBAaw3VO9ALbt+5hcdfP4BZxvbkFJtzhz96gv1uh1/96le4c+cO7t65jVB55bDcFxfEtOejfYeiwpCRR0glUY2SMrabCSbUkOEpSKU+EG2OAejYnFzg3vMvYOld3xuAkEG6y3JvhDcU41dH6mkkO5E0WsRNFSswV7xUXDiumP6R17c6Ifnlz/4em80WZjHGGYQKpQoI6Cyn8IegN0Ayw2azxWbesL2RyajPcZjmjGmeOSkxZ8zTjO3JjOnWJT+4d1XACdZpTLWdZ5zPBcloHrbXoVhblwoho3U6CDZnEFt6x/6wYLc0HOoBy2FBqx2+0E3SWmW2747dfoerJ3v0/R6+PxDOrMuAMz0nukjmgp5nIBfkeYaViez0RP8EAPDWMantUNAxw5HhmGDY5g0sTcgWZl8FVjjMif4ZmvhqGYsVIGU0H9oWED1g7zU5kx1OxyVjnfhvHZslFEUO+XD0rs2vFlbvsNQxbxM4vyLUPAFpivQaCEsYwsGJZomL0kHvDvbmC3LOVGkJ5enogno9zrXVdClKumdevlYBHioAQ9I8DDRgtyw41AYrRdN54wBXKTReMnc7ag/x7VmNkOgqJKIkrg9teF6vkww4IGs+byOOKtg1iNoMJjEXpbeOr796gPv37+Ott/d4/9338PJLL+Hy9AzWKr5+8AS3Lm8jj4GIgZmt5NYc1v++3iZTq0m5IGvGxBk5w6skGVykXDPtP66ElZlvNtRZSdNnk77fJHi/tpDXcm03JU9re5AVeqhF4EfqLSUW8ScMY2ZPa7Lx1xKIej7pQCbM7bDeSG5XgOZQRXlxnJ6K/C35a+eslFYb7f/NsNsf8PTqBo8fP8L+ZofDfj8CeLGMs/MzpJRweXmO8/NTvDG9AzPa8XsHppnuzLv9ns6/3XF6usXbb7+NV15+FZ9/8Tl+//vf4b33fofXXnkJr776Mi4vbxG1c815ERk/WaFSViMdAEnWE5ETm4SG9jaSv+w+Wrw5J87CslXuOfhEvkqA49l2l3mlZRSLoZyJCWa3tW0Yh13EMN3rZAnzvMFUItGOEK3xHaOVmfDk6TXe++BDeHKcXpziJ3/xp7i4vMRSGwws7sz4TEKZWQH6UgHg7B7uzdv37uGtd97Cz3/6M3z5+Rf44vPP8eobr8KTI3VawD/65gqffPY5WimUIe8W+auwuDns93j6+BHu372DoOo7+lER2IGaUTLYDxu3rUf+N4wQu3MdFhRMxog2OEGm5L9jzHJr7njplZfpK9PrkbW7SpbYGwzToXuCGUnj+njGd0vDZiSSD4crFqpd/6zh9n/29a1OSHJ2zAVABMeIGgq+NCajBtx6R981PcgEbz6m/iq1XiEpCE5czzYkwf6G6HmvFvLFeHBPhT+bpoIyTZQNpgwrBWZMFtJUMM8TpmnCdrvBPHHQVlbiNAEoJifOwqBTJh78EfRbZY+zA6iNLZbFgUNvagdV7G52uL66FpTp6L2i7g40pkoOeIN5h9eKZg1tadjv9vBGK3PvHd25cD1l9l9zZhWTMponLMaKCkKkghNCTk7GnBI2OWEu/JMSUkNOBcXESQCUOGYcEv0DPBmQec8MRvgxkS8BSB7cFw2r6kCtaK3CWwNqp5KgNTlwMhFwBc2AHDtv5IDMl8YZQTlZZEMDks6ZaFRTdQQhBTYk4hiJUtYoejhw/fARrq6vng3MCrBNFUuOCqw7PJG0Gv4jTeS2DCJO5o65TFj2h2E6Rlvy1aeFYFcfAShImeMgUFBLIPnQEs2vHj18iNdefR27J1f4T3/3t/j+W9/FK6++gkdffoPf++8wTTNOT7e4uLjAPM0DwYjXYCJYcKJIyma7eSVJhpBUGSmiAid3yIYxIVykR/37SLYABl8X6TPnAsudz97BA1OtEio1+HtLq2yFCm7uvdOhNqURfAfnBgqq4owE2kJzsM5Ezg1Fwbfr8+LajtcF/ynfNxLRcTDrOnB2gZvLBfbyCzDwmXLeVZexFdt9OYWSzMm96F2EfM432WxOkE8zW8+S8R/OKzbbhLt3L/Dw66/xwXt/wB/e/S3eeO1NvPz6G7j33PNIs6NWthLtyMAq+GQe3DILdC8hYxr3rbWu9axKeZLqyh29KuFUtXy8F7pzvx3/nemmMQ4IObSRjxzl8XECqgDV1HOEFxWwVvf61c8//wxPnj5BswU/+PGP8eKLL7J9bVk+LDoK9AwbJW5YjO7fOSUSRwHMm1O8+MoreO+9D/H00Zf4/e//gO3pCZ7ubnA4VGzmE1w9vcHlvXvoKeHpzQ5XT69wuL7B2WnBd954Gffu3MYrr7yCUgoTutgd+q7dM4erjmMo7rHpyIqkgdeWDSgG7gU7mjMzWtlJe8wwb89wdnkLyAm1xy5UJDPxC1MIFnx4pMBDBai1LBL3+jPNRPPg/gi1/acBJN/uhIS9tzo8RRhQOCzMtHqHQZcckHPOR6OTtdJHBZwkbVTVqQQAYMD1JgzAVxOgsIDHwcX3kPTXoNHjgMuBz52HS04ZUH/1mK3MvqwOoZTBGTFSvRQGGpc/SecvwTOdXlOZME8Tzs/PcXK6Jent9BTbMtM9MmWcpiTORYEVyf0SB+mx59po+NQ6DjBUJBx6x04JX/cOrw373Q6tNuyvb7AcDpRFLgv6sjA7b2wHcSS9oy0H7Ja6ejVAKp1OglkTGrAgYWlN/UhWNrU11EVNUstwMMCVKWHOCVNOuNhusSkF21KwKYQtS8lrOyEFdZcoxNLJS/A8IU0TEyxVyCmzRWY8LZAbTb5SHES9orcFrXVNme2DELa7ucH7738IuMETJZ2s+qOii0oDsaiGDwegw9GNybMCVJhCkTgoBnvraMsCQ8eUMyWYEcxZtKMr4Q4/FOhnAzHwLidXHp61dnz11QO8/f0/wbw9waMHD/Dk+gqb0w0uLy9Ra8X1NaW0zz33PNaheBAyoqRerZMIomaE+11JU+uN67jHwD5B+Uqoaq/cbYYBW4evi6ua70pSemWgZTtBZm3xPbEOdgRYPfKzVl8c71X/uzDZlNIBaqHlZDIv9HGYSuWN8KYYXCUlGJOSLz/iyQzCIQIpwOA0GVjopDmNa0fK2Gy3qPvDQHuPLdgB4/DL7EDq6KVjCmRRag8kOjbP8wbnZyd06728wGuvvoynj5/g9+++h1/99l1c3rmD7//oR7h79w7MgLPt6vcCk7Nwp5HiKhFe128QHzaSPHvvqDXkv6sCBCMpWQ+nSQlW1x01Y/FIoErtm7yiNK11Gi+aUK5MN41nhpEev6fTcQNI+OLLr/D7997Hw8eP8fobr+Htt97CNBV4o5y/zCxgh2IQGTO43nI1LJaw2y14/PQxnjx5jM8/+wKPHj3C1dUjeEp474MP8OHHH6MpGa2N69SFTG+3W1xcnmG6PMOtsy3uXN7F/bv3kMsMyxOmso7lyBbDPSkZdnFZop27ummLr6b1sdlsUPIsBMWH/LzDRrfAVADduX0bkwwYocGHuWSg+kAbe4uBmVT+DZTKVx7eaIcb21y9dxTNdXKtkXTcQv0jr291QnJzdY06LaMCJI9Co7PV9+LeCOgP6AvbO6kY3BdWHrKBj75bt6NgEpWZYFr3IDYC4ZrHytePIK4+khIAw3CJ0LwDvSHLvE0Ftz6JpFdWBeH86fC2wFtFylUqG4Fi+rwx/CkXPPn8U46xBuS0l4YMbg5ZKiiYsRzW6zE0y/j5KaGXAk8FliekeYvNZoNpnnCx3WAzk61/VhLm7RnmTOvrkgwbyZuLEijIon7fKhZVtns/kuraxIMXxkFUywG+LMhgddXrAm9EPUj2o6IpUI0wmmt1wfWyw+PrhYkj0drhXAqsh3ptDqQsng0DR+2UYFsmNF0Kk9ONAdupYDtlzFJcFGMQPJ3pMwC1nK6sYC4T9svCNksu6GYghnFcKRhBJYSctinV0HroVNLQabWpMqIXRWQXpUyYpg0Z9T7+elVH2UqqpSsjQJKsBrkBqxeMXrU1fPXVA7zx5lso73yXLcda8ejxEzx6fIXdbsc2GHOz0TpptcIRyYlacEPvt8LoCFRMzyzltLrj+rqf4m7x0G6E0sH1CkvwGmiWbLexKuRqXVBrH+s8gmZKE9Jq5cB5LDaPRLvkibyg3ijXt6SWnrhTlqRu0EEZ8n0lZjQrd7irqDFbJ0G4P3toKrbMRZOWJfWOxDVncjqmMo87uJky5wh5V5sy8eAyFi89dbQeYnqMpAxaO5t5i/v3n4P3jufuv4B7917C79/7A37/hz/gX/8v/1/cu3cXr772Kl57+QWcX5xxdo9lTPOE1Ng6PS5yma/wwWU4sNS1napfsJSfmfycLACmNhIHQXqjXVZGHM8DsQrkjN/LRvXd0ZigtHUYokNursgDPUml4A/vfYzHj55iKgU//uEPsN1s0GTTQNJ4DF6Vr02nJcTVo8f46sFX+OCDD/Dpg69ws9sDZjjbbDCXCbfPz/Hg4SO4JTz/8iu499x95FLQmuOgwZmH/YKrJ0/x6JtvsLjj8cMH+MP776HkgvPTLZ67fx8vv/oynnv+Pu7cvYt5ntFqY9HaTedH4uykTG+PSAiqfOuXwwE2TWiJ126u0qcL9RWVwEEV5v3nXkRGGehJThl96bAeSKuPZ8jH3ITe2lgHPBeTCoRAyFlgcv13clHAmT3/lNe3OiH58sFXmKYyTHRyypxJ4T5sx9l6oZRunmd076PnGo6K8zQDYGDNljFNBWEHPuSUoPSve9fwNAUnpujDewTgQ7eGsYkscQOZBphZDkmsCKm9r3AwwJYChCRYghX56glXCz09bNV+B5ScwEBnSsKsO3oXnwYMlMkMXTI1EtLaQH0sEiIADVJyoMj8hgs8riOZ1Ek66OGdcwJ7xzxPUqFk5FLo0CXPBssTUi6D51DKhHmaqUxKlD5uwARnMqDkhLKZkEvCNBXkXFDmGZ4LE7RcGIx79F9ZNUAHQ0C50cqJJC7g7rBcj2m7ra0D7oL7suxJ9n10daUET/4QTgVV6x2H2rCkgj0aqsizHY6uhIDupXzupg07dAatoaOjwJCEpKWUyDkCk9yGgidXe1zfVJycOp5cVWw3DacnE8wc4UfSgxgMVcyh7Og60A2ADN54r/hn9Me//uprzPMMM6O5k9M34eawR543QJanSKCEUl601oCEgRz0EQy53hKkQtLsH3bT85oggbb5bpWqjERzqK5puTTwUyWZ0jBiCzUP90jGNAVPQaiSEJja1Mp1R/ZIhlSJ6vBiHBGE3oFmPRoAEHGMyVYityzW09oNY8yIOU5RPIS65RjJyoXxgDNKODHZQRl1oDJJeySbDUfQnsOIESMOxcyrUooQq5VDE4MDW+vofYH3hnv37+Dy1gVefull/P6DD/Hpp5/hF3//Czx68DW+973v4uz0HHlDJCvnDNQV5eP9Ajz19X8jUCSM744UZOojn6Cc4T2LVyZeU1IRlzPHDSRH7oYqngrvG2XTrZGvE5yE3vsY/BlBcgmCs3cUS3jw1QN8+OFHMBjefP0NvHj/OdT+7CgDWruTfFvrAR9+8Ak+/eRTfPnpJ3h89Qhujovbl3jr7bdw+8493L19B1MpePTwIf6f/4//GVaAH/7gu3j9jTfI5XFDSXGOANfXe/zyl7/C2fkZnl4/ZZJRD/jy00/x8Yfv4b33fo+Ly1t47vkX8frrr+ON11/DyXZGWxbFMa79FbXnc5+mCTHqYpqo3qrdkSQXZlLsYwr30htu3bqNs7PzWK1M8KoPawlTLFh8NYJMqYz4wtoj2py8fzYK8JX24JAlQTI41sLwH3t9qxOS5dARcyOABbnk0Wf1vjp1JgWh3fU1ISv4cFIlSe2aEHeikwdHldggWcId82YDBGQuKR88+v2ZUkdjeyULsoJ3TPO8TiV1DPg5k6MJM84dOPQ9AKBs2TNeWkOrFaVMtBNGJAIyxXIeQLBMSLw7zFSLjwDPhIm3hC2AJnlwH9ViIEEYQS7aVpR6OVIKk3qgpSBHAgBh/w7BihZHgGPZ7wnZWoXv90fX7lrgnKJZx5wbWw8YJ/TtjQc0XUx9VLO855RjQ59fnWqLnApyKQhL5ayDcy4Tn0M2TIJ6cyd8X3LGdjNjErfn4vSEhOZSMJUJVjjqvkM26TmNOS2RHTIRaKhOZQXloqyww803EiD+WWG9Y7/b4frJY9TdHstuP9pbKSd89vAhljShKW3ZXS/o0wm25xt43mK3OB5fXaHMBdkcuXVMKWFuDY+ur5FOtlzfDshERUEHaLr2DsBlLx/zijoM+z1NtMqh4fr6Gk/3FTf7js3Fc9ic38dmLkx8wfVVksFVBo0kGSvhmD9zme65Do6KQ+uobfWzaI1uqPtasRwObAHVOqpEHu5i+Ake7r1jWRahVUkmhosQk0rVT6Yr6LERH1GYwljhSmI9FCEd9VBF/1iNtUiWjflRGQVlKJ6gxCdpeqy7A5rTYmmFrWOOT6hTehCPPSG5WlQGdHM53ZKzksDYMelesbvfR+Iyl5U5SOSTs7K6Zi+lWlm3uKzOc8Grr76IF198Ho8fP8H773+ATz79BP/u3/87/P69F/D9H34fr732CqZC8mu0NCzT3ZlVtIjo3vj9klpkQug4ZygmakdsyZJAi2pteGZApbG3jeJ5HHr8qMbZMOBUc4+WXHdUZyujivPQu8sTBXj33d8BMGw3W7z91ptoS0XrlURwXafB0Kvjd394F7/4xW/w6JtH6H3Bnbvn+PM/+XO88srLOD0/Q86U1HrnPd/MGxQr2O+vUJcdeWe9AtWx73uYJWw2W2QkXJxdosxb2G6P04stTueC84sLPHzwAB999AH2+z1+85tf491338Pd23fwJ9//Pr77vTdxdnqCkBY6mPSHK2wUqqVknVVqh8ch4C6FTIMlx6F23Ll9G6UkLEsbuKwp4eeATqH1rQ4vJg/al5IMV3Hb1b6xeL7RqgHRrogB/9DV+z/3+lYnJIebHfpmll8Fb86CRXcuRqjHwc+N0nRI0BFzhVBjGFsYGcVBF+2ZekPm+xQ6/r6sCIXZGPYWFRJhRQaCnEiEMpgGq3XMcxY60hh0jaPQo/UUJL5pmtYqpxR0B8p2g6lk6f9X1MNyWjep/s57x5SLFq6NytlBeHqaJgWt9gznoGtBJ0uYTTCmqpDxGT6QUgVj9cqnqM75A0K0tLkPBYOB/fjNJERrxbcBE0emKHnSJjM4kOMZNW1Sk68ETdFaO9CHQslmBTfUDkFG5n5OydArD0mSxHzM54j10R0i8fKgMyEdgZxtthvM84xNJn8nFVNCzDyFhMqMeZ5RUsZmKticnCCXCXkqmKeNEseY5iwzqZTx9OoKv/jd7/HlNw+xdAaJk6ngzt/8X3B5cYbtdoMyZfhhj88+/ggPPvsU++trtP0em5Lx8gsvYN5s0JL4MmZAmlABVHc0mJyNXZNrjya3VvpzJO84LA2LG07PLnB2WfDgwde4fvoUc8nYTOx352SYEzCVIs+NSFQ01fZIHZMl/e0pk8Q7bTDPGZYLPK/Q/JlQR3RWuZEQe2c70ntlZdw6UnCDDgsamLQ2wfctDn8Yic/aW+EKnJKhVfJGYjBZ7ySNb/XM2bpatDx52Oa8hs5sE1rVHlHxMA5hhOwRLFACXXUQWUg0RHNoGOgoIhj2a6uR2w1EsUpZx4WWicSlUFkxSWHs4QgBTjLm3oH8KXpvKH0l8Z6ebPD88/fw+Wev4Je/+jU+/uhDfPzxh3j1lVfxzptv4pWXX8LJyQlsTkRy1ILhFkxChYh09LGVXcecjWSXxGch13CSMHURwa/hd13b5hJGwcJ5VffSVZSnkjE57+sU76bC5+nVAV9//QglJ9y+fYmT0xO2hp3ciZInHPYHfPXlA/zy73+Nzz/7DPN2gzfffhVvfucNvPjSfcAoRW+BqDq9NgzAPM+Y5oKbQ8f+eg9YJ1EXwDdfP8JXX36Fp08f49HDR7i+3mGpHdU6DlXt6dpQUsbF+Qn+1b/6l7Dk+NUvf4fPP/sS/+bf/Fv84he/wJ//2Z/iu++8hrOz08E5IxeEnC2DhoO2aOWIIGvrcDuOKAFOLy5x78UXcFj2MNMadgBCsWBM4ror8XDN23E+WwOEygHomkelRIVztIge8qhQYtMHfPhHX9/qhOTyzi2kUjQPomvmhI2AY06oNCD2ZIZFDqloDvOYv2GoTtknj72sqi2hTGXcy1YratEBZtTbb0tBRNG1v6bApH5+z8xSSyo4qD1S60HQuUsy5Wh9xyRA/fDeG/Y3O4SU0/cHwAz73U4ZsCzD9fNIOoLLEu0KygO7/E3kFggRlhI9TQJ5MCjwjZkjhp0M47w7Z78FimLsR3YHcp5GwtO8jxkrUdXGi4GJNsj0eNDBYMHWFqFTm6CJb2Apa/Ko2h9Rfat6zVLk8EO4eQI6hII07MiZ0jAOPFMSmTqDZpAjq4b5rYor3dve4d7QDje43t/gWtLjrOqwR8WsDx8bM1QjMB0Waf0N458pUZI8bzYo04z723kE15IzSj1gedrQrk2Hf8Lti0tcnp4OXw8AsDLBckJ10FPHDD1PsFxIPrOMm8MeFQ4kcWMyA/pkCRtLmBwwOOYy4/ziAhtNek3Rc+iNMtPWUOuCZak8rBoPcG/kNfTWsNSKVisOdUFdDmgO7A8H+fz4IDaPZybiM3rDZGwRUaYOtYvkXxFJnJmUSRIumr5355prxpaha80VVYGAIc9skRUlB3AmKElJLoKIrRjQO9txTYhQc6mdJImslaZqroQk3IgNbNNFLDIF+dhbWcgKD2xjwtaKlFSQkRonYcfa8igKIFWTic/SOxrkkJsw0CvXQZEsj7larVZ0IwH2hZdewtnFJV757DN8+OGH+OSjj/DR73+P1195Be+88128+MrLOLk8BZKM1BASUbYLtLpVnHM1PuPaHH8ndnD8HosCO0K4xYHQv4vYFtlO8lV5dUxeNyFT2pH45uvPSbJNhnvPPY95e0LlXaJx5OefPcAv/v4X+OLTz9Faw5tvvYm33n4Tz92/h5QM9bDD0qqKFAoAiCY7ERtzTNhi8hmlJWTQqPDpzRP8x//tP+Dp06dq+XPdJnOODkDDkgFIMtv3e2ynCd958w288eqb+Ozzr/Dub/6A3/3hPfyv//bf43e//Q1+/KPv4bvffZs0BQ8wpGmCPY5GPHTdJ84d6l0tmEPHW99/XdYWhDwcIHKINIrOGFpJhE3tGHB+UUdHV+KcE91vofC4EoJXhDAoD8fT7v+x17c6IfnLv/ornJydIMyh4gCjsQv70LUSHq+1kQtQD4TW9WeGydeBKMvV7gZ1cRwWGi8daj9CLGJAmAyc4Nh3Wfm6I3cn4S8OS2XVPXcZRIl9zgKKioPCw8DlVzKVhJSYPHTJTIOUKATuGaliE+HOvaGMAW51JCpuHP3emxw3EtUD7G9rAeWVeOhqQ5nlo15lHqhL98qULSWYOQ7LAphhnjlZMueEw6ECwFC6hEsiExD2qkytqyQlQ0lFxOCVoMx9I++YkJp1Vn8l7KEtiJzR+gl+AheEdxmyQaRQBf+YPyJwh5CiYMmmZx0wO1VBSn8iIOofmyAOi6CZTIltBP8VMWH1vbLTR5UOchh4EDa0Ctzsr2XY9v9fWoS9dlib6zYgWmFEBkiA5MHMddHjfiaqq8bvQvNZzDArydnnjDkXlJRxmAp2Tx5hmmdMmw2mmclSmcpYK5uTLbbn5GCkQjXXNE3YTJRBmwHZ6fdbTJNcW8Pijr2MpCqSmPouQ7mFBOHDgv1uj+WwDC7QspALUWvHYSGXp3XH4XBQwt/Q6mFMjT4sTfe7A+vq0PN0cXZU8sf9SKSqmipFw1q1d+PMILa9VPWbJPDIbGuMAbP8dwmGAu6/lAwTdSlEJxMDfJBfFw3gc02+ZnLpWJZGx0/t3eBs996lrnb0tmCWZJNrm2gJkx4M+XOswyaXVhIe2UZ4+/wc77zzDh589RW+/PJz7G9u8M3VExw++hi3n7uHs8sLTKWwUOis0kfSBcdgKsPoLWgGCJWNvRry0mgFBPGfiNKx1JsbbXwftYbCnK+P4iNaQ/zvnGd8/fVDKit7xf17d0gCty2W2vCb3/wGf/u3P8fV0yf4zhuv4Qd/8ie4e/cOWqvY7w7kZsilNCUb07ZLTrDkmHLG7rADFsc2z9jO3C/VG7ZzQTtUquacCHhtyygWu5Le4D7lkrGZN+LsFLzyyqt44cVX8eb3v4tf/Pzn+Oj99/DgX/9bfPzhp/jzv/gz3H/hPg59T64hSTSaf9VHQh0xpsPQvGHenuL25SUtL4xtM3OHuRyghf6G63WIJYL+YEftadfzTUk8uYjXlsmZ9CNE+gjt+mOvb3VC8tnnn+Hk9ARzmcj9qBUlF5R5ot/HNPNnMj2zRHVDzFwJV4TeGgpPcB1aSfI5Hiww+n0sLgMkoR/X19fYHw5I7qz6dgf6VdQGoHMYGIC6sLI/1IXjzi1htxAhqbXRjQ+GdqiAsd++tEb2t3f2lZ2HE6VeeXioEA0i8elQgzzGgJnkH5KiL+hN1RGQnN87J4NlCEKFHEYTgLZW8NbRQal0trW6i4F/MGBZrqCjHQD9H/Z7ISmqYDwke4L0ktATmp+tio+UVpljKTPCydSU+MHZOkuFI7JDPkGFQh6tsyKZJ6wLAocSLcdmsxGKVdVGiLouWkBBTJTcMyDxOJSOKlMuEfZfmTPxXjFRFJGyHc3TOUIBUjJY/L54SSMp9P6Mfj9UZM07FVKqvruSLjjQ2ooKUWYaaBFXvNcFLZJZrDB5A3DoHXv14DioUZC58xDjXgh2kY3v7i7raCXKzMadZOSUx+BBttUSJoNGK2SUzQzbTJi2G0wn55i3Jygy9As5e5m2OJ2U8Foas2yC+MvKWYqMtow1FWosd4yk9Nikq8r4rC0VN7s9v6PTQG85LEgp4WZ3w6ShViYJzqSGzqpEPuFAXSqoSqW0vUmiOQ7eHpmDPzMqIEEtiVgD4KHSlYSYkkfb0OwwlQm1Nca4nAFNVc1TGZV4EloxT5mHSa1I5thsSLA8HPYygcRISolOZRUwnWZhKeH+Sy/jB/FIARyWhp3u05QzzBtaW/id4IBaaGzdHCOCxE9aMhy6TAgdIDmBCp4sp9jhceFdmItatkpEhmpJUJgheDhJHBb+zvXNDb2YasfZ2Snu3r6NDODpw8f46U//Hr/59buwKeFv/ou/xk/+9EdIljV4dcKy7LE/dNQmrk9z1N5Re0dpDZupkDuyYzLdU8J0cglYQW8NZ2dneOO1N/HzX/wCqSQYyCNLE2NncrWDDdgfFrx87x5u37oc542jIZeEN998HW+/+Tref/dd/N3//nf41W9+jw8++QJ//df/An/yg+8B2I/40ExSFidvzLtI80bp8WuvvY5UZhwPJyTopO5ADS8Uxq2ueT6RtCMBycMQkHu8u6ZcMSSiAZQqizIBxUi3fwakVnegLh2t7dRPbsi2ADc3ugkYB2ZKYQHuiHbKsJwxYDMIsTy0THbbMeMh5UQr72RAKbBMbfnJ2TmrqZxQQDJaNkGlgNAEbuelrkOTmgPNyGMJ7w3EQuiEweFdJmiVapnG4EkZbMVSK1wkSiZJAMxQa8cio6imBefyGWH10onmNOpoGjirZMx0UXWNVNiDNwFIoNwR3UVKW6tzs3WRAkDVvY4eZvwuR8WzXZGVMLE6WpMOeB9GSsuyoNaq6jGNzL31Dl8OR5AvxiEaZGGiFra2sVyW4eFRovLSTORGxFrRfBonMStQqUh8jv0nTPA6tLSS2mdBqg3Ugj/29d8Jsi45k2AndUH00OEx3yXWsBIAJSjrvRpsAgyYcH0MR8/AkSMo6H0jsaL81zm8LwJIHAAQgjJFwrgqWEZi5Y5oQfV2ZCMvQuWhLUrUmhAABkoa8DV9N4LC1alK6ilcHpVoKjkPpC2Lj5JTxizzMtbgGM8kRyEi9U6SZ0+eiga15XEvMRA38rZOtluYJWwvzpHMWBVDa9O5l6JyDBfdMClECv4Upc1sJRONqVI/dElpqTZpg4TbZOAWvLFQji1OM70Ox5ymMV+n96N2YGtSw4nbJvPDrAQtKx5FQhbeEtUdDjqzes6C82iYRRTIVnM9PeecM5o5CljEJe88THLHBA49JKIIqhwB+iaZoaeYjSVkVrnvvlbUDrgllDKDYzkWzEUoAzpSb0BviocVdVlIpHTFObAYI2o64U9++Cd49Y3XcXJ6gvNbt7DUBU+vb3D77h38+V/8OV546Xm88MLzQrCrrttQygnJ0XIB7so82aLuuN4f8OTpHp9+8jm2t7ewvIWXgusbzj6aSsZbb7yOj95/H4+vrmDGZ+N7ymdTbaOlvi0zfvCjH+Lk5Ext4kjgHIfDggTgzbfexnP3n8PPfvZz/Oznv8S//V//Pa6vdvjzn/wAIQOOpDHWTqy/lDPm7Qlu3bm1trOEaLSu0iIKTD2LHkTVDok4WAAhGVI7Nimw8bkjPOmhRgxhLPhngJD8Q/tsjmeIoAvAaYzGPpa8QcCMj/8s+o3OAX1Q1TtQXd7EuOXjrDCe0K4gkaS3Z8VjKEY1B8dD59G/TUhj4q+704wLBpsYiGFrphk229N2wknA5zljM80MDjr8LeSp7qNK2O0PdDVV7zzOJo/M2ElGsu6aVFzFBVhwkNFZ645D69gdDrheOso0wQFyA5SQjLaPsyoyJ3fA0Ic6CcnQKjd07x3WO2ozLAuDR+1NpEcbz4RVZdNBwAfSevhVROKiAYcIJOLI4joJ7hUJ0PvKeYE2ayQ8QQru7QAeskBFfDclYUkqG+2p7m20f47XBzkCa9Ue1TFkw98Ew5taV8kC4aAknNdtrKJHQsNPIJK1JjbRBhDuM3gv4ztlwfoOWMlMlAv5CAH3Ux5M5CzWRyTwERRHkDtePwpaBgx7fQ4ypKPlUVGMkbhoRggAxPjylMIvwvWtkkhyyoD1fUZypImtvVWg06un9Y56tGlNSEgMiIT2BnM8JUsRLBOhageYJI97GF4iwfGBPEgoVw0JvMFHBZoyp43H3gWAlCn7HPcPPsiwOWdMxnYklPDO84xUNthuTpSA5+E0C4ihMYorDmiMmUxd3J1IEkdrKjwrFPPi2dfeR8zYiay5LAtudoHiGrAsRCrBFpiBXCB44wRkpwdJSUR7aAvQhlU+txsTquaAlwxPJFfWzufQnQlI9Y4bONwycp6wyRNKptrvpBi2maTwrWXAFsyToZycSJ2XpfggytSkHtu1jpdefhkNCbvm6E5H21vPv4y3Myc2T06UNEWxBYd3ju7oraE3KuYGH9BJSCWiM+HOvbt4/Z03YWYo84TujhMj3+v2xV3cuXsLjx4/1uA9KsY4uXrBzaFi6RWXlxd457vfpRRZyTmduNXezhndHKeXF/gXf/2XuH3vefzqF38Pmu9luMZSABJtBJeIzHpUAC88dx+3bl3isNSRuAEip+oMpK29Yp/zfxsMDY2fFeqxKMAAeXdG662r0FNLMNiw3P7/pNe3OiFxMGN3ZzXAc80HCWwEdMOA3mMwU2TmkQCMqhCmgUrK7hVZCbvGY6RKhBAWYN6AxofGRKBR2rZ0gG3vcRjSmyHrfdeKkrNIgNZIXAXWh8j+c8yWAIB14mOXdXjOE9EPXb8l9bHLxLaNqvRoQ7SUaHBWtphLwTxlTIkzf8gPIaTY4Nj1jtqhuRc8enkvuiBiQpJmzs3ROWAsOWf1sOojOtR7lxus+Da5oDaN7jYOxmuB3BwOcM3sySkBrUtJI3QIMR68Y6kiULoO9JRAWwxDlVEc7yVYNWYiZgGZ97ooeeX9Dliyu8FkYd20XmCGpS3cgM50ZKiHjAfv4LSoZRUmY1FRJ61VgRVcy06k7dhTIyqNlEQQ6x3dAgXRfBYlPkx2I9Gg+gCqzHsHkqTPsaZslKfP8pKggx4wzPM8EpaY4FwyXTljzovpuUaihHGvB7Q2Ev9xOuujXV+WCM7aYkoWlXwETVXmanPFNGAplnXPlFC4OD4pChElsL0+852PVQNBiuw9pP7qgSvhWtzpgKskDpEOeyQrqydDRImuJLnbYFYMqwGDaQ5I+IlE8qdkXlF8rJ++ekDQ24EIUZkmPi8wOeFU17y2svQcSimYS0EkrxzYlrHZbmAATk9OkU4z7t1b29sA2PZMpjkzuudqP5RkIyEFmPD12mQj3zULiInUosTxUKu4Pm0MSKy1Ybffw2od7bVkXa6WHb449t6wbxU3feE6qcsgcwZtvvcOzwV7GCoMSyqoqWCB4eBEelLSXC7xyDbu2E4FxYA5dVhvOJkytjJBnNOMi/PtmswaELOiqhP5ei5lNIBjO+T2a2Y4LRmX9+8KiWIEysb37YpXrqGKy36v84Eq0OEODPGPRDDdnG7xoz/7U7z93bfHoFgv01Cy5VZBWIPoZCmZ40hKwZOHj3RCGKwbUhGJvxQAlfu4NcYgyX0tZZRcUJeKcCcfLXTtZ0tRNNC8LSeZT3ri0EPwv/8pr291QvK//E//GvN2g1IyTk5mnGwKTk9mXFycY7vZyiJCLOHOdsUkgk0qBblMklDRkXRQOzODsgOYzIYGvPc+gn8UkgymfQR4qTeBkF/1SGjIDzBF5O5RzSnoeiQMIZlSlALfPzgcBNziwzH6tN0XETDBGS2RbSnj6o0k3wDaQnIYEH3OSX34Lgkq1GNWYpPYz8/ThCB85tEG48dQtSL1UqIfy9npxLk8aT3sXMHaAXgq7Ft7hxvNtWLaK8nCHXW/Z3UhVYc5sCw7VmsAp7462y6LYPHuJCa7k+gY7PyQibZaaYutuT2YCRF7wL6Ntua9OQ8nrFWlxxJxyI+mI6kCpR25SxoNVa9dhEqug1LKcFyMINe9jcCeLKtF0eAd6/gDY9Bw60O5AWBwN/yA0d5J2YF9vJ+SgmXtN7szMQ6+zvpaD7Lmna0NYG3PgAEtCMmAPbP+ATklK8mA0VVWlzWk6DxvgwgstYfuAQ93G4d77MuU2UptvSImeidLw16fLRWwqgSLlAQhmhSAYx3Opm+rPWPmUI0xkDeoekx67+jscM+EDwcXv+t3mZMJhbW1CIiCQBnXQDgjO1O9gnAeRvB+7Gj8QWtKdnkPO4BlIXGXOiAfM1HC2JHfUwgYZMynrxZGWN0Al20Cjp61q5AxkAuUcuIMHSGEUyFHa55nxgfdnJjFxGqf84ZKLhpUOqHMBWlL9CfMLDn8MwiQ4FgI8YQ2mTOeyIlqo8XV5U/TWkU1YHFggWGHTH8bm3BTK673e1wfDqgLRz14ZSzxtiAfFhoU9o6iSe2H5YYHcF3oQuwk8Vc5eS+9sX1bstRrhVPDLWHfiNBOE4u84M4F+stWfqBrnV4dtaIYvaliYGiBHGezlGI5o8KFLi2YT7YM12ZI8wZBECYB15Fdo0w6x148vbrGk0dPAEiej4QkdaVDcd7IRapaS91Ico4kFp3Xf356gnme+azteM1obarSM7VZzfDMjKR/7PWtTkh+86tfa+Gvm/p8U/Cv/uV/jXzp8ERSTj0s+OLTz7C/uUFJhqU2pFywb8CDbx6jdSBPp5i3JzBk3H3uLu7ev4t93WMG8KMf/gDmDVWzL+BYvU1MkiuQ+NabDIuiClRbx+XYl6cJgGYF4MgozF2yNRFVo8oLCMeCVKr/3aUPhyOsukd8SxqKBTBBABd6Lppm2yOzje9AoiQljzLLYlgjItIbYI0Q7vVREazKl7FVrRYeAUNeC206721wJ6IKspRQ5pm9ZQeagnaZilQnzgQJ9LowybAZBDdIxmsmp4NeFkhJ9xXwMOESirG6CkbriclIqxWIacTehxuk6z26O2rndOYuRKa7YdnvUXXIGwA/HHjYJEGuvQ04lJU32xIOw9KJgBhM5Ec+6947+tJQMujY2TustvXwQ9BJeQTFgRHVjAprpJYGEmE4QgX1lykl9IFCrAiaYz2oaAu/15JSsns0o2UsAsNIYuO1LlORpPU7sVYAjJky8cuOFYHq7iPhCe+PlDKmROJhUbXPQ4/pSE5UcQDRFjMgmSgRSUkmUadnZsOYjXYcCwIPugrgIr+brlsXGfdSae5RouPjnsRUYMTBEIhFOiK5juLClEjplVz9/Ui0Ivk5Di761cy9lg3InsYGHdVwypLh62BX9hPk7/i/DF+9mXQlXHI0EutuWJY1aXI/mhcUE5+PkjkWS8GnSwPFMhGc43tQ3SPzukAQLebmJEwlMZHRMMWUWPlZJD8pI03kBPWUYdPEBCl3XMwTLrdbkmFFdI7p75MlTOacXdU7TGiFwQEVKxgFn+PQKuNAazhwsWBpFYsTLayt41B9EMx7VwyQGWKvFVBMqAsntrfuqIcD/EA7imnKAx0BgDxP5PGlhA6Sjg+dh320vGBCVs34vt6ROzkrCYD1jqnQQBO9qR2McZYl3UPAyKvKCUtv6Dkj5Sk2Jfdo77h68hSnpye4desS01SASNnNUPsCpARit+Qiki73z4DUmguJTqF17h148nSPh49vcOvObTQzXN1c4+nDr/HgwVc47PY4HBbc3Ow5Fn4zY79fsNvt4ZjhKLh96z5e/+73MJ2c4mx7G59+8B4+//Ir/OCdd7AcbhCEywwe8nMpHIZWGw6HBfNMP46mAX61VrZNRGyDAfv9AZ75s3qgJ0MpZUgxzRQIOlgpeRDSDELmRkwqOSOsmbuq265gw0M/2PdanR7VUWS3PhIcwEXCWxcPLfF9xMPjitVH4oFx+PmQSUa4dhya+srWxyHrAKw1yoZTuK0KWbGsHi4r75C2OiBPhQ5rq09EN2h6c6EyCdxsVZA3nBVslpkQ5cms0DbzjM20YZBSZVoyAx0rTxuSuFRoVV+VTJIErc1NWAUW6o5Wn2lV1Uqy4n4vIi7SaMEcapUrMLk7vTEpSkKARsXaWW05iOSQ/MhWiatPvyzq/yP8YOJ5UJnUNSywaDrqMUE15mPwJX6Lc7Is1xV4sJgGw1kgRMDBqw7l6F/TJTQr8Dk4OToCYOuq+oNvcbRu4SG9jucHHvApYe+rdHqd09PHfgjECYDe+1mkir9TELyj1juSKvTuTb+b5DK5HtfcIz5aXpEQtdrEF9M+kS1A71Sh8FrFUzKhVdFyi6REyVb8N9e5AVKqsCVq4z5CKAL6mlBaXm2/x3YMeS2oeAJA91KPxEM72hkbhmIW0SbqQ4ZqxpYjYwKYlDlVi3AmX1pJSkZcZNMVDbBov4HKFYMPMjK5bJQ2r0kdbQvgKx8llHQQ0sZWJVWKMJMEVWRNWydd9zH0UesTgfK5kiAm7pweXUZcSzDx0jLyLJmzO/pUMG9mpFRwUnhox3Mo8kwKMn/45bgoA0kJZnImJ62us8f4bNgeqY0k3/3hACSSjJuKodYdS23ymOL7zNOE3c01DrudbBE406bkItK0YyoTOVApkmwIBaZKNc8TDhqxUVsn/SDTnyv2Rcyf2u+XESvooQN08D1YdDP2rmMi/vjrW52QJHfNCwEQqo1e8e/+4/+O//TzguYLlmXPINwgR9MZKWWcnJ6imQO5YXu6Qclb1J7xnbfewv37t3F56wJLP+D5F57Hf/w//ndcnp7h9ZdegKGjJCc5cxHkZ8zgT2c6b7o7WqqovcMmPox5JpfDe0fezkPR08916Cs4xt+T68G2Ty5ZD4oQda2NfAltvv1hQe1OiLFRLREHhtvKV4khx8VEIK3iNQhStm6cWdEaA5xlLARzhBYYkCZB5E5CUwLMRBIOM6uwIocOCB0+QPglaCcgAij//ZQUMFTlHisbojjtOmApeRWbnreGHikaWz94O40/NBjQKM1d3NE0vOs6AkkUqt3hTiMk9448bdZgowPBjYTKUFd0kVDnXGAwTKXgbHuCaVNg2+1AtbJg6dDo10YJuScbiQ/vmdaAgmfrHehV6A5Rpyo4eVkOMGMistQ2KtDm7GnXyqQvlazDW2qPA034SpaSoFXUekBKXF8BgjQlR61HS4mTTHPmd6DjJfG0rmSM65QoEQ3XaKnk8gFpOlxDDdFBNCYOSgeAEmgK1lYPF5DaWS6ukJKOSB0cVJICgzzLYLiiAqYxDtHXx2JCgaBWk9AMB1GLSAhj7Y09msUzI3IWbQpeZqURoYwDSSNIKEKL4oAlwkXFS8oFRCU7ttuNkkkHVBEPjg9WlCWSLW9McoY8Xt+9trVVNa7N+1iH/P2+FhRH67yDxVc3KUPy2oYbCUOgHFKj8W74aKNBSEoD1YahPkKCErce+SYTFMXCSNZy0qiP+Gexh+S/kRLQNQE8PtA6je8ATnD24DEcRZzuRom8Kbm19VoYLtMzSFRTG9hSZszhWQsoDuREBIj290coo36ODv2eYS5sXSUh2TDul0BBc2ZbN8vWYLPdojtQtCdNw2DD6iVaI+gdl2cnQu95vxkLXa2nBiCN1hzUgjYDYvQHHNiqZd4NGvpIH5MEeg4l7fsnV1d4cqX1p3uYcsbti0ukTMK2Bf/pH6B6/7nXtzohIas5DIsI71nKsAJcH3Yw4wKa1HuGJXSc4fmXX8SP/vRH2J4lfPn5p/hPf/d/YH+zAzChFMecgOvHD7FfbvD44Tf48P0P8NPLX+A7L7/ESqOTo0GfAK7M6g1el7WyAIYPAsQ071rtJWXZvHdlq5mGSdkR/V4gxlFrYqagUUsy50ER4pJwst1SEth5cOdJ6YuZiFNMdqp6rgOy7Y7Z1/HvZoarp9e4ubnGyek5NidMPrqg9qqADChoc++hLQua7OH5Cr4KNPeCPXUXvN76GsgQVXC8s/PeRv99VEsIYJD30FQGRxwKTxPab/N3cLRR+JXb4JK0IKmlSIkwKnFTe81BAqkpoMfcBqjCQnc4xMgHcKPgcOPAk0cPESZXSdVsHKpJSUYfASwBxkC3cjPWZ8KNbuOAm3RY52Qomw0r6A3U+qJ6pevedxeCpBsVXI+MVQbNSlXxSIoLHswrYbE5j/Wl6rpz4rDCI1Qj2jpVUvV62JOzBfIfiOzx8KOCoePQqAqorZE07WyJ+dHndymx6rKIVe3wqgk/PQi4kbwxsDb1PJtLUaSkho/ZtX74mUp19ZyhpCPUT7bKuockR+hMWt0tzQwWS4+/DJiJ7MzvwrZKOkrO6yCftkq5Z3Bj9vsd0RetgwS1scZcLH3nIyQHsY8RiVdS0pLXQ98YBy3r+WNVowE2zuCcErq8JFwKukBpuDbTQFPMQMa7Bd8toBbD4MIAUDPkaG0nQfp6Xz2rZEoqWSGsiJH2zbgGxPpkmzZECVCcYT7pismh1NI2N7ZUItnl1/eR0Eci+0xcMJ7YOdmQx0KJCHRdg3OSec97IM9IAw06mI3knF/EZd7mSu4bEdyJBc5Q1QktjOeVUlL84v0olkbRUQZnD+N+xaDG5g1hNMnn4CPHZDHBf5cSYE7y7oR1rMiKxHG9JCFZgQo9fPQQZycnmE5P+Xy6ISxS/tjrW52QhFyUJi9B6CH0lkSq8QgyngBk3L1/H9//4ffxnbdex3ab8Ny92/js84/xu1+/hwzHb/7+Z/j688+wOdniZn+Drx8+wu76gF/87Df4yx//GK+9+gKaKklLGRVVGnWt2yGJZaDijBlZs48sn8usS1oY7rKAFqakrXDKzLoMz1IuSEoowinPnRB8VwCkDK6r5cCAxmDsmGU9HdewtmFW6ebtacJmnrDdnqJMMzdVyhpMBnjtUuGwErm5uYZtJ1Z7mqUzbzZApwFTXSqmaWZLpsUQMjmHesduv4e3jilnHA4LpokJUl32hA2XymcbmwvgwDsRTtlWsCiO4Vh7y6bDL0imIVUe/MJOngxbHqqzzdQp47ohApRHoHZfuTFwEZPt2eeKdTXws4HRljL96UoOurwiXIZ4rdtoVwRE7QhlFtbAPSpxfscEDHIr2xH6XQUtU3vJO1t5KZCHlLGZNIWaN0WkVBvk26jgUs44yxsOLyxhHmgDlub1KIEUVF8AqSH6GAKZegRqThRlu84HYlKdh1qVPLK1hlwKdjc36LUxuVnYmz/s9qM96e5Y2kIDrtaxrweEPPy4nWWamutOVZjOIiRjJQlz1NrHGonDnZPduybr+lCqBJIykoTojSISBBwdpqr6+9ru9Pi9lBCGhAYS0XnmKWmJeVMR1yC7/NqOJMtM+njYiihqeSCG8V6BF3BMg61LFpEAMSEP4rrpnppY+8EROywLJhHduT/okh0GhVkCgSh6aLsvMmtmQhdjLSIgRTECW6cXuxKnjiB5x6HP79CkQjpOmuJ6irhkjpULFHEvwKFknN2EI47bKOqFhChlG/dOGceIqdJsjYGNXR47o+QxxseeEzwJLY5oIkQoUBcYxqwtFlbiXAEcNhmXppgLAHvnMFEzQx5tQR/3KtR+bCUVrQVH6xUJRHZ7Z9wppaAbW4ZhT0cX7KzWUlwmi54Q9TtARBbA2ekJ0fZES4x/yutbnZBU9Xx5mhjnG5gDIkEHOWjcQADP33sOL7/4Epal4uHDJ7i5uULJZ+gdmIphOdzgs/c/4gFXyHzeWMLjpw/xq1/+Bm+8+hrM9nKe6yPh8VHtMkiM/i4wZGaURUmdcnSIMmAxWHWvI5uG5SHrjUVqeu/4zKjOMrhZSykcZd76kDAOIaIF8Y+mN1ExRmYe5L/TsxMmQ/UAwJAmR+oKUbXCUx4LejNvNMejjxHrJRdO60yGPvXx2bWyisllGtXD2TQhPB/2+z2yHDqjF28GTNNER81K7gQHXJEzFEOvOCm2r8oNWU13Qa3tIHM1RdeAZ4M/UNUmylNB2LIT2qaZlgmuNAA6mUYAD9lnJBCB2gSfpssS32FwDWFLOaYFQ883nhGDahjPxRwmBJTeGzqYIABxWKWBPMBMZFqs7SFV7j0+ygg0JFWHda/K0MHgJFicH+0M0sAgJAeE7oGquIOsKsc0TVRNgFV2VpI8abx1zml4p+Q8SbYPpDLBRc6k1bzBNgl2HvuEEnd3DttDo6dNQkIbSE1Hc86R6c7EpgqZXHrYapPftSw0a6uabVWXiroc5NeS4Kr2lh1JyxHIY0xB7wz2rZFYvYRnhwLNSGC7o7YD90VhFVxrG9yMlVjq6J1+FzApoCBEKVAIqL2i6wlp+WgN5Kim15jC+FC1xzHIvnx2WpMe3BgdYi5uHjA4M3GwhXonEmF3chCyEq5x7KQKJCDVNAo2PnX+XrwvOi3SgEAqdKz5uq47XB48q5opfHzc2Mad5+koqQnllB3dK1+nwXsbz2cgkGT4r4kT1kLNjGMQeusa1bHykaAkL/huTCQOXPfJ4NCgR5H0Y6ggEIRvJlhxnST2Zr1f7C0pz4QOBoLBsNDGdfD3K+Oi+0BEIuEZiGjECMNwvnaQ20jOTOb+ANdiIFxujtbY3iY93/T5qtyO/EnK6eloez1Lgv/HX9/qhASROUMQnGC2GAufBBu6JKXuwId/eBeWO04vzvH06gmePH6Cr774EpsykYPSHJuTLZ67fw+vvfoCLk83eO/99/HZZw/w3u9+h3e/8wa+986rgFWhE6yJulQqIfmL4XDmQNdobVPl2QEgJ1UIRFNoF91oqqZeCJERW6WXIPEIkVlrA4dU1d1Rl4ZWuYi9q7etIBQOpiVlQeg84MLXYEC3xQRpHiV1AID1WrqLNW6ApePpqSR95ZRlmdzGgs+ae5FUXSJl7GW17dalFmiwTm5DEHQXzScZhmLqvTIRSUg2AUNpknTokrsQMtN6WMaQwa4FsyzLSq5UWOzehzFUb1EbMAEINVcCK+t5SKCVKHjn4DNnW4pTWTFIYKHcgVEFE7N/IkC11lBMhDvEfE4VYoiWT6gFuI7inuqJIx0lSvC17bHW4lwEpioxFAERM+h3sB6CSfB0F+KhkT68lkBhRjLW0RdHX0bdLz8RXkzwDwIpjEONyBGG5wI5MBoGqSFgWchAPNeS8kioORaAn2lJiVvj52cwKeKQTCmHXMiYkcyYpM5JHq7K4PNsJClHAuyx5hrn4rRo/7WOQBvCVyMUczGpuknBgU73zbB5b61p1MR6cNbK6rrkpPZXQ8izg3eBhBUlBZPD1oLDRWSOh0+Y33Ed96okBgqa2tn7/R7Bd4g2I4stHlxBxKR8Op4f11UpHVV7B4aBaEVlz/vZx/4lSiCUojchlrzOpnlfISMthYdzr9z/R/Cm1gP/97IPtWO0g00xn2tuJEVSFg4ysCq73jumslGStaKjAw8ZB7zUP+NzHDnPR3GS36HktS3m40BeW3il0NsDJm6Zkp8kxWF45wSp20CEIpuNoYhs7WpkRe8qRkQoTqtJnyESSLZCTc82yLDuMWuvH8UCA7KK6h6IEknAUIxtQ4nmMFvb+SkVlKkwZgnBcfzTejbf6oQkelc5qeqIKhIYMBJJUvx9S4armyf4xU//E5JJ2qTDfWJHB6cnZ/iLv/xr/NmPf4iX7t9GKR1ff/0j/OxnP8d//N9+iv/hf/i/4/q/+m/wp3/6fWw2W7S2G1wOLmwFiT66mBhkNAVnIxSC7m19oB3IVnB6yhHTdansYLrDm/gXvQ2In5AoVA3EF4Q+gwut5ISSj2ZchKJBBzAAuJQe7PP3cc15ygNuHMV3CgtpbUY50OZcaK8fPB5LlMTVOkhTCYaeCJcD0KGgv9cHxNj6EpvQibY4OFo+wAQIRTAYkFf4ufWj2S/OQ8mUlOTtTIkvGFzawpkn06RBcxa6fKpccikijgXSpMPcyT9YcsLZ2RlK4u8sh73kwW1Uit3ZzkAuOOjzeouDglM+Q5uQS0GrQD/QNfdke4KcM5bDYXBg6rIQWUnG8eW9Y+8rswbjvqliDiKj1BrF6CFBwrRuk/tq9gSpGuImK8lz8PCznCRFh5KdI1JlBxjBV6SHSTGEcJjWc1TvRv8fM4TQPHWidA5HSWmMTwiORVWleIhH3CNxykcKGoyKkAezvkOKEQB5SHxZrfOwL0Kjog2QdEAmX/eMviFi6iu3vWzUZcbYdZBA7ZjW+5CwAmzxRWIWHjitrvyr3pp8dfpIiokCsqWn2hruPsYqhHS6tyYiLEY/v/dG1Kiycs7Jh+quH1X7DnJ/6A1SiKyBZOacjFOjhdZFmzOSBmu8rvjM1h2p+igejgcaxnXmlJXkKy7+g4OfOWzH0lap+JhVMwocoSaKI5GQ9C7VkoV7KJ/dcCiNwiLajGpFLWHQqHgSe1MLeKxN41nNnzvg6YC1WRt7x/SfLNJifpo791KZWBwFggH00a7p3UZBFsVDcqjNaqONNjy2dAYkmT1aMixyfaVXzDrHjaNQGhN6nU1s6ysB1Pyj8JTqSrYZS5wD/FpVomKrQk2Vhbtj0iTuwV2x9Vv+sde3OiGBILtmHNoErIGW1SQRj6wo1XrHnIDtPGO/36NZI50Bhl3teP2lF/H8vfv46qMP4G9/BxvcRmsVd25d4F/+13+Dy4tz/I//4/+M/+n/9T/h888/xX/33/632GxDERPCJuE0groMsio3AD0Y2XmQsGKfEh5LuN7fKPsGxkyU8V0F8xPEZMbrEaIwECHVioQJhY6EdXrIPlnwBBwY2TH/fWTpgf4o3q2ESsGz2j8wGOY8iajp4DA7MsUr6mrc5KG2sRHAoYo4RocHKuKtYp4K5pywXw4wdJKjRCZsjTI2M8O+VgRvAhYcF0i6SaUB++gMSCUlWCnjME46hF0HRHeH1cDeGF6CrhuYyfZkyyAeyIBhtOXmKY9nUkpG94RN2Yj41Y9UHLRBLznj9PQc3YHPv/gSt29d4s7t26MiJ+N+hsOx3++xqNdNqSkTv7osqL1hv99jM82YLeOw36MtC1KaRaRdUBf5EyRO1gWAMm9GO6JWVqhBNFTOC4CGTVFRKveFjf6y8JeA01NUoVGR+5D2RgI1EmlES4g/ykqSVwg/kFCFbs2WUqmHjg5P/HkLdEdVpw0+lg5F94EUOkB5dje0LsLeIq6FPtX66ldCRdUK9wPc+ylloh+IRsdahJB07yNJCgTmmftoCV1IBA9aw5Sm4cIKX6nuwe3h8LM6SK1ct03XbkOl4sAgtgfPhigMh3wetG7MEmdiKalZlkpPCegZuiKLkVwciVDROALOYJHCJMezJT+FRm5sKcGZ7AeHyHRARysBRvJ8tCX6SMJAbxAlz6zKg2j7bFuIMmuXtB3oSyREPuKM+1HbKNaj6/PErQjOWZBZDasp5tJjkB2vwXtfHb4dEKZE5DwIwtlGO7gtMqlz10wmG+R4WELtKteSeG+OwcNwVER0CkkxwLWLzPsRbbE+UOCktULZcRg7wuVtFdwi3d/WyVeacgbEKVlVWmxf51wo5Mh87sFlyfOGKWur6EaTuH9iPvLtTkg4VTKUC+zP8oECGWwDxCFkevhT2eKd730f5xcX+ObJ1/jwww/xzTcPkQy4enyF7/31f4Vl9xBffvYxXn7uFrYnE6HxMuGv/vJfYLuZ8W//1/+AP/zht/irv/hzXJ6/gEPdg1mkDnCjW14YcYUccHA24oTHmhTof4gVr1k1qkQ5GE9fDIBJ801gQXNydPjGvzdJH+FqN3hA8Ak5SV7ZQeQlLidaO+DhOgx6nBn4Yb9DqzQno0Z1ZC1jowaTvS7rfIVsEl6q19rRBjRc5OrJYoNkQTd6XziA6/3NM74oEdzNj3qzIBQ64GynoyV69LUdTTC1GSW7q6wvKpnxCES+ZNI3z7OGwDGJC2mbGVUSvKcrqROwte8OHjbhUhvvU9SKyA70lJDAydCHw4Kz01NcXF5g0bA1ep9wYKI7kKxgho9KywyY5w0wb4bXigFotWE5bDDniSPXk2GpB9TGidi9Ow51waEF4x5wyagZNIUg1IalHlAkIYwpomY0hnPdtCZUMIknxUrXjpABcVi61lfA5utxs6511FVC6ZDqxyTXXaFxVobyYRkrY/Xz4O8EgrOaw61cH3nPQAdiJDHjmvpAesbBbBjJVlx0HDKRvvJ7AmNSqlAhVqe+vqfHn2rZqEjoERtubhA+DgDGoR0HpCvBD4mpos9Ybx43Qi/RzzgxeXOi1gJdRvmr3AglHRkrOhFX097gOAOXTJRrZcy10ufURl+d2htqVcGkxLS1ioXuavyu3Y8I+l1Jeh8oCI0IOTsmFDlItvolOTkeKRBMEaW690FMjjhGVRZJtwBGy80dQ/Mdbeco6Oimrc9J0bbBaMUxjgmlajGwleuOP0uoQhTgRG2sO7JBHCGhDh1MWFoDEo0h3Rwmu4pg54RFvEEFjTf0TnSZaiLAjO/fWxuP3+DobRn8sOYs1F0bP+teIxmnj3fN7ZGysjWNvcixvzu8UYQwpYSL87NR5G7LDLhUnUoq61EM/8de3+qEJKOvWmyskF2GfBB6ZQAFEItkXxs++vwrvLI5xff+5Id46+138LP/9Hf49W/fxaNHj/Grv38X//1//39DyY5sTTwARz0scAO+9/3v4f7953D1+Aq3b19gt9uhaaZBVPpEN1QVQQeWrVDuGsxM/eIgwwURKoKYYUAVMISbXmwc9mQLYuCcO7GTcGVkgiR+QaLLocFEDtTbwmDqowfGwzkuaUzUjHrRlPD0qsFo+h4poNPA5wEwQVOSJIXFlA3VGlyttEBOwjOHJMt1Ui6JhyKA6h723lHbQk4GgCHLDO8OS+SiOJOqRcHRUlTYAe66EtkVBYGvhLFQj4zWQzyxkAQ6CZHzPFNvD4Mn1wESaExUxrwHvbUh3Y1gkDVgzrxjLjM2J1upOGKmEANl06ykQBt4i0XqPNBZ1hLQrI4+PAmmM5becdgvFEcquam1AomHT4cCreDwzWa7npVzR2/TIFhOJRQ8wOGwRZB56zF1xQnr9nWRkehqafAxAhUJpK1HkNZ3jTXMJIyttHARDeDE1XLtCHTKdK+iBXhkytRVJavijBZAAdtUsV7M1qTanQk7eQ99fG93tjcHpG5QYsO1gyB3HsH/0H2K/DdWVbSdoWvyI4QF0VrTP1iT3qO/hCMcgePem8uXIpI+/Xc1qUdgcOwGJNX3PiD2rucxOB9jRwchU0eumaD948LKhvqwwDBNM3yjIqz3oQBZOUqKlUregD4KRxdPhnhGi5RQNvdQwlG1jtgmCpZ1qBID3YqXu9pKbRlt4t7JGeM8LYgYn9dpuakIPazkZ8mZm/fdYWhCfhRf0irDXuDr8MPWOe9M+8iF1DBWYCCJJNI7LNW1va3/L8RHwWUBQIVU6+jW13ULIc2KV7lkehSlBJcZlZlh6VKK+dH8pBETjR+aV2PM4DY6VsO3eObbeUYQjeme7ejLonEAHbvDOrbiH3t9qxOSMhXAOazNQbJh8iOzmRQQJRBGMg0N3zz6Gv1Dx+7qEX70wz/B3/wXf4OlNrz37sf4ze//gI8++BTvvP06ar0aED3JcHyYl7cucXl5icUPhNaiCoMNg6IisqP5qr4ngZVBjG6cdO+M/mPK6zAlBzDlqIZU+1hYkEe/fO3Prs6ZmYRnEf2OuQKHfRWJktNCo0UCRG+dUTi5I1uGp44W1Zh63QCrrDJlojAdyEiC+qKy4OIOKfOoEFNCLpzsORIrrJVQF/8kkJSAgIec1Q2tdlRJyZBITAwpbR6VcxIjfPXMCAVUk/qIVRToUSOZZRyGODK4AiCnSvb2R8A8yviXpQ2WfT4yGis5ZKEkLmaIi+CdQ8dG4qGqE8D+Zo+OUARIZaODHKZkarRDhDbAYSmPAJeMCqhc8uAftDFVGStR0gqSFQBHZElGZcK4WjchdbWUcDg0chl0XxlM7Shx035wKWycz6/ME2Lceutd909tBD3/lJIcJjESl/B1SOHd4wHvRxIJrSMMkz8GTxsJfaiz4vsMMmOsu+6MIeOQA5hgK+j3QB3WIiGgfCbEGCmuAZikSnKn7LOLI+EIdCWQk5XfNqz54zspbUaP1E3IkB+nx3iWC8SbMZKTSNzqmAKsg6qLN+RjG4qfpv0vM7LeOsa0YiU2rvlABpCML8RoEH+NJSEA8Y3ogNtErl8BGwPkGuuhOotizSNB0edI/efxF0IVpjzxeRtQhyrPYN107UmOunFf+f2ogInP4/5IKaF6JECKsyK4j1Ag7k9rdeSe3mQGqLjQEbN2NG+ns/2VJ2C335ND5p0mlO6AV8Q3Dc5Xa4fx7CxnrsnOYpVTxlflJITYZKn44uwIYm7KCVj2Y9/A0up87Swai/iPKeVxL2LKdG7pKLnJSIVjVzidnPfE3HE47DFNkxL4CQ4JPgxw6zgsz5j0/Gdf3+qEJKD88IYgwQejMuBLrRKPTNKRYWiHPT7/7BPM2fBnP/kz/MWf/Rm++OgLLPsdPvn9B/jRd99GPcpEYZzU2FX9DaJUyEUl14oFzQqTf7ZalUSsZkIBC+RgYoMi0QRNdO0drcrjwQxmPIjjWvjZGF4crXXJhbsOudWcJ14OjMx/bbEAnjidd4XDgaVVRJg11zwax2g7VJPfSIA2+tZ0LV2tnd19QPxu2nQ95Lkr4A5bh5G1I+8HwpK6n8mQ5oxJEzWDMd5cDgBWUDKnldZaUcG+bioMTAYiNKEsgTFxBDASjQh8x7r9AfG7WmdG3kLOnBwaJDBWOyQeN2+EkbsUB4my1eVwQPAAoiZprcL1dymVwS9JlpGQ5MUi7wd99vDGUAIXrbp44NHXj3VaJlpCx3RWS0EEVZCtDQ4SAhtkpx5VvUixaCsSp3NhVN9a7oh5LEGqzWLBem1oEFromT5axiKiKzDSsoLEWctSoGANrjlQxiCRuhJWHfh5mhGHblxPSgafprG2g2weyWAc4qepDEVDEHlrXYaaiOu4Dnlv+GxU2X6HP0goVWqtWBaMRABmJE22rueSxv5gcF95KkR+qirrxrZmEDKBIwWPD4Iu/SK4PlogDo37ykMOqyTHdVJY9Flij7rLcZQ/D7jdIBSyr4UESbd8Lt3ZZu0jUVNcZKYDOI34muZZJf091V/k3dBN2yjv1T5jCHcgGbpXtZTTQJ6aL4g5SZYNrbqoQnpfM9T9QfeLqpzeWVREbBmEYFatCDUT/aDIhwq+TxzUNk+BT/DR9jVBC6sCsyPJ9FEStirWMArL1lxTzrsQqqQ5OlBxEzYH5OwcDnuioa3Ribx3xETvSGxaZwGLlJASE6uYK1O7y8yNPBzXxMX9fo/aK6Z5g+YJuSfNYOOznbYbFnvO4X3uca8Kem9YFjntPmOSmQE0WJxdf+T1rU5IWgd6N2ynE6SccXV9RWmtA/CG1BNKmXBx+w6urp5inmfkZNjv97g4P0HtDZ989hleeullvHj/Du7cPsfnn3+Njz//EouydxjEindGSRgnIAah1AlhNckMI3jWWgfEGos8SXIWFeeQ9yI4AV29WRPCIZ8N+EBUyJQua6HhQAtGe5Zss4k7U9dqMEzkmDSoLyh+RRwo7PkrAOu3GWAnAGDbw0l+XG72WDrhwNFDBaS00cHeVxQm5aTvsiYp/J5K+dK68ZuCYJBTu/gbMQ2WQZZBOChdDkdbKhJHjLB/iY5cEjkUOVOOCR8SN3dXMmORx7LSSCbnxFXyScWPVDjuHMseh5UBlhNar6r2TJu0y8jJ0JZ+1IcV691YU2crgjY5f4Jx37CXwoZrR4oU49RhJB5cTXycqveO9l+Wl4sH4UzV4Ugm4CJoCsUSWz/WDYMfg0vtq6ycw8mEYgl1iIo8af1345ovUxlEYXM+mFpjvsr6GvJdJKpajhKynMnHosfE2pbtCKg7yvw1CWJVrQIl2aj8hzzaAbcsxCN4ECR5xgBIM2BKZSQjTHxNs6pCjts1DZUTVM15COWSh9oluF21y8AwKlWkIdF0AL0dmLjqGbXGBKHXeK4M6JGYdUBoCb9ftkwjLSMyVlXFR3EWs1yAUE5wAm1CYovJwy7BRJnknnRofXsoiWyQN2M2V6hteH0GTrFWzBQEZAAH2KkNE/YWISfvdG4bLYf4R+6OhGjXqmzTiR8DOA0OdBrXuZP/EFwPB9FMNyZNkDw/p+CuMYkhT8I1+67DXWgvbBQrzYFqES6ZrMf3iFgAIUYsVHpsjbWtzd4nhhOwEJ74TqnQibeAPL1J93UdxgicX14gEu9k0VpiFGsOeLdBWI+eX0xFniaqDeuyIDub8fUIvTjU/Sq88DD2TEKa82j9p5SRS4I5J7Wn5nq+QkZTXJ9Qm38OCYmDhlnf/87buHfvLv72p3+Lx1dX0dBFbYbvvPEmfvwvfoIH33yBZTkgwfHRhx9iWfbYbE5w/fgpHn3zDV59/hJn24zUD9gvnGzpHkOahMDYCiM6ROxx9qiZaHNjB8Q3hisJ3kpp7QNXSeQAzWPpTmwSqnSJ7xPCE/Grg4gIVSyxeTFkoYjDdSBEBsSUGZG9eP0hQ+OmCHiOxCcdLlpYUYk1EI5FLgBWP4USctDonco7oS8L4JSdlZLgyGheBd1ioDxRpWQjgWy0F2A4qII32KhYBpydEpLIhAHDQ/Bv1ntQ1cPZLP3QlFxgJe/q3jJAyNMjnq8iSXhlUArJ710G3BtQNoC6Bh84joid7KdW70DSPBlL6B4Os+IQGJOjWimfLoXGWMkMk0YkAA5LwKRWVWttTB5mgMpH1xUcFkPJhQoaJUwhHbRkq2xUeAFR2I6lN1SthdG6+M/8CYiZk1ZeTCoJZcqoe87UoSZQCbuG0bW++m+QdMhnEkocBrRI1iJRdv1vaB9FQikTKMOA7t11GDn/LgED4o7KmIRNJjp0D1Vl5/IuwhGiprXXpERxj2gglDYZLfbV2kziaOREE7hRjPRO40K5+DooiZ+mCMfPJngA4FWEb/dRwJgcWIG4n5UJd05jT4S753D0VX8/GZ91TgnWSUQN87PWGw5Lw15WCvRQqUMe2wNlgnPF6D4mJeYuE0OupSaZr8zDEmPF2jZYlUns5LKtoFwDTNBNCTBRnYF2+RofTK6mkbCad0iMNm6pmVBiMDEhcK6EDRikaZiNpKiHjLp3TS2m2ixm16z7INaT2rFKAoIgWxsJqJF8ZNcwR9h4VkAoBccS0D5QwqLvUOsykuR0zCaG8QyxTJRzJBZtfK/aWFDM81bX3jFtpuEzs/EtUeZEMf5Kjl6TZwT5W4he6459Bdyo8prLhKI92axz3Mp4EP/461udkHSZG730wqt4+53v4OtvvsSvfvt7kkxBeVIuG3z52VeofSHBZy54653v4sFXX+Hp46eojY503R21OnpPeOnFlyBi9XgY7j4OQNrDa+pcBD4Dx9fDR/+zV8fkxumNrYUQbPx+cCO0shBDj8wdh/0eeSoDtsxI8G5qw7APjVDkkA0KgJlxzgWtcrPGoRmkteFICHAIH6D34aFoR9+3qZpL2hRsRfA0IH+EhxwHhhWUktH6MibMppw5gVdBvI+NAwXJdpQYSN1RK+AYhCwitmnY1cNCOtfHgUbvT/XpXYHMDXBWofvO9tOAd21NDJNYQu48TIZ89agNQw7CeNzDWt07lT7mrkRFZFZnAJvkOLq0Ro+TTlUYab1EUXgvGIW+/OILfP3NI5yenOP09AxnJ1ucbDZIs7FFVMqqMHDAPVPGm4jCEIHj9zocKqKRCX1Wa13yUsNeKp7aG1qNhNoGsZSQ+HoIphS240DcREvkthjAseUAvDtq3yODjru1cx0l9NGD55+Z8l7tsJILh+apau1eWbHqxruSY4fQDnGMwmhqTK4O35G+7kMiIdxvccAPtYrGMfBnnY69Q33h45Dmc4/ZNUyIFk2edEhlFFwn3RvGFaPdvYdTZkO4AKeU2Zc38i7SM+o4H3JOGo3lIatsrgtAkplb+H2Uf3BY6RBDoEp9oIDRmvWIPW0dP2E5YbKEMm303Bl3dvsd8jRhKgWHwwKBwpjKtJLNVYmXTNJ7zkoAG4ntN7sd1oq9YVnaiDOBYKnzAB+rdzXKa50trJSNLrsQMbhJzYholbAtmVOR51FwgIL8rEKhsxDwpLaRdmMyk1Iqj4PYDcjwMWgyjcRXbXAln4Ch1QVutHfoABEa7Q+OtTC4y/Yf6wgRjD0LJfdSZXp8VhQbfI6hQOO2YAyPTKn3jmbLiK+1dZiSBjp2+4iFLD4dk/ZPbR2eqOpjktSRSsJYUAgzUBY7NH5lcUqHEwczTHJbggr8x17f6oSEZCoesLkUbDcb3Lt1G9988w0aGqazghdeuo2Hj77Gc/fu4d69u9gd9nj69ClOT07xxadfYrvZ4t7dO3j89AYPvn6ClE/xne+8hqVew33RzdeDkAxs8AZEnozqPKq6qPodREJq1+OINo8WvUuWFmV5SmlMOyWhT41UJQuDoCv7azryOR2ibSjX9DNZo6dVP76SoXRIGZBKVAgVyePQ/v+R92cxl2XZWSj6jdmstfffRJuRkV1l9Y2ryi7bhcAJFx6OAMuCIyRsiSfsB54sQLqYq4usy0UXJDCCB8QL5pUXC8lIvICQhRBwD7aPO1wHt+WqyqzKNjIiMpq/23utNecc9+EbY66dBXZVnaOje1LekOXMiL/Ze6255hzjG1+z+oSwIPHNjW60MSZAIue6Dg1qw7KwKs/ZRjwSAKH8Tw1GzSkDQr8LIrrrLNmvmcOToq6S4M/w0RcTTLlxxxgpU7Nq3TdaN/KBdVPsmnV9X7YpdnOiIN7Er7CwbeKIsC7DrODNidJRLpINKecNds0aeNgHD82CrKQxBLOIDjbGCXj8+AnOn55jHEZoK7i6OMP+6gI9I0Kb2WdTwtwUWEoFRHH99BQ5Z9h0gOQyGFE5ZSQQBp5nXutS9pinCdM0YbfbYZoXNOv4cxCcnBxju9lgLgvVB1oxDBnHx0fYjCOarrJuNuge4sgqXoWclMtyQcTKbckjY8rVSZUivevmpmU31Q6jBlMcCADRzp0BQD8K4XpcDf3WtcOf46qU96M6jqqJdZFcazZGhPTiwdfjumbENnB+jhgCWimUl3bSgykP7ACBZZqIFXO+LqNKV1rAOFpia75p6/yfaOsZuiJJbDRaX6cqasRmYeBos7+DeUz0PcpdfbWrUroKBwIEmmJBFDEfcGKcN2Dmces4mpVeteZMLAg0hnTAKzFr9sQ1kYdtL5gAxRZi/CVDAZwnJdpjLvyze3NV+3O3ed95ICKo84JSzSelNlwtewABZSq4f/9dXF1eQhJwdHSEYcyQRLJ0TAnDOBpyrCxkasM0sWDIObNojAIJwCYnmjY2hWrt48/WLAfGEG8J4SBiwZdmRYu81r5XVf4Lr6dnGEmEltqt5Z2j0poXV712hsdFGEyFLmNXPku181UKmvBnOEJP91eS6CW1XpAV5//Yft+RGpgqDhFuJCdW0AQwwiWqK65Y4JbOKfmDXx/oggRgJPbDR+/hu9Kn8Myzz+Ld+w9xdLRB1QFTnXH/wTu4e/sOlv0lLp4olqViWRa88+ZbuLo4x2c+80mcnp7gd7/8FZxd7PDi3Y/i+RduYl4uUDH1jse7PYBmVxWc6zZrE1wloPageadMu3DbSH3ThssdfZMzR9ngqIDlBBzMX4NlgaAZgbNVNKhZQRsZzrp4V22werHqGY4Eio1/DvMrjE/RK1t+BlXYZ1ptspMYiVRt9quwA8ZgVAdFFYB1ZNr4wESzrG+N8+31gV4lnZ4P4k6FzhlpDf3AOCQPqheI1kH5cwmgE/4giqgeEiZggBnsZ6DfG/tiQ7B8tu+mUrbebNThsl73jqBJGYvHZr1dM0XPsix2j/x6r4djCBFnT87w8MF7JN66jJL9Ne8HeOio80TszwL4GS4uzgGs8lgoelcrJiukfJGfcZ5nGjupmfYFgURuKJICLqZLnO8v6V0DAIEhiudnZ7h17TqOj094L43/45Jcj2EPVpy77DvH3AtkRw/88/sG55HuELFl7q6aBhU7X8V2drH7RnKx9M2+2ZiBMNUqs+f1Xw+FZkUtVA+6Uz4uVLJVQ2HY7LCQWwnhtqz6KJFkb0PVYuS4x8aBtVVE/8VmsU3jRr8Opp6ysSzXI4xvUjti5QU80R6D0r3YIGBKZURyPwo2HXy+Ktjyc4wliB39ctuAQP1/f7bgf3/Q3HKE4wm9niLM9eNSaPI+/GZ5oyErQuoolsJQL0OVIp2EvVgkZ8hUKbCxFIzcDQCGaMTInjyIIA0blFowLzNKaciJ/KvhRsaTp4/xy7/6K7gsC565fROf/MRH4E6+4zBgu93i+PQEJyenHPUuBdPVE7zx1jt4+OA9THOh+i0GXDs5xkc/+hHcuXOHXi5WDKgWLPZ1qhW1LAfLltdzmRcWcLp6PYVhwG6/7zlQAiESrw0hJaroRLDdbJANCWIT0ZBSBqqZcSr5Gu7AzWeTlz1ECgrErmEU58EoBR+tAnFELQuC+YvACvBifBk3TeDeo/36kTdIRGiuBYMk4/cJp3B/GHxIoBUhZLz+xj3ce/cxnnvuRbz22mvYTVdArbh5egOX52fYDwNuXr8BKRVPHj3CG2+9jcvLK3z8Ex/Gyx96Ae/eewe/8b/9Fk62W/ypP/5FpLFhnvecfx6QiXwOx6C3Yg+MGYUB3Xa6e07Y4e8ISa8kJXD2hzU7wzdgMRMyCTxg1o/KwykoZ7qcQyoWr3JjgpqUrFbaPQcJgAXkpRSZKtxgJjWhb84ifiD4phzft6GI+iGJXp3DNm7m5agtXBtZtLUj9bFUs87KHf8CQHhcuUEWI+/FEJAsBMsdboOaWbV1cjHYhFKN4+MIS6vQ5moeIiKelizRvFOsaXbo3b094LbndmhxnNTsa3mQp8TODz66C8GoPu4eyzm2etGg5BPUHvpga8nsmwuINLxz/z7fi0tVAXePWaF1+HvzXR30P7Ab451/tQ2HB6hZeneeTOgkuhx5EKQcjJDNTq8qK7paK2DjP9R1LHn/4QPkx0/wzO07OL5xvee4RBtvxbRaoLdSgQYMQwI5Ml58rsWGf7amzRLs18LBTe9C4vpu9p7g4xZHCHwdAwhpHR2hIxz278ajEgnIkagRycs+evH34y9b944WWkHbzNfED+4UM6Ccz9dGNZK5e68HZvADaR1fOqFbhesWYLHfYXhiQhxX2oHbDzBdVUPOV1CQ2Ol7jWrD4t4eAu5XJq23C2z7kCMlta+vbkYnQvRHxMbgZgYmYmocv9ZECQEz3MJacDLNnNfu0OTOYBUbu7W+3gFrbIQCgros3Gu0dCVjEEBNFi9wVBJQOKk7dRGA//PxT34CX/7aV3H2jXdwdrFHjQkfef4FlLLg6uoK07QAeoWAjBQjhnHEi8+9iBfuvognT8/wla9+DV999VVM04T3Hj7E/QcP8dzdu/jUxz+OZ+/ewfZowDzPHLdHwWCy/8Xkv1wvEWiKMhfkISOmjNoUb99/D7/+61/C0dERPvXRjxp6S0Ox/TTjvafMXStlxhiFo5XSyDWzcemsC+ZSUFpFzBlLKQgSMJeKlBgQOOSMFBJSzBAhmrrdbgHw38ecMOSMYRhwdHSM8WiDNGRIShgzG6ZgxXJtDcM48v5WRdSGcRwo+j7Ypxzh/HZeH+iCZEg0Fjt7eoZf+9X/ij/2R78f3/eF78NXv/YVvPvgHZw/PUMJAW9d7fD2G2/SITBFnFy/ho99/MO4++wzeOMbr+O3f+t3kFrDF7/4OTz77Cnu338XS5nhcfKlFqQc0aqi1IqYMmBdQogRpa6bm8N2MeiaE6PrwcIHqvZOnZsdIetWbUMVgZuRAUQGmvDgrVqZndHhNjukakUPcVJgKdo3FI46wAehFKIaElDmqSscODu2wy8063jp4NnVDHZgO3TdI8cN5YiJ79+vgRjxy70eOtyn/O9s7rqqnAN3XodQfsqzn3P8lCKLDVXUOnd0YYWwnegn3DwdmlHn3fD3Jkn983ZpIoypb+8vGAyuNqJqjQdiNMtuQDAOQ1eaUIo3dztp73B97DXPnJV3dnokDNtqxdnZGWpTpJShGrqiRcKqRPHRQQd8ekG4Mtc7qde+sFWWxsHQN5GD+9i/x4oBUz9oAOZpxjLPuHZ8wkKmeYfM6xoSZ/LvPryPfPYE167fwPboGBJ5PctEOJ/yzwAEjh9S8tET1kJB3Hh+5VY4J0SxEoOJHFdmCJXan6VmYwmXHqtJzt2E0M0JvQiAUFUiYsRxtL7+CGySg1WVZPRhyEyxresIx51JPRtnOVAoqBXjUKA2rqtofB933AwRvYFR/6CKPhUWSIfoY8z+k/vv4LiW1gP9ABcx/kQzlCJyHRnBPkjohGGx665qLsOOQkLWhsrfV99P6NPi0lgYquHMYipqWhfVFEOCtTGj6VCd5vEUXfnX12yw9exIK/dEaEBKQx/TQIThoG01xWQN7dwdG4MB2MaEpVTMy4KraY88Dvi+L34v7r93hqvLc/zuf/ttPHvjFm7dvIHj42MS6uuKYO+urlDSDIhgs8n44h/5Aj75qY/hjTffwJtvvI6zs0u8+uo38Oqrr+Hu3Wfw6U9+DC+99BzGcTRgWlG18JJ1NNf8hIYETQmSRiQV/N5vfxXvvfsY2xc3HKXngGEYME0zLi/P8fo3XkdrFfM8YdldAqUYaiaQFDFsNmbBQC5NjAGtVLSlYmcZPbUUSAv2PEmvXMWUkUGIrmezToiWwZNGxhicnp7g+eeew4vP3sHpySk8MHbcbIAYMQ4ZknL/uTSZM95WWM+zP+j1gS5Ivve7vwu/87tfwcXZhHtvvYlf+xXgU5/5CD79qU/h7vPP4OnZE1ycnxOOb0DOA7YnJzg6PsHV5RV+87e+jLdefxNlmvH5z3wKLzz7DN67/w67xGAHWAxIKQA12SRDLUfFpVABNZC86dHr5FmYosKfGKwHsvNIBHZoSeT4hacmN5iQ0Fy2q9Y9GyzL0Kh1I2UBlDokHg7mdbU1vqeUyDo3pz4A0MhOhzJgZYifrlkwELxPunYoKaXUwayfIQafVPuorprw71fAR1itrSqoZnIwH9tYum4wQzhmpwTAUpj99ztE6KnCIms3dtjjUmIKJm+K9E6iqzp6weVSYC/sBZR4B64FcVSIP588loo6zUasXa9DtCRQkm65CTx5condbkJtipyTmZ4RBtjtdr1DbOowvF178JoS3ZB+QDhm52oLP9V8U1ZBtwN3MmiDt84rnEC5JEi18A/fSD69dfMmWqmY5gVPzp7a9UpoZDNDRHB1tcd+foBheIoXX3zRCIwMdfSD1n0/FkeVBH3NtXrgpwIxSajjy+6BokCjY00njPpaNGTFC1JeiYom0fJe0JsAROlF8WGRFsyPpZnayJHKWlfJuq+pPiZ8XxFcoZUFlcCI4FWRYyJ/SFtHa4IIhkCSt5tywe6c35MYKLP3A90/XyejB5ZiqsaRAtBznOz2hsDxR2vS651iXAy/ftwvDkZhtgRgiFM7eGbVijQFx1baCgsNM02LQXqKRL8u9nnc+dUjLIylgyBEh9WKQIGa46n1PapAVai431DgujKUCgA8hRbNyPcpQmmCbh+I+TGDZCyNyPbdu3fxhc99Fr/6a7+Kp4/P8Zu/8Zv443/8BzAMGbVWdvgxE11aFit8abu+31VsNgM+85lP4aMf+Qjeufcu3n77Xbz5xht45+138OS9B3jj+Wfx4ksv4rkXnse102vdlyVF9LFg8xlY4HX66ldexbv37mNIGednZ3h68RRDTgjxGLU0nD09Q5n2GIYESQFtSCjmvQOTQpdpDxHY2RMQtyPGmBHDiJgDkhHssxlmHgZXOgdLtXVPlWQIYnU+FRTnTx5hjMCHnnsGtS5QpRt4WRbmhmnAvDTEUKniCg0RDVEy1nbqD359oAuS7/mez+HWM9fxCz//X3F+fo5vvPkVPHzvbdx9/lncfe4Obt64iWdu3wa0oCwV07Tg6fkF3nzzHh4+fISnj55iO2R87KMfxgvP3cHu8owbZAwIyYiHEIQ8kg0tnl3AhykPmZ4VKRtbnhsdvTiidXlkU1NGaJtmWxn3rhOvxnCnfI5mMtyYtEO7rkqp1ZEK7aOH6hBsCD3DwA/v3dQwL9XgaW6sDdozWbptsR8aqvTj8GLCXj3G3Aoqbt5iNVTo4Xo+eml1tTFfrekFAVQMTPOeZDCXbroxkT2wIsLkX5D17eOzQxVBP6d70UTLcm2UKrtkOyeSHwtNB3jQeNUuQNWCstBPJsaM1T6Zn620Bq0F80R0puXGBF+l+VqrJP+KDlBVLLXi8vISFxcXnO0H6W6odSLZNQbT9huqoW31hRHCPb0THiXb1yizeOw2rCMLG1G1asWi3yYbA9lhTnm5mjmUuMaob/Q5Jtx94Q5unFyDZ1uM2xEP33sPV9MepTQ8eOceogTcuXMHmAUPHr6Hs4srvPjC87hxekpiJHysotC2AI3qotoUggBV6ehEBMxp1t4L9H1SeLsL/fN6MeIcJf9dfKZ44FXjG/EirMSiapCf+yOEULuxIL9e+rNTSkVVJ1A7AucHom/ihu6Yjb1CO9LHr48IyZoQMRvwZlJW/7RNAfMoAt4/LvFip0WOBqWvf+dQWZFhnS7sfQZb37U/M+h/B5BDE0MEdOUANCUi6eqRalLjBoXazw4xoImrYbjnMIXArqkyV6W4c2utaOZJ0QMT+SnhI3Axf5YYQucl+QgLB8+3B9jxz0M3UXP1Vi2FI5yudsKKSth71dbw+c9+Gk8ePcbv/d6r+Po33sbRyW/ji3/kC4iGdIpUjMOIo+0xFSkporaKi4sLLPOMeeaeeeeZ27hz6zY+8uGX8PVXX8Xrr38Dr33jLbz59n3cvPV1fM/nvhsvvPAChoHk9RhdLms5Xprx6u99Hb/0C7+K3e4SIdLXZnu8wVtvvYUv/bd7QBPM82KhptyRokQUWVOevfhThaVFF+zn2Y4WQTNzzTxk5JSx2YzYHm1wtBmRYkROA0KKmOcZF+cX9jwF1GXBmAaknDCkiJwinrlzGzFnU+DZOspsdmtrmOcFQRh+6QWkyqpO+1avD3RBskwzPvzSS7jxP1/Hb/7mb+P119/C5eUZvvK1J/jy174KgJ2v80HLQrJPFJKgbl0/xYsvPIdnbt1ktx9IEEopYRwHSDLKlWWPUF4ZO5s9pWRELEu/FXbyVStSEvMDOOi8lcZjECIrKYzsoCoBSqAjt3A5mQoffO9815A3burMB2EnGWKAhGSTZ1us1qHVMiG0TM+RQIWHd2/sgixnJaQ+UvFOhJMZ6QUAxC3Y64pMWBcjAm4wpRqZM2DIA/JA+JlFj3sGrPNof7gaqBpyKLqrAOywLYWFVUpMkGwwMp+Teq2iL4edHyyV9wDhEdusqx2eanNuhSIhdaVSlFXlsswLPI9kmn2jp+dCqRVJEmKs2O/2eO/hIwbkmbTTT8TusokCIEKjdLKuAeG2yTPJNSQSRffLTLRIBfN8hbJU7PcT5nnPzicl3Lxxk0mqUMCMvkSsYAxOGFwRL5HVRr7WimUuePb2DTz7DDsgWPd0enyC05MTPH7yBA8evIdrp9eQU0KOCXeevYMbN29YuF5DKQtqM4JhTqhVoTF0S3cWGy7DdvdZFg0EaKguSUIPg1IX6EHAnJD1CWfZuJLLI+vFnpfiRb9xr7qbcwjwNCDKjrmIqiNNdog5A1PMR6YrwFTNdj/C+QrBEC4FuVrBOB9qSbW1mddPcHt+z0zy4opPvooaooTVCdYs+8V8IViBGJlUImJwK33p11CViJRzuarn7oCFMWDogvqIVrpzcoDxf+xedPCzrWgJmvmbmK9PJ59HYSOjiuyJ5qJmAujFt31aa+ycn+OFlipcsU+EQ4wALDArN3RjN0D7+hWJqE0RtBoZk1WMNzEBgtZoZ56GjO/9vi/gyZMLvHP/IX7vd78OCRFf/MLnmO3UKqXLKfdnIIWI69euY6kLdtOEi7Nzxh9ow3Yc8D1f+Dy+6/Ofxle+/BXce+ddPH7vCf7zf/4F3LnzDL7rM5/ASy89jxwCSl3YkknG6994F//lf/klPH56hpQmJBVc7Qp+78u/h/OLC1xcXsKN+mLm3j2XZv4gse/dvizi4CNsBvit4XbmcVQLdphwdn5hUDtH4SlEvPDyh3Dj9k3cPj7BMi+ocwETkwPOz85Qo2AcNsibDXbLTP6cAmOmrUGMSvuAxuc5NjboCm9k/zAYo9WCOgmO0oAvfO6zePnFl/DWOw/x6quv48nZjt1oMQ+BQIh+kzOOtyfIKeH6jWu4fv064jgibwakHJECN9KYCK1DuZnEIH3jC1HswT5QiFgHnM1yu3ll7oWhdwPwh4UFBdSD5njY9ZyX5jwGPYC2WQY7dyMY7Ao7yEJK1lEaIqNU8sTo2Q78frf29U0B6IALN1g5HG3w57l7pW/I8zSjtoJhHLoEUKuH5fF95xiR8tjNpjp7v8EQGhZ27EYXlGnm7xVBCqmTRXkQ2PglRStICIc7Vuwz0ZDYNaUGaJc1KsrC6wHvYP2QaSts7RvfUqaVzNzlbqErpHgvrF22/3a7+qsnl3j65IzkP4kd9egFli8JK+K8wGQHSSl0KRU5Zdy98wyOr50CoK2zS56X3USux7JgN+2x2+2wn/bY73c4OjpBgyutgHXHqh2OV7VNojXUUnB5eYVlXnB8dIy7d5/tBnJq5nKtCZoAp6enOD29BqiZiLmsDwppDcWgXScWS20oWhEaV1iIHGe2pXS4OFnR3tp6f4ADFES8WHSIw5RbcNSBBUcp3HTN4AeA9GdWWzNlFohymgKmGuLo66BzVkzJYngmOU39vtOzoVEfDgFDPKtVQ6L2z0EUAlAhpsiLgYRN4xGDhVnsnjt0i11HUyGsvhUNfHajdZ61Lh0B4Z5THLzsxVrswZ4Hbs12rdsBrwZQk7yzLKaaxpANJem2GbGrm+5ZsSDwQpsv1hLqmj26TAtlzrCf3Ww87ErCZFENpZQ1r8dASvco4p7HApSNDxFo5+s4ptlaZYNnz5dnuDDqgWOwa9dP8Cf++B/Fz//8L+H+g/v4+ldfQ5KGz3/+swgporaC/XTVIydSjAgpIsaE7YYj+VoKyrxgmvg8SgA+/ZlP48Mfehn37z3AO/fu472HD/DLv/QU3/jGM/jkpz6Ju3dvYxwilnnBb/zql/DowX1Ijqh1omeNVjz6yqs4Pj5CTrGPqyABVbuw1sbqCc5XC0K7hSgkFScoprbBrrgJJ8cofD7tvJIAlYClKYZNxhe/+H3QBlxdXOLi7BznT59gLgUaE0NKQ0IJAYt4cxqgklBVMC8LGoAUPamdY+tOwo4rjeAPen2gC5JWqOeurQAVONke47nnEqa5It1/jGVh3PK1a6cYR7KJx5wxpgE5pi5nizFgBt0rQ46IQzJIki+xwiEJuiKBxQhDklxxUeuMMAyUuVbtD1uwzcqrVeBAVkfiiPk4VFgTjFpcMnsQPGXdlGdduEFXMA5AKTO7QIMrAVgBouZYWbgH2hwa1fgnTvRUmEpCbHO3M9d+lhdGtTXspj1CCBgg1n2a9NHRHCXUW1sBAiW+AIxU6/JZ2rm3siI1tTIEroqNp5RkKz/AQvSxzppK2ownA0UnlnZ8synHOL6hxQgEeoT4GINf7oRZGoWJjbOqmI090CW5qAy7chJdzBmXl1d4+vgMs6Eo7KDN4bZp78y986T0tXXZbZCAWhakNODk+AQ3rl/HMAyoM9fwEBMQBTJsgM2x3S6SDYNxes7Pz/HovcfszmXdwLsSKqwBZZRZBoybDVIMuLq8wksvvoAoEbUw82Kd+/CQcQUPRxwLtHENJ5PFQtHHbo4he/ZTXVY/GPr4rdc7pmSIhI9gFD0Tx8YJ2pqNcSoL5EhX2pgSQquY57kbibFo53MXACCKjVxDJ6qrrW8vNIIEiK0pdE6E9mKoGvk8gOsigCPPEAaSBaXYSFVZjDlqAEWy683D3quF0PcHiKXVyipRjsqCO3biqMUv+PI2xNXRizV3iX/Oy2CjEJP3V1OyuSLLSc+O9DA80zeOlTStyl8YDY3qFWEv2QhrMJ9IrbHxZ7rZ1xORga0Pj8gg8tmwVEWSZF47AOoBN0vVUBu6JPvz7e80GvdE1r+Cj6GD7ZHNDnZfx6jAs3du4ZU/+kfw//0vP49HT8/wW7/x22i14fu/+AWcnGyxLIwH8F9UK4s4sfs5DIP9M2Ke9liWCbuLSwQIXnzxBdy5cwdvvvkW3njjDXzt1ddw/8FDvPD8XXz+85/DydExzi+eUmEFBRpHmHMrgEYsSyMPyXFTl0qDQ7SV2yQ2ugpAWSxJHJgFaHEE4oBYroBlRpSGCEAj96UQI1IicXsYIo6PRtTWcHR0E88++wzKvuJyt8f51RWu9lcodUYaicCSqGtnSRBUoflhE4VGC5S0hrqaHP7beX2wCxLwoWmIKLVhWujR/8ytm7h54wbSsOFDacQ6gBt0Mta5w7BNgLkpdFpQm2KAkQ+bzf2kmVmRWGclkMKZZ1U6i/qDROmYGEuZv2deaq9yVZqBJYsdcAYrWyhCc5Jh5cMnNh7pHboVNdzQ5X03upNHbQbdWkNUbuopxT5uAAS1sMsNAJqWXskuFijmh3WtJiUVn5zzdXx8zI69VNhknJspBCFH8jfADUqg2E8LrnYsYmIUZCNjL1PpkHNrRppbKmJsWALly5uR0dYIsFFLXW211TrY6uZKq8fFYcIrhATGkOIaUvi+xcRDL0pA4AmCUmxsEyMkp07WbMqumBHoDQ/eeoD9buoOktF8CToY35EU9HWohiiIvfcqFSllvPjiS8g5oZSKEDPvZ1tVIaVUqBKlK60Sip0rri52eO/hQ0jgJuNW0PAwMXUOhHmoqKsZeI1uP3MbJydHmMqCJBEwCa9EN/8yVr8IUMkz0sh7PM1EtkQ4alGDuVnRmXJBApowZE19/ADFUgukFrgrLmtrFplLWXqKcnfnLezqxSDhUirzb5D6YXV44PbDrDUouK6iSbSpLmKniChrgQBYISwdoek8DWsceGMTEDnmSCEwA8YM0pzTBaybbGsNxdGasP6u0ohIpZxJriwViobNuGEBb/C6ltaLLrENf5pm41Z44RLs/doIV/h8cxzL761V+yigOuICckdcUeR7JQtIapg9VoLPk/1z8FqbGCPgJoFYNoyju2WeOWry8Y2ZgfX71lY5tbu3dq6ay6p97dhzwcKDqFSti32d0swsUIWCA4TFi7hSZzzz7E38iT/5A/hf/9dfxePHD/E7v/k7uLq8wB/7o38MN27dsN/HArcrrApROeeqBQDbzYhxyNiOGzRt2O8mlJbw8kc+jOeeew5ff/01vHv/XXzlK1/BO/fewQsvvIhPfv/ngFe3eHpxzuKtFWgt4ERTwTTo1u8hhI1ysJF8UKohWa9wY1q0YIKiIqHqDhoKBAuiEFvJYMEcU0I0GS+04fh4CxGlW60ycRiNjUaWgAEgal3A0Z6YF4lWRImI0QqjRO+fGDhWH8ZkhOGGb+f1gS5IohnG1MaJvIp1fDl3a2lBYk6DhO7jnyzEqpk/iD+ATRt284yiEddSZuaGG78Ek6EF875wsgfYNRAGD86vokFTV8MAqqX7AXTehMH3nuwJ8MCVBigaSnMPg0BioD25wbIBWiloFvgHoHMsAhpyjByNSLPiJfSDuS6EjzVnKGgW55C4NjPQEemHu4eoOakOAkhhoFtrnFHHGLDb7zDPM27evAkJYhwSYL+fsCzAvBRstxucnmzRloI1ttw6dhGkTE4OMzEUTQIWtWLB8l2WUuhgGFyt4pfA7LGDy/+sCDDpqqqizobQOGnXoWdDlqjVp0Ljsl4BQp+JZMSs1ij5hCQsy4SHDx9hnivyMJAz0GpXNyD42uL15DSOrYWAYxhtDcMw4Oatm7h16zZyHtFqwTgOAEI33uPG4UWGSSjBOfHFxSUuzy+Rh4FryMnT1qV27wk7rNBoouTo0rIsuHbjBjkASCzGHIkQ5yGxwOhTCJHuQumETq6P2H0KoOiGelClr0ILFiBmo0sx4hsXGtU1TVEWum12m25If1ZdvaYg+gVhUu9S3/88I67vFfbn2ho3ZJei1nXs17tz5Xupqn0CpIY0VivMmDRc4GOw6uMMgZEX7RqJuXAKuWgp8VBRGy8Nw4BoozPPoClGOGUCLAvfjv5Yceb/HcX/x0dWVggeIDRBVik+nHegtY9m5lasOZLVddXuWS0NNaxBoU6iJsr5vkdvve5e7DY1hMe5TEQGtZEwzMTuA8TZkuuaRS3EwJTjAEOB/HaGYONVi6NwhEsEGiKKrcd5mvq4INqeS9Q8GpKcoNLwwgt38T/9T38C/+W//BLefvttfP2113F5cYnv/+L340MffgnJ5NCidh5EweLOrI6qGaIWU0ISwTBskPYzpj1HrZ/4+Cdx/fp1vPnmm7i6usJXvvIVnN68jZc+9AL+5Mf+BI5Pt7i8OEcrFbuLPb7061/C+ZOnRHtEwUl0g6c+O5G6NiLfMURU1I6aecaQtBlNFrhfTRMbb5k0mwZ7FddOr6EsCxHiZmt9XzDt6KvCSAIix7DrD+MHiSrRSGXD4RYOzWTfOUXzqPnWrw92QRJHdnB1QcwBMcMISWvQEotwAWLEvBiZzh5mwr/SlSzTfkKtFTkPAARDHAiYBUuBtf42BFjXwgOsd5tqoKxtbu7P4Wx4ONIQVoLqKle17lNXmJJLh1Cqn2XeATXnl6B20pp3gxENaRhh4DSaMFK+lHVmDpjKRR3l4ObZlHzInh0D6wyDYCnFrju3BrLaeehMc8NiEfZPnp6jlAUpJeSYsSwFDST5lmVGXdi5aGW1HkKgYqkXeKFvcK1WzItBzQBSUJM2suNTTzG1TsuvIZoXez5jJ6+GQV28smgriuOBX0OKSCFgP01UDFi6a23uPss9n+874+bN2/3gT8ZTQKvYTxOR88A4gFobloWHTi0LailIQXDtxk3cuHEd47Ah6lCInNWyoJn9eGsNEeRfpJCIImnDfj/jvUeP2VVaxpFPBKA+/gjdAbVDvH6NwMtQa8GNG9e52XjTK2JNpY2coDY+seLGeUP2TFQheVZLQzAEBqaUiZHfQ0tt3o/aajfG8w6UuWpmHGYoBLkG1tUF8i34FzD3UQEt5ux9qn9KrlMJXsqYsZg9c84XgX1tNXSM10Q7+rZyuJpjfjZKMqdlpYV/rcUaF1icBaDCjCUqrHyMsKJ4gCK4Q2ZTlHmxP1UsZcF+2q8jHBs9uD9EMKTUYxqaVvLOvAEyNdU6wRH//4ZiuOOvHVRLtULJul9Zrw8LYGscgoBczgZJXAfNkNH1YC5GkmXUfTUiOvkL6PuPP4PaTMlkLsgiDH0sIPocrfLxZRysSEwxYVkWqx8dNbYmpPMXeDD7dSiVDGZ1JEbYxNy4dQN/8k/9cfzX//pf8eqrr+L+uw/w8//Lz+OzTz+LT3/6Uzg+OqIVRGsmmUXfhzh6dYI/uEaFrqqbcYN5nrHf73Fycg0vvfQSri4v8dZbb+HRew9wdvYIjx7cw91n72B3eYmT42OUAuwuLvqh7w7IHtBXWmV4qHn3CEgbCI74NzZBinUNdOsJayqlFZPuAteun+Lk+BjTfjZpcqCj+b5iKTNNQtuaOi2Vo8MEFoc230USQYZdFxEL6aOHyaFn0h/0+o4Kkp/+6Z/GT//0T+PrX/86AOBzn/sc/s7f+Tv4oR/6IQDAfr/H3/ybfxP/8l/+S0zThB/8wR/EP/tn/wx3797tP+P111/Hj//4j+M//sf/iJOTE/zYj/0YfuqnfoqoxXf4kiFBIg+9Q7SDlZxFxFt3VdUOJ4OGl2WGz72DSDff8WImglHjIZp7aBBc7fcYhwEQciFiYDbLYVfmjp3loFsL1k0uy2IdjBGvoqAW8imC8EAsrfWbFwBzNiW6o+awClQbHdE6G7a5KBTN4LLFrNqhVK3slz2udjuOokLE/oqk35wzch7YQQB9dOHKF/9nnmfsdjtstnzI/MUGmN1/lIimgYVG4SbRWkMSdsQx81BFK1BwI1ttuRfM0wIJATkPvBa1sFjyzaYI1MhRwX63KA+3YDwYehkY58A3VMBmYRxRBLfsRu3+JkkCooxY9hU7J/uZLFaN59AWchU8CRPigWuCkAKGwcYI84KtKXliCEjjYNfq0K7fI+VNjdWsCIS55gKrfT0UY0rYHm0xTxNqLXh6do6H7z2EWoEgNoY0HLVLIbu1OBTS/PBfC+Amis0wYmsbp/Mc/P5bHw6VauCO/b0pZaoCS6EaLAbKlOmPworQ12mUAKnOreCB3cpiSILdorqSi/0P1bt9HKAtWHM4eHw72VJ7QcaSMyCCuSI98FIbEkIvzjufoZlzMGy0Fd6PrjW18EIvbMR4OU1RloJlWdCUz3SyEMQGBujFNHTSLg/L2qW1e2tsoqFa3RPIPpd/4mqjHlX6rLgqLQT0Z9SJwHpwLUJIpm5fJfDSwRZTKPE/1j3Mxn19zBdCv6fN7fMByvUNIQji4x70IhWyqniK3S8P26vejEEQYu78uKat72WwZ1sbzFuJRXLThvC+WADKT7WRZ8cRGomYvgfXZUFICTkPht60rhhyH5eTa6f4k3/q/4Zbt67jt/+338LF03P8+q/8N7z1xtv43Oc+i5deegFAw1IXBEmGmtg4yhCkYM+9IIGJ3LSR32y3uDsMODk9xrTbIcaAadrj/v138e5bb+HJw/sdDS+tYdwOmHYTVWCRnCkttJwvHo+AgKDVuBoryuzCAqKIpkhS7dcLtg5qJTr7Pd/z3bh54waWebb074hWiUTP8x5L2dt6hV1vety0FozwLtAANsk2VhcJyMOB4MEf8m/x+o6qgJdeegn/8B/+Q3zyk5+EquJf/It/gb/wF/4Cfv3Xfx2f+9zn8Df+xt/Av/23/xY/+7M/i+vXr+Ov/bW/hr/4F/8ifv7nf54PVa34c3/uz+G5557DL/zCL+Cdd97Bj/7ojyLnjH/wD/7Bd/JWAABH22MgJeTKDrTUSg+NKFC1mXcQ+3OYcRk3qJAyUo69U1QFRjO1qvPCFE0RjHlkZxqB8egYEqkph2o3BhKQ/7CSTINVn2oogoFo5toIUQzqEjuLC2+0Sc5qci2wM+O5QvRCso1SNLF4UibrIoCLNhhfXiv2ZUFAQQwsnqZpwm6esCwFKQ9UqoRIW/XAwyOFDBFlFkZnxPM95JyNPd04zwSMJyKoFSiT+Q6oS/3IRB/SYItYEZoiSIOWiirBFmuk5LTYhloUdandLIwPmM30D7raAG4kbhi1FI60lsoNlR0r73/rDyFJu2JmWCtBmfdkWqauwPEu0mf4MSW02qygaKttNoCcWSSVUhECH0pkg4XNVZLvGQeFkdqsu6JWUyFl3oNogHwzYl7OGZujYyPcajff22w2MMW3oR4ukwQJrGok3VbBTJ2C4BwTI1Uv+z1eePYu6n4m4S0EQt61IWXmajgauPpreAYHDzWH96PwAJFATkVThQY1JEHXg6qZJbp1k8G+tpmzKu35WVTCrOkPj2dHCU2CsKI6WOWkwWDlZiiNwhBGSIf8xWaowQL6alu5DgDNxKp7BYmYpFHQYChOVXat9nlYWHNc4EWJQhHC2Dv34KieF52wdYbDpmb9PHKwjztBUNvSR15ywEOlQSKRiCCx+x55Vx9jfF8WjAMVzUbEDYbwWPEUJXV1XVD068LxFEgs1gPkqZkLKdbnzg8irveKUmF8oXUEBUd1lGjuvJReaJDgToWOI2CwZ8Naf9unFAdPM60ZNHakTkj8QmszQk4Y8oCYEqarHWXDIUIaEFLG5z//PXjp+Zfxy7/8y3j7nft4/Rtv4MGD+/jYxz+Gj37so7hx4wbSGG38xM/tPkNeZFH+HVFrgO4nPh8h4eTkGNdOTrDdbrHb7XDt5DreeutNPHryCHnISDnhxq3rCBKxu9qhIiFKRowDWlsACQghoSyFRXNYx2jV1ncIVqSZKqeZ6hKu4DSagWjERz/8MXzqU5+0+yEIYcTV5YTdbsLSKsoycfQcqvkiB3M7jvz5TWyvsWKxCYK57MaYuOZqYzL2t/ES7bjc/77XrVu38I//8T/Gj/zIj+DOnTv4mZ/5GfzIj/wIAOB3f/d38V3f9V34xV/8RfzAD/wA/t2/+3f483/+z+Ptt9/uqMk//+f/HH/rb/0tPHjwAIPNwL/V6+zsDNevX8dP/r/+JkLOmOcFrpNPNk9tdV3UChgHBKZ+ALsLy0zhmq1d817ngroUpBCxGQb+eToIVGvvJ1+llBBjohJCYJ1Q7YQs70oU2mfNgBUypfYIaveQ8IOqlIJ5XsiLGTJzEvZ7aGV3vdvvsJt2EBGcHh8zI8UPoWUGFMiJm++8LLjY7cijyQPfT23YpIzrJ6dIJuP0jbVZseHkMm87Bd65K0Ki0do0zZiuFgB0CQwxIuaEMQ/o6ciVHhhMA2aFzt/XbDQQLMVXLGdB+qalNgeepz0A47LY7rNKNdEPWd5e6Z2x2NhEBOTWeDcph+M7g8bNMySEgJgODJ7s+2OK3cPFX2pcD4VFn/fd3jYmmNeIAhKdqHzg4QJA1aSFEvm+YgRkzanIxmvphyZYaLLI4DVYponQeK1YSkEycux+vwfHAMXWekMMgrIsWOYZH/vwx3hIB87HWcS0zqvhAa9+dpg8FICu8LoCyCkCnbeCDm3bYu+/m2MkMaWR/0CuKeceUI3l3BQbG1ohJwcHkEMs3h0GPtqIMfU18H6H31WFxnAwV1oJ1jeLPjaFoPuQ+Dioq1ms8yte9NWG2jh2iSlaWGLo+U1qs3kYiruOE9fQxa6k0HV/6WMy23v4PcbLMD8Of3+eji3gYcwDofbrLob8iatc+ED1awRT3MC5Ef6/cnDwGXesJyC7v4oYOsTKb71uXOAHn02tUDckze6jK+wcNWsHChcolYcxRqSc7B6UTrx1BMqNH/k+bWypACol7O54nGLCdjyCasN+mkgsNtS2FHoy7acJX/3aq/jy7/0Onj59gtqA05NjfOhDL+Ezn/4E7ty5g5xSTx/38WoviEPsTakbTxbzLKq1IYlgd7XD5eUVvvbqa3jw6AFCCnjmzg2cPTnD5ZMztLTBOIyIEbi8vML1a9fx+NFjXF5eIGbGOKyDU3SuVbA9vClWpNiKJT5zilvXbuKVH/hjOLl5xLMxRTZ5lko+zTOWZcJSZ0r3lftwylsMw4icIjlQEroVA4nZG2y3Rzg9PcFmswUCsLu6wv/z//438PTpU1y7dg2/3+t/N4ek1oqf/dmfxeXlJV555RX82q/9GpZlwZ/+03+6f81nPvMZvPzyy70g+cVf/EV893d/9/tGOD/4gz+IH//xH8dv/dZv4fu+7/v+h79rsqh0f52dnQEAK+7GYB+IYIwZwxj558G19J5MGYxZHvrD5JtWrdStO3k1hADYCGluBUNOiCEBlfCsb24xJogKZZJoKKhWiaoRGtkhE0GrfkbBJVzLUlCXClQg0N26k74gAbt5wVtvvwMJETdu3MR2s8HTR2d47+FjbI+22BxtsVRgmSfo3HB87RgxJxSezt2LIo8jUt5AJGMxSL0UGl/dvnETpycnXXniqbWrJDphnhbmUVQWWsMwYLffoapiGBJy3mAzspg4lCnCCKfiqIBtPhLc9MnJmUS0FG6URht1Tk6khxNCq3XsAsBMgJp3pl6AHkLSduiJwZ4AptIgrTGwy5CTGBNHHxAEaUgBABJ0sdlwX3lutNXgf6rW+RBECN2CvBOCy2pTrlB34KL7Yk787I2barG8G4SISEQWwTrpw8/XCbp20LjPS0oJY85wt8qUEsZBsNls4IZxCthM3zpVg+3neW8y2mxxBiSJUhUV+obqzx0dPSmdTyFiqSyOSEBdHY3RaO/vI4WyLFAEhJQ7QgJUGx3YARzJF5kX//4112eFDwK+ucjIKfEgtYPS0UgI0NrSibauGBPwa1Mi18OLEh93OMlW/ISEW7kLnCAswqIz2WFWq5ukEeFp1pm65JiNjH0EIXpEjxr7/Y0cDrEIeZ4djaNYrDJ1b3ShMA4YCYWen+TFvztkkk/WjISu9nlt/BHSepAKETiqCm2s5aiHdcGuulP/fg1wq/lpLl3ae5gEa0+Pob5C5EtXgMstBZqtnd4qNCti1UbvZSH3T8QEBkwOP5Tts5Ajj6P/XDPII5xIuXxZqvmfMPkWgWaJMiTUUjCMCd/1mU/gQy/dxWuvvYbf+M3fwe5qh1e/+hreePNN3L51E5/+5Mfx8ssfwna7NURz3X/8RqWY+meIaXWsVhXEIeNYjvCpT30Kd57ewXi0xdHxiG+89nWcPTqDtoLWApb9gvnyCs99/OO4dnyEr3z1azg6OcWuFZRpQlQi0BLYpG3ygDgMmJaCy/NLypUh/Vw6PjrGxz72EczLhHv3znjdc0KyvK0QAsbtEcbNFrFmzLsJANcrp8J8RlptCMnNA1f0UsAmj8nwnln1rV/fcUHyG7/xG3jllVeMpHOCf/2v/zU++9nP4ktf+hKGYcCNGzfe9/V3797FvXv3AAD37t17XzHif+9/9/u9fuqnfgp/9+/+3f/+L6wibwEYImV/QQQyJIRibPTAmZeCXzvkoR+2sC5OgmCenLjHxR0iyY2UccaV1xE8gIr71VKtk0QzuJ+3Dc03buYpuCHP+nuJwszTzOqyJbQmKEuxjosbxcnxNVxcXOLi7ArzjvkBZ+dneHp2htu3nmGh0yr2o+BYEm7cuNWD3xzd2E8k626OTtAanQ1Pjo8xDhzD1LlgFM4pc0p0MDUSnwI4Ps29um5lts9E18CUE6IVP9UJX3DEwdxTRVHL0jeZFZQjjLsUynujYu2g4JuoJ8mKQYTNdPAsNppqV9Z4Z34I+rlFuhcu1cZ6zUkgAiytoAm7i5wGNARoKxBzznQuDMQRI3JMYgz2Xgy2/yYfFj/jooUWcqSnnWNUmyVGS0I00ifAn7Msdv0ECObh4gRRX8sO/TeX2AKYdP390zz3wqD7aAhW8l+jf0CTBsSIpRTUOnf0jxB6Q0DqRZArahyiZ+R4oMLIr3vkyKyUgloUKaPfrzyM5G8opds8CCwszTt5v5cAUuZ1cVSqHXS+K7oBRCsySlWY1S8cyocIYhoQ1CWcLuX159UfS+vi2/tHJw2GKgjJfH28YByKzmWw50A1dI4E1FR58PdkyJyNNASNRlZ2vT0gsxuL2bhIlKpBIhJ0cGXWE+CBj45qSocF1OSkK2rgYz0BC1tRgXNa2MesJm3Oh1u9Vdbgw9Zs3cBUeQF9xKalkZBqKizpxZNzSziqXqMqzBJe3LvE+Bi2X3hDI6YCc/ktn0lHrIxLp+YYas8bD1dDvhc+b7QMaFAUzL5uBYwAEQ4cqqHsQYBrJ0f43i98Dh/60Av46u99Ba9/4w3sLi7w1vkZ3nnzddy6eRMf/fjH8dLLL+P2zVtIOfcGrLWGCvLZmh3YIWTuGVoR4gAdBwzDgjBEPH56hrOzC2yPjolAK0nB0zSh1gXPPvsMYk546+13EULGZkiUP9eGHBqQIsQ4K0dHJ7i63CM2wfnFOVylc3x8hE998mM4OT7G5eUFGhqqVhKjhXzAnAekfIE4bDAMW4RA5DrlzP3eJOWAG226hQAtM/KQu3JLbMzz7by+44Lk05/+NL70pS/h6dOn+Ff/6l/hx37sx/Cf//N//k5/zHf0+smf/En8xE/8RP/vs7MzfOhDH4Iz4QVqlrwREkgCDdFIR62u3amJp4Pp7ktjiF4ADbe8EwpGkoUl+HJTrwAaUqK7XR8NWFeTI1EUMQIZmqKoHYgS6URaeZBH0/ZLEqSUTc/eUFGhQZFCgtRKWCxmHB+dMDPAXGA//LGPYb/b4fT4GMl4JdvNFkfHJzg+OaFEzDo0D9bjRu5wckKOgUTSukC1crRjayaGCHr9cQ8MgUUHmmI2IuZ2c4QBrXdiLNrYfbdG9ZGbkKlyXBBgnhuVRRRD+jhegG/ISm5OCAHTPPUuvjVat6ecscye9ss/z3Gw0cHCokDXsU2w8L1Safa1yebzcOC06twjV58w6Xids5dCTgut0GuHhal8CqitMMk3hR41DlsG5ApwNFXqwjGVdQ6oXqQ02xB5sFfL7VFDQxLYVdI7wdRQxguxyqp/5pxy7zR56FXr3EnmLb2L8y4WNEeK5Ivsr3b259ZDK9n7hnvBZd5OlA2QTubUpuYIbOZ6NrEplQz9oOZ6awdEH+8Y+lBNbRFCNP4Br697mFQ7XNcueDU6q62htAIgGG/c3nGQfgh6MRz64boSMPxQkii8D+qfE7Y2YeNZU7k16wZNgbOq19DX3iF8Dx82WXOkynslViCKGMnXOs3mvBdT6BBO4ObvgYVVGRrqPCqFq2MO1oSNT2CFi48wHcBMlrjNTCkjQQo9KprFJxBUMJ6AqhF8Vwt+tT2WRU3o40gnxxMptT0zKEd0QhTJE345DjBUsblrrxgianhkNbUiVvWcF9z20/jvar5RxWW/NLX0gqjBrfgN8VM6x9LjRswXZuXJQBg7cu30FN/7vd+LD7/8Ebz15hu4d+8dPHn6BO89uI9HD9/Db/2338ELz7+AZ+/exfWbt3Dtxgm2200vnonUFVvTvPawwgdDwHy2w7133sbNm9fRqiKNW+ynBa1SrYQYsD05wvUb1zFsr+Hs4grDUGiVb80KYUfFUhecnZ9xlGz3ptaKl567jU9+/BPYjhtcXOwhC6X11RQ7zfb0Ok/kg+QN0nCEcUufFT+/fHsrjQG08DNHG1IcOrJXS4MMsYd9fqvXd1yQDMOAT3ziEwCAL37xi/iVX/kV/NN/+k/xl/7SX8I8z3jy5Mn7UJJ3330Xzz33HADgueeewy//8i+/7+e9++67/e9+v9c4jhjH8b//CyVcXB0eDWT7ssOiOiF6toT4g8jNtTbmrbArAUIKSCH2Taua9FVb67Ja8qIaELRvNDmETv6T4PBx6NVmU2DZL5z5xYBhHBCHtGZeHGxkDHIKdJFV79YEN5aKxfIDGoAbt2+hacMmD+gB7n3zaaiwGbk9TDFwphjjYAXE6i6LEoDQugsnQ5zclyP296d+SIKdRAAQTFrH7tkZ7+zex83GumdCvzyiONOOCrRiZk1RkbuvBgwNYaGRjBHv8/xx4AZU8mIdqdn8m2cDEzrn93XQqsp47NowzzOGmLDb7fi7hsQHv9bVxRLonW5TBaI5JgqVNBIiIKUTVTkGsSNVYDL0xn3XhZV2mDalt4yTf6N1I6UVVL5hHFCMDL0z3wYnRvfZdMNqje/wt6AtM3i4r0qO4rN4IXIHUDLpnhpaG+K4QZ3pQ+CmYtFmyosFdvkBUQ1uV1k5DMXWK5pCF6IPiykbnHsBO6RaIyl4M45EJ63AdH6MqmAxcihHqs4FsOupK+8oBOMsBIflHRUxxYrxUzq5GWwSOAayokVXNIVnvBeUYghH7agDn1U6GYsINCrUxnCrB4QXw6E/EzTCc7fYuMLdIRg53D6T2c5Hsw2H/SxYV+qHLZGFYCiJfaEpq2KIVijZCNr2AS2O7vib5GdVJ+8qIflmzpoCdPWjIKKW2tEVNgq2DwtsfyCqxQLLikr7eoF0NCrECEkJu/3elF9Efty9Nxx4xIihRJyE1z5eciS22XgypNh9NZaycJRukmoRoBmXjvcjIcJRzdVjJ8WEpVaU2own05DMzZRkUq65m7dv49btm/jEpz6JBw/u462338Q7b93D5cUFvvHVr+PNb7yJOG5wfDzi1q0bePa5u9hsNrh56ya2R0f98FK1z9GfbcG4IbG1BUXOI84v2Agv2pBzxOb4CNdOrmE7DHgyPUFRZs6okgMjSlVlWwpqmaHKEVHMgk988mP47Mc/gjFnXJ7tkIMAKaJMDcvC/KeqC9wssTVFKIq6sFDZT+QsXj85RggR2+0Ww3ZDF1zjSflac/4KUIFq6NS38fo/7EPSWsM0TfjiF7+InDP+w3/4D/jhH/5hAMCXv/xlvP7663jllVcAAK+88gr+/t//+7h//z6effZZAMC///f/HteuXcNnP/vZ7/h3p2idu9DwhZCy9lwYzg8DSLYEZU0OidoG2qgps8q5dgfUWir2ZQ+tiu24IdlKAERj7ysP102y4gLsrGsrqJVdzlIW1FJRG5CHkQmJIUBiQM6pExadme222wrtCguFIkYg5y03RysA3JNAjbxL1Q37BEjo5mBweNK9IezgqrVgGAaMeUAz11FHI+SbixEAxTrFcUMiWCkL97/AbA8nfYqlPMbITX9aFqAVugtaFxQbUBO7nWqw8xCT6dlXs7QYLardOh/PsRnHsY9QYop941UoQuT98GAzH5UAQB4HaGu4ttmg8bYbt8cttBXzRBb+mttBoqsT06CKEAuAhlIKR4a6KnliDJCkqMu8qnIiDfyCHYxOiu6R8qCnS1kKQkgQe5jFVFxUF+j7UCRPp3WU0JE8wuDrAREkcKzjCIB1h4txsqIVPHWxDJFm3IEY0MpaKHq3f+3aDUOo1iJIAJibH3ysA5BbNfgIACxCSy1QsBkohYhdWYqpQ+zw3c2ouqI+UXj4kTBNlA0gf6ECVvi3znWw6oVqu+Yb/wHxOYjlo5iDMrzIWUeBfmI7+ucEa0ou7fAOceU8HED0XqzyAlmfEPn9zJdhh5xjQj/T/aC1ELJDafYhNyogoMLI+wo0l/22hpi8wFr/3N8bQKKtGrJzeJ00NIRGzko0BEhb68Rxv9YQ9DWmWrkX6UpUdUSQn5zXMQXyUTgm5T3KgahtmWdI96Zp9qzZM6EZbK1YBmswVKiw0B5yhg92m1/nSBQzDhHTNEGMi9bcN4R1D0dQaHCPD7+HiKFzeJoIpv0e+9qAFKj8aUSXa2UzuNmMeOmlj+Kll17C7mqPd++9i2+8dg8PHz3Gsi/YTxd48vQRvvbq16Amg7196zZu3r6N27dv4faN0762KoDjk1O88PzzuLq6xNOzp6j7PaTOhq0BJ0cjrh1vkSViK8DQCmqzpHiwAQrVSN9BiCiiAih4/vm7+MIXvhsoM+a5II0ZxxKwu9qjNXrLLPOEYmeYgMV5aEArDUudABFchYBlT8uIzWaD7ckpjo+PUU8qrp+c4OhoizxGKg+FiJgGKui+ndd3VJD85E/+JH7oh34IL7/8Ms7Pz/EzP/Mz+E//6T/h537u53D9+nX8lb/yV/ATP/ETuHXrFq5du4a//tf/Ol555RX8wA/8AADgz/7ZP4vPfvaz+Mt/+S/jH/2jf4R79+7hb//tv42/+lf/6v8YAfkWr+02I6WMRasR6to6j1YWKbVURFVo4dM1JCpMaqlolYmq6PNH6/eUh0ADEHM0p0XYOGiFAMkupuLD0QNoQBAaGykUaUy2KRsr3vgHpRVEMzWDKnXmdVWfoK0ugNE3SBEL9vKIJYUxMK174tc0gyclHHSAyveppSEKmeoheFy5/TwBxNYR7bHd4RM0/TK1Sm0KlYAhW6fX+EjQOj2sRU9bCEM77yMEMHHTKXXc1Dnu4oFUHcK1z+sOK1RErCRG5/I0U2QAlCaPwwhFQynOE2DV7hLcZoTNoIS3g6AjCVxTR2ZCtDLna+Hhn1JiNAAo6wyBCpN5MdWBmT9RmXNkXIt60LUHKzZogb7dbpBTRisVF+fn5neTUFqzADW+b8Lt9kCLqxpWZKY1Fl0xRbTK/A2B9nA5qYBnKHG0xfdFMq8YgVG7ygpYXQM8lK7VaiZ0RHWWua7Xjnpm3lEFzaoMSShlJcPxjmtv02tZu6b+/GBFF/jz7L43dnBS7PrZ4S8SkFOCpwmvvBLzrjFESmJAKQ3B5NsEc3ykYt9jZypsLAL7WTGQuMr76WWu9NEa1WbuYeIOmtrf/xqyxy4/xYgUEzRwbTNbxYsgKwAdpREbb/n7MxRCGosoqrJgY2RTrqmSKM/b34uaaONL9N/kaJ2bMQrK4quq34xe9PrnMWo6GwBx9IP7WpNVEQXYKMiKt5wymjZMuz2fL3FXT5MqQzqiBdg4yYptBZHdRThOEfO/EMCNdtFaw26+IhKdMort4UiC1pZ1zwH38eQNIdYGNWcAOWLQ1K9l1YbBHEyXQrntbt7harrCcJXhQba3n7mL28+8jMuLczx49x4ePXwbT58+QdGGJg3TvuKNN97AG6+/hRgHbLLi6PgYp9dOcXzrBsZxRCkLpotz6H5GuLzAqCw4RApundzCAGDZT5j2kxXTa96QTfC4J0vtGWixKj7y4gvIAJZmz0gMCAMwtoymgqkUTMJ13cfccE+YimbmlBBgWSZsxgHLfo+rqz32J3ucP73A+dEWj997jNPrJ0h5wFIKSlOkPBwU6X/w6zsqSO7fv48f/dEfxTvvvIPr16/je77ne/BzP/dz+DN/5s8AAP7JP/knCCHgh3/4h99njOavGCP+zb/5N/jxH/9xvPLKKzg+PsaP/diP4e/9vb/3nbyN/hLzshAfqUB6nDwLCPOksDloCIL5mw3LgP74qW/+9k8wGWYMBlMKjFvCDSFGASxcr3ta2IhEUsImZ3busgYjIbrrJ6v2rmCwzcbMHwEcHJTimQb2ANvh7pWzd2Yu20IjSSzExINEnB+jSDlZh7Rmmrj5VOtupPI+Mhjn8jZ/tU6nlorj0xM6Ki7eLducuTbovPD7zSjIR0rNO2iR9ecH6SZCxViD3jk05/KB3bsqYWQ163O/TiFEc61Ug/utq0Qw47zWIX8oeQrJLaW9wwP9MyCKMW2wGUcsS8Vud4UQmPQZQzIIn51kDIJhCN13pTWYpb7xD+zAUbBg80MtxYhxyLwPtWFICQCLq6jsxEIY+J7tvbl7pgaYWZdyHGMwd4BAU0CsFcDAmX5jfghs/Q3DgHmee6q0SECbly4ZFRsDOXrjc/0hZZRaMU97OthGHxsp0NBRBRGY0zEYY16bqYl8tGSITlhVO77g3QE4JUbXN7Mxh1iKtDoRcr22qpXZUsqi6zB1VgwdhAKtcNQUCvk+7KxBdVNp3ffGx0le3NRaIBDOzyFrrpOPpOIaV++vUlfir2dEOUoUA4sXIrMcyy2V68gekRVVkZXH4w6b2n+/f43zJvjNxXx41isgUCvCiVBIN0GsVohAooVqeoAi90dHa0IQU7tUkhN99CK+BuhyK6BasO8rQM+Y8uKck5vWk6KDIxzwNOjYrx1gjRAoTHB5b2v2PUpOHr8CQEgI1Vxeq7nFCqzwGfr4D14w2X7qjRudqG0fbP6zAdHQUdYjMVNIW5utNsyLmpwXUJ2w2Qx48YXncOP6Fo8eP8KjJ49webXH1X6CWm6TaMM0Aft5wsP3HkJej3bNGl545hpefuElPB0zglZAIlqIePbOs6i14eLJU1zs9oywgCVz++Lz4gyGcCHgaNzi9o1n+P6EisKQAhoWhFEQa0QsQKwNKQpR/rYgpEglqDkIiwjXRG1YrhK0VhQJiPkhDfNU0YpLt63RzXQWPsyJ+oNe/4d9SP7/8XIfkv/P//v/gWHImFs1FjPHJt31Vb3r8TgivjzJMxj5K4h3YgInKwLo4wjvnn12Hw12TMH8MDps7RCtWkVPdMFTUZsF1altRtosuC2uRDe/HQq3Imckd62VmQBYZZ+qNJfqAXsHmxihZvpQ1MruIpqJDtRSd5uSbGSbCuFWMd+ElYSkbjxhv4sZNYJbN2/h8uoCu2mH5jQFRd+EY7JNKoRONq2NfBX3aXASorsP+giAHjH0aQm6Fo0SyMPZTcyIEEgf04gA8zxb/gcPPR/rda6FXSiXJUKrZWckBk6FyIAuPzSV3XmIAUFivxcpJXP7BFG5PhZQGwW4ystMz+za+3UQiTg9PiXJd+GIcZ5nzErlSoiJbH1diyUnYzZH9LCOVNjZr0VazpmHzlSw2++w3Ww7z722QhvtYgqziz2aKkdahhw0Q3RCDMjm13N1dWXFXOpmex6SRsInwwWrjRD204SjzZYOxWg0CzTESKJxKYyj5agDi5p1jZdS8M2u084fck+fZEnPPOzMIlvIFfBuu5S1kKBkGBzVKrkKThiH7SMume++IiHYzzJswStboN9rT72GYPX+cATBHqEQEkcvPk6CrlJv40+5zJlj54rBCOJe6HRUMxA5wDcVPbC1QGRkRRz8kI9iWVq+clI+IPquxV7r5M4VNeH32X5oGypRr2quxRxlQtDHoNrXMFGJ1UAMlvllvjGB98A/Z3RvpFb6PQfQfZr82gN2AFtT2mzsyLduhVFbR7fSXM5sjat7urifjH3mUhYr2MgFpDdOQ0oRg5gjd6mYZ65hxYqo0SxNkYeM84tLXF7ucHFxgXmecXl5iadPn+L8/LxzZbLQjLJpw5iAz3/2s9hdXOLhwweo2hCGiFdeeQXP3X0BX/6d1/ALv/RrVB0G7h1+upHjFi2WgXvGEBSnJ8d0sUYgeTcGsEIx2oUpk5ZaUXWGqmdZcb/MymKkoiAYkToEQXNCdfWqSCDJSNPRRtwhIELw3oNH/+f5kPxf4TUtO9Q2A2qBVQKkINCl9FaD14hV/zd7VATQWp4s4TVdMsA6Pgl9sTphL5pEEw0WfmebBwDCxOw+JKRefGhtNhqyZFpDHOBE0FpBh1MeMilmDMMIsYeAnhGpd4z+kMcoJnW2TVHYBa6b+WJfFzornhwb5sOEEBEB+gJohIIcErrn26jE2jWeu8FgVXZsl5cXPNQaR1i1cnRjHEFL5bVNoa3mVFGMNGuH3zzPqK0hpcFUPUwEdpZ/Cpy1S2Ja72Jkz+gmR0GM4U8JpXYCmplWmU24+N7cuzReS4kRYx6xGTe4urrCUljQLKr9/gPCqHBdibvFfDqoePDEZmH6pdBPxY2berFp6BvXjdiGwM02DwMiyBGqVtikmDAMo6Xthk40rbViXhb7nGbUFwF0t+CEcRgQjwTXyjEEgmUxm2k7GJq5kNbjY0zT3IvQLvsFR0NMTQVCSqZIi1jKgrwbuxopGDcKSl4OwPTanBKGcWRRWGdycQKVDBCOf7zT9PGg2L0vptgKgQdWscNYZJWkwtZX7RuwF4cVIaEfYh5o2SXcADNN+mGrRi6knwcJxzxknJzK3sNk31027K61HBX7e/SMKCeHiiGNVIwopK4jKV6EhmajqhosvKxyrDxf7RCMc9azrFpDaXsIxIzCOIJzhUuzcQ5g19heMQiKFnjhBwh0WrpR3fs5KyvPrhfCVozUpght9YIJwToSR4IhaGZcRiTYvGiCQpcKNLofk5tnyHZjlENtrTv9tmp7mt13PyC1CYBmzsDSUUg+DQL3X1F7flMKXUnWZrNksPvUvaccGbMCEhBEgRG2wSIaQBPFri58FlLAJkYiJI3p1TFnZrjY2hvGEQ3AuBkQgxupEYl5+vQpLi7Osbu8xMXFFaaZcvmvfv1NfObTH0PLbAReeOEFnBxfx/nTS7z21dfQSmGKMdD5STGK7UULxPaEqoJ9VVw+fM+4s27CR+SrVe6DMVl4KECSrDSo8n06ss3myswse1GOLt8XS/xtEpCGDLXiTcLK+/pWrw90QeJsb+YGKc2kACIAra4yMuBgQfMhTMkDf3hT4ChCWjeKpjSlcce9AFhuADehYPLfZp1OByrEZo9mQsTgtQPTMIdF7eCCNIPMqdiOImYghQ6P2q5mxQiwGUekGJCDHng4gA61It1CGodVuxUAtXGm7kRINy4qpfbxFosz1/KjQ+wLGOwnjTJLR2PWMCuxjg22WQM+5+S1EcSQOqoj2pBiQkomdWyNI5zAkztqRBp4r9TVQTFww/JusW+iZp9vRWctpRvjxRAJU5gxggZBCyQJBiHR8ez8AtM0I+XcHX/dk6VZ8qyvuf1MkhcC+ShRAq+LKmCH9GFH14w02ZQ6fYFgP+17J53N5Vcgtl4i1FAuznRXfxEWABE5mhtjI+SfrMN03kcKAUNOqJGo1jiOHXUIIhCDx1OiFbSvta60sRGCd6spDowQiBG5NcS479wJ7z4BIISRa8BkwCQ507UUGRjHjKrNwi7XA7vB4H7wd9ZaMVYSzV0eT9K5jUMMqdIgWOYZc1loNAiiQE05yoKqWdjzQZrNE6fW1scETI3WTiDW5oTK0Neto1E8bH226vNEGAwG82DhxfMDjtdS+6HdrKhujQW5d+opRYxx5IX3QDox1ZHN8f3Z6tudFQX1kDho5FDzWOyfbZpLbw6SH9CG8sJQFha8B5iyrenOJemFpPG0IMjmS+Hr3gmntZgXhzVlVAcRZVqmiTLqYIWajZK5z1lBamoyf9UDLkIMHH+Ljc0dhXFEsYFFFZv4xg8a6Lrte0Y0R9teyDUqGhWKcWDsRVTFkBJKbTRpDIHZTnb3Q4xISnSCCc0moZWAWgrCOBBRWRagKTZ5NCRGcO36CU5OjjoyPO9nPHr8BPfuvYvXvv42PvGJD+NTn7yJIUaUqeCrX30ND997RGBbihVozbYiKxpbJYEea/NKRA5wA74YYChgMFRVIUFNHShQNV8YQxurUO1E9aW5TauaslD6KDCmhDCOgBV5ecw28qt49OZ9fKvXB7oggURIcLjRIMXmIwMluRPmAmFs1dJWDwNK5mJ/yCVGSFzRENR10SmkQ6kBNqsWY5/72zl4a4c6eYnr9wL4ps3buqEDqRXlbQfcE3WJILtUrbCo+dah0WW2uanCLPhtM7LDwDNpJEREBAy+sQn5F/vdjrk2sm60EuxwjTx4qd5wnkkDqvWWTbEsMwD6uZAs6lHmB7JEOEol8DyRqoCbysXgn9/IlIlqHR9NiCMsDr3a7+Ecn7Ht5eB3ehS482BCcFtqORin8aGba0OBGgpzIK018mhTT0NtcDiOXYgXEeum0G2+HXEC5acpGeIwUH5dOPC3sV3o8+xSOTfm6IxrOOfckTiSGQVi1vawIiRn+omMeejhkcUO6CAcw7lZIDea0AuOnIzvpA3LYgcJ/Ot44BA9ZOGdINBMMz8+eF7AOD+pYrPdIhkByFc/Sb7k9aQw9GdU7cDsDrigKk7t8/gz2pqRYYNCg8/dgeH4CMfgaIbjP1imElGoYGtPVTHbWnW5p6NBYsWE9kO0Qqp2wjAlmg0IRNUEglpoqrdKUTlCDEpScRTvvDkGCpHjKB+jarQRa+ScvdqB6LvJ4bjDxzIi2smfaojPoRTWnzENhqjBDuADoiwA2wsJ6xvgj9b489lNc8xZbbTHPcUZH+t9DyIoxrNQVUhjZdIO3lsIPPCioWghkO9SULpqUeGcISPHWj3kXhqtf97ax6hOWm7qDq9rIwBbAw1EfUNwQrzJbWAFCpgY30phvAI/Fua52OejdLYtBa0UjONIS4LoikhHPwNyHJBsLM2imetqGDIKHLkSRMsNO9puUG38GRARNeLaqeLs6TkePXqM3/ntr+DDL7+E7ZDw+L1zvPHGW6jS2BgL0Yx+S3n4MVDWCb0mVQ5BIFWZhRUEw5hxfHyEo+0Wl1eXuLra8Tq3iKYMSUXYQYTPvEiEgGNrEYpBonHHBm8YHQVvlCqrRFQP1MR6Tv5Brw90QUKDHo5QPLWzRiWVozX4sa+qQOKBxYOPyED1DQve4AhyGntibOdZaAOqGgQngLKoiQfEPrLPBWiE7gN0hbAbbATiMwPYQxr6HBuGYoTg2nqHMdmVxBix2Wx40ETQQhmGwrRGXoAKhjQgxGzdPICmWOrcN+5gxNOiDr1UaJu7UkVEMIwDFOjdgEPp2sDKF46K0NbfZbfJrq0XICmiE8ZcDhl7qjMPxGgdajggs7FzkU5QLPOywq22ATr64iMobsimtALNvrbbLVLOuLy45OEv6DJhh+qbSRwjSOhCSoTr0cyWmmTYZEZ7zUmktokfOnJCgZhN1tlgu4QAKZg827pkPdjSRQ7Iy9ILhZTodsgZ9QxB6ht+qTOVSTEi2jpEEOQh48hC+JrJet0/JwQWPbSkFY5qzBFYhB2UCKAtIiVBii4tBjYbOv9O08QiyQ6q0fwk2FEruUUQqOVF5RxxbbNBtc6SM3or762D9zFfiAGIWN16a0NIuRcMzUaRrZg8VALEyLLVgjQhZshn8e8SDsZkB4VxHMx52A8SsGipraJoAEbeTvIFMotBIezsnawaytlqwbzMNuJzqwEeDNk4Scs0YV4WpJSwPd4CupI23WOlqhrXhp/ZHXEDWGynlAirm9qJslXa+xOddVK1k2mZzOsEbPhyhC9V5zoRSXDSfDOEIkjg2FGVa2Vx1MG8Yuy+xER3Z5cIO++FPCcfZ/EXBx8Jiin1VIFCx1eXw9daOnHYHXoVVEt6MykSSK5cKspSGGAKYDNuECVa8WO8HjQgeH5U6+shmTJrWcgTabVCZ3LHmiFBBTRErKgoZebemGjmKM2QbYOF1KTN/sw5ARrKZkREkAc+K55szFEXkFPCmDfQqqihYMhHqEvDPBVM8x5f+b1XocuEUk3Jl9RG/tpROVUW86IcOTbjrK2pykAWQR4pWy5LwdnZGS4vLmwUz8BOTcdgYdogkU2wBIU2Q/lCwBA5PvR8rf57nA8W2CQKQJWlfPuk1g90QSIQdn3Sx79QEH53gpRDmyEw6h5aTZ8Nwxf5YOQ8EnZvxWc8KMvCnxjIXVCYlFLNo0O0G4qtHYSCroMuOYQdNFy4yU3P4JCujzmE4x3rFkW1G/tEs8VfLFwuyhr61jNOHLsRxlf7eCAEJ9itkdUp5o40+whD4oEsU/gZ1lAvGErDQovkz2BwvEvzQh9n9Jm8dfnNYHd1EqECMaxkTT90xAq2ViumUvtILWUnKSvGYezKqRCF3XDlQR9jMLUT0RGRhIvzK8KmhkCsCA+vf4oc5TDNRA0G5gPbWjW3WW44vJXmNWIbnHd7hLEbiXSGzgSDuduymA+DYpr22Oseo5mC5ZSRh8yDa1kwzwvXLhgmdnV1xeuc3CDMiK1gZ+uHkCrvcy0Flxc7jona6i2jQTEEIj+lUZbujqe8tNrvv/Nvgt1jBZ2IMfKy1a5GUAgUCOQreFYU4XByPHbTwo0JXhAG43+YNN+uqzrS5IijoWR2ygFt5TQZbcYQAeWBo/xsIQakuBacXuxDDpoArAjmIcIQIMiDIaa2f1C5RRTQvVwAFjvM88mIieZzA7TvQ7BnXEDJ8OjyY9BcLwY/rFnADCnh5PgECMBcSkc/nGwqWPOM/OfWVrFF6PcxZwZwelq451P1YZVIl/UD1QzdrOHSuqb4SmDkkhXUMWWk4EjEioTgoCh3ma9L8n2cE4Iaashmi/ye0hExXqdmBb6TtK1YrA1VGgCOHPcWs0G5/YI6LX1cHULCVF0ZafkxqqiGJPRQQkcBA5uc4koi8RGXdpWQgIodIq583kJmszGXhRwaaC/OYAWwH/jVoh2q2jWGNQYS+rWqxjuK5kMzV1q437h5DUVfwJtvvomrqytoSFApUHECgrsDHzgv+7kognFkYbuUBcuemWkNAGIzCTtFFq0qYiPSkmNEyNJ/PhCMn0J0C9Y0pcQgvWxhuC5bpwFjRUq5rwd25Mxh+nZeH+iCRCGUWNqh7s6WMac+ivBcA2kkU0ISECrc96C5YZJY9oKSHMpphh9uRgq18U4Kq7U0ORFW9Ro7W6EktVZfhPbwNpIfQwhdMQNu6aa+4OciJ4VeEmIL2NneCvBhdDdS22DpCcHI8W7wBC9GFKouwRV4dLdX94djFVeFhIA176sZMVfZveeYkFOCjgLZS1eVOHLghmDNDnaFdi+FZnp+bWrVN6vppRTsrnbIZkomqmi1WMcLstZjQs8A8a4vBKSczWSrdfQGUJw9edw5JEEIkSqUXVS02al657jOtp3XIQh9DQm0e5ikwJGYk0yjZ7dU7WTNlK0Yqa3Pp0WofiGJlR3otdNThADs9zOWeeZYrY8LgBQyNPK3uWGciDkighySagflNM8k5DYxxUZkoaIN0oDaDvwymsG7gu69sybKHvAHxLrTUEkYBcdU2mwGbWMwVXr20EqfkslaGuYyE3nxxY11pACxehj2M5oARtpcbDziCjjVlRjpPIJ44O+xEhO9sOE1cUK3inQU0JuAQ6+T6pEGvcvleGnZFxtBdnEpvEmJ0dHVhGjcqz7mMxTJnUT5e7je7LGCQOkCCsqoU07088lqhntWNDUiL3lohmKtfCLgoPMHTNKMjpwA7w9mtIoKQSxkMQQWCNCO1Dji6UTPZs/rMi9AKb1IA7i2AKCHZIIj1hCT8eLWa9GfA3+/hkb4/7Nmn/tiU6hHCaSITc7IMWKeF8zzhMvzS0OUuC6GxHHbYs/u9miLMQ/QwDGojx6h1ca7DVIqR39GKo8h+RFqt1kP9kDaJ2ghKhQRO2rszrYKeV+RBRsvcg3Y3q4NlDCvI3wFibOlVSyoaFpQtOHa9Wv4SPwQ7t+/j4cPHvYRG5uR0NeQGjcmxoQ8kA+VtxvU1jC0jBoarvYTpjJ3JZF741AhxmZwqROCVsSc6LCMbDWpIkjr/y5DQhw4shIIdFlTuaMht+L7iJ13/6f4kPxf7eVjBR8T8CG2bkrkgBSlZiAU7EADYPwDcQmgqQ8aOB5phiaQvOMujs6xICSMwJERgK5icYlpytlg19pRD3/TrszgeHsl29VK6aiASIrD+fDv13UzzW7p7ChLXHkPqxxU7b2ZpNBmWITVYv9+co7MJ8A+y6ogWDfYHJNt+DD+h10r+/tg5mbePRO2p/QyODcHDcEgzJX7Y/yPsnQvCoaCeWMhyHmAJMq3i0tHJSKNm4P0WbrEirDYGcYI2kOIc/yAZrlF4CZa5tKlrRDpUHKIq2HTOAwYhsz47xvXMS8V835m/k9kJoqS3YUAwZCyoW0V+6sd1Iy1cs4YhsHY7x6Frtjt9ri63HEdRhaMs0UFQCO222MMOa8p113eGw0e55pohi557D0UGKwwJFqxN8TNilibwUtrlmMCbr5qZNlq3W0QBJvjRwkIJqMK5snS0LqyRtQJsXYNDY3qpENbw+hIEw+BshiCEgIUASmCXI31eDD+hCDWYM+GbaoH+4HL2psArrsQ+wx+kB6qc/xgDBBISgfFo43CFnKSNLCwkCAmV1/RV4ggWNGkTU0lRMmsWiyDk65h4yFnpvE6RTRQhekF97KsGVyO2AQzCpPQeszFfr/mOgFWkKggJBsFNSP+GiLB/qMRoYP0whTg9WLHXnvRK2BDsiwLyeeHjsDC5qgjgU2Nv2P7kxUAroDz398Kk6Fb40iJqjZAC8wDowLVTSOt0Cilj3w9gTulZPtoYNEd2BzNZYHujJ+hTLKWxDFDygPaxMKfox76zATLgSllQZk5Ek0pcjRkazhFjjUCrECxc8FzYFLOHGPYXoSkQPOAUT5Xyc6Ub+bVLa2gCuNPahAgRAQEjO0Iz7/4Ip599g6enD3Fk6dn2O0nLBPdkt1pHKpIKWB7fIyj7YhxSFgKbfCvwoIwDsjTHrv9hZFuG6BUksbQeBVEEGpB04pQFsQ8svgKAYONBEWA5mhzO3g+Vc1R2eXr6M0EVNHkD4HK5n2wLNYNpqkZiPkszw5nh2VTSraLsUNxQhl/Ruvytmgbmcdo11YRA4Doh/b6PoIAOeaOTBC9oFWzWpUM6zxcoqhBetgazZUqRCJizHZ62ianyspUVsKovzrkbtUqDcG0Oz3292jWzA7MpxAwDANEAqZpb+iajZ2MAKa+wQAYhpF2zwvnrMW66HKwgXv3TlWMcS3M9U8Muck5W6cqBlnSKTMPI27kof+dRgVKMSWCKUO8K7ExiQe0lVKRjPQZgplMNf7uNJjlv5FaW6VxmftMEEJoKM0ySwJ6oq7PemtrmBplyTlvsdtf2FgmkndgHSgAJmIGEo890XTIA462R8gj1SfzMhMuF5euUj4I0EKaa5FreRwzTk+OsSwkiZZlMVdidvXuiuqZTf3gCc5DMtdUaWi62Ee2Ejiu16QalB5TwOIoio3eovoozv40cuRSytTHGD5q6UCtuhlhABDsmmJF3Bo30uhwPvi82IJHtMDEIAcjFysAJJBj0+za92so0hVsh7wFfy7UJJ6xS6P5+/a7fX9OYkcIWZDISAtxbw68zmfImFe5zn+wjtveMq9fRAIPMC/GVGHjWDX55DqmkrZyisIhP0DJJwlKgr5Lzlel3IHSzB4SCSz6HKHw0Q/3K+5ffNxMnq6KoNESdTme9gZjGKS7vvq1agCGwa3f+f4Zvgh7bzyYFBxZ2JYLH5PN+wkPHjzE5eXOFF8Kid4MBEOY6SwjRkSdFoZXhijcb0Pov1cr1SANwH7a4/Gj97jf1IpmMRTV0CUffdJJWDAMCTXWzmG72u1o/mdcPkpbFxyNI06Pjjv5OifBVBRaSUZu1iD7/jYMA/Z7y96yZ0V83xGPCgHErk8IYtwovsaYMe33yKcnyJsRz9y5g2mifB6quLq8xFJL375zjjg+OcaYQn/Ox3FGKUxVL/MppmmPs4tzTNNi90Ks+BfbP+y8KAuLExmAlGCkLLO98CaDz3uICdFk5kGY8eeUS/aBfwhGNiEmupMqevcj/nDYhkBCnXd66Ae6a6P5EPqmCoP3vIKlkqI/yFZspODQ9mFXSchcfIOxjqFDw+JMd9sQFGbFbQszRlMCxA4R+iYLk32u3SXWTQhWRFUnSnmn6JLn2heGd1IS6VIKVSxlMvKuvefqFa13cnTpHMfR3BFTh2XZUfH9q12ETc6IgQery21rrSxgfKe2hbvO26W/f5eUxSEilGgOnAY/2+9ywyQBoKWSCGlW1CSNGX9HABv2Q0HSoJuBpRQpUuo8FJo5jWnsvJv1LBSMecR4dIzLy0tM84TB3UdroYFbI6l0O2wIsTcFJ3YRx0dH2B4fY7/f9yA5ARA0oBWgNXIu/B7Z6mbntMx49PghAO88jHyq5JhME8P0YiXCk3Oyg902/lr7yMQPQmmreaAEscRXc/fNmbLYQM+ZGCISIjw52g/jpdJGe7MZEWLAPE+YJ6pDhmHoc/Nm69OfAy+mVVjwVZgRl1AFIOrcERaIi4/AYnKfQ6BVuo9C+7X0cSafezoliF1DJ5SLxH7Ya1NodYmzFVHV5fNMotbMRqFU/nerXBBN1X6/7xBqI2DtpPloxFoitM3kpeZ/oVy3aCTvelhnMz5baMGapjXviEUqD+heeOpKZvVDvvMJOgrJ98yRBAsxetjMUDVivnmdiu1XrbbO0xGYd2JlgeP7jnuTQCObB/++1rAZHB3RPqro2UeG+LbaMAwDch7xzr13cbXbcVRgnIUQA4ZAtCG2tpLSTVXiiBxsz5ZGlBdSkUMwGbyPs614N9dqNC+3SWpVUcxzwHa7ISJjRNlda5AkWJaC/X6HZT/jdLPBc8/exem1E8SUOMoG12eIbvfg3Cz+k1Pk6FYb6HhLdWSMAZIz30uwUVAymXpzhV/DuKH8+GizMYPM4FU/rl+7xnRiKN2XG2X2pLXx859EmiQuc4PWE4gA13fnePT4DI8ePWVkSS/gYeozjl3QGpZ5hqhiyAPP0UVhy9uKFOez8XzMMRrqXpCESFatfxgKkkwILgLWMTUM4wA/S4sCUgpVDofdiUmjqLJQtLIY1GmzRWGnJAEHLqHGGTC/gl5o2KL32PkYWIXDo8uh0GDy4MCujAmT2tvJmKKR+xSqLCB8tKRRHSyBt2eUKkdbC4qy0B2xWkcabOPhQufm5Y6z3nmp+UBwnug22hwzLJVSvGiFUmvF0opjN2eqlQx3vri5O6G1VRobSfAAvWpqCtvQ7D1JEETbOB1lSUaYJVGMP78UQZkXBKFqgR2gdMQrCMwXwroznlBMJQ7BDOJsfgt05ZJv7uPxaA8hr3Mx0h1n4OyYY0y4ODvHUgpSV6S4zT2N2442WxwfHeHpk6dmNAWM2xHXb95k5s009WgDD/Wad1TDqHV5zWH8sD7ArTXE6LwRWMAci+GT66ddnRCTpRLbNWZRvI4oxIpejudc7il20BBmV4DE4Rg7WVKVWTdaOQKCh5PZwXHzxg3Mc8F77z3CshTQIbV1nkzTiiGbIzHBGjtg2HXHgS65pVXKWZt30SzGmzYWJkokx1FIf7mJYYiUcNaF/gwa6MvA4EnbdBfQb0ECiX6NaGjV2gsSFoX1fZL+Tgxv1giJmPomuKbYChDpHA+A3IFOGNcGVQtZHChFlejoDX9PtHvneUUA+VfJ0lT9Xvq6kMCgPZ51a1HmRYMjfQEBS126DDrFDFgxpeDaE+NWUIlWeajHaGokf9bdjgAdeXRTshyNpwd0BK8ecEc4Zjrgc0CxPT7Chz/yMt5++x08fnqGmAdTCM2m8EPfxxqAmGht7iPGYJ4njOsS1ErZNWKApAQtFSkNGFPCfr+3cXxl1pgqUjKmtghU6Qw97Sby4oJAa8HFxTnGzYgXPvoyxpiwGUYMw9BHo9lHTgBUGqqNFAV02Y4pogZB0oCmXBfzsnQpPMeDicRvQzi9gW6B8Rm1VIQhIRaBIvbCESIYoPAU7e6SG2kZ0FrDaChlCAVoPPJTjjg5vYZnbt/Cw3sPcH6166pFV80pCpPOg0CrYm4TeSqB+T1iXJEAjosCTUyQzJekIWII5nnyvif29399oAuSFJN5bHjSbkOdPFWKRJ0e6mR5E5x/8vtDP+lXdnXTRtlUK4iwbA9nHJu5lqKtpMzG382zyeVs3CTdTIwPDmWXaocOWqPJVDbiECIPP4Ely6JzYg6RGAFQtCGCRjtcgNIt2VVDLwyoBIp0ogUXS1NzcuXjwwe0qIXF2QZg3U8UWSV9QuVIE1MllNIzMtgIeHiexd4fhA46ApTs/ypWuWwzvSDJqQlHR0cAOCpaxyGAt1peCIr9DLGsHNRqvJMKSamjO7TOJ7cn5wEhULpYG99LjgHH260ZaRFx8A6myxuh2F2do1R6vEgMqMZS93Ee1xDX28npKS6vdlxjIeDx2TmOtlsjn64x6Muy2JjIzNlMygmsxbPDNITsXSXCzpNjHsoPY0rYDmP/Woi51BpaE4JgSAE1ABN4UCTJLKaEgXjTnoV5NNdRaSYHtplwq6WngQIVKQlyFETRrvhxaSdRBSHgrhVlVkhyoNu6KTNk4/fxWdlPeys6Qu/Gk4S++XrBtfImPNeEJoRNxApf820JQAyJPBk4ydi8Jl15IeYXEgJatABGQx0B7VJ1qooEKQZsxw2VXNl5J7CDvWK/3+Ggnjwgv6odSLwGAjGJ8rreDscvECaXo0vpDZlF/xForWJaXOXCl7tAAyxSxPY8BYBKorxbr3c+iNn3e8K4o0/FitIopsyw9+UISYy2DwrH4+2AYAvumkTDRLqjqBecfEc0sHz+peexORoxd2UjsNlsIcKx22azgYhgVybM89QVRCAQ10ee3J/tfAgMqxzzgKaUz+8uL7C/vMR+mtDQUJTF7VILauWeG4+PcHl5ATd7PD4+wksfegnXr1/HJo2Iarwq+10xkauxzAWtAdtxXPfbyEDBamNntVHz0dGRIV8NpRZy2MzrpkYTSIggIhFJjEzjdkk6oJjnxWwmOErU1jAOI1yOvcyLKa64alIaKQKpjc9HK7h2/RTbzYjH7z3Bo0dPcDXPRO0kcp9EMWUlkXWoMPNHBAlgoyGC7OOZGMi3koAkwYIOY/eU+VavD3RBAjvYtRKuorES4SsPTaMcK7zvIfH+ypUIPq4YhnEdoQgg2rozHcmrBq1Wm7XJ+8lJgBl1ZdsMWqOVrj+kpXZYNQyZc1MxiFrXrgJqFbONMsQgV+/exVKCW+/EDDIz4lY84LdUODF1HZk4K1ziilS4ZDcbLOcISc65HwCUlS5EdRChyQs62EZ9AIkD3ULekY9OvGzc6B06DyEgxITTa9cRgmB/dUXJtQMZoojZkKi6IGpCsE2tk2Xt5zq5zwvPZTEESMVQEoVat5yEaAzJz+CIRQOGYbS5fuvjEYhgM+b1Z3SUxTdXwdVuj9YaNuNoCBy/b5lnnJWCpTYMKSCPA8pSkGLAuBmx3y+ANiRhhk3ITqpWc9XlzXTvhJwjloWQf5NVGdK5IY19b53m7peRk5njNQXaKrH0UMhaqh3sRAfdpM15NLzHimJzchGSuMdhhDbg/PzcpN2E08k/4NgSwTKbzR4+dF4WKG9XonvVlCEp0S6fCoCG2BTwtF1IHw+4csk5EusTbtfM/oBSWVPEpYDQzGNFtLsGi6ReCDRXH7XGxsQ64SOgKxTyMBD+t7VWC31/ogRsN9temPdQOdsP/H17QUUyvJF07drQNMyLfV47sZNXnJBtIXHBTA8dAV7VQ4apKwCX1fbrUR1LQa1m/mUj7BiI+ChCD26U1gAfpTriGhKGzYicMqZpwjLPlnDsmAsPpyEGqKZe5C8LOWI5Z9t7yEcLCjzzzO1+v6LtF57JNeSMGAIu93tc7a8wLxM9eAzt5fcBi5Gqp2VmoRwUimpS1S2Oj4+wTHs8vH8f+/3enhUxBMf29ZRwc7MB0Mx/BKhF8fTJOa7iDkPKGNIIkYjaGmZrmvb7HYvVzbZzdxzJzILeZB0iYCEqxpwhQXrC+FyX3siKCNTCN32vdG7XkG0MdbAPCYhSDTEBR4L9fqIhW2tQragldRVhaRnzsiCPEc+9cIQbN2/jzXfu4enTc6Z/K4vVGivqMkEW4xIKOZhFBDEZhUFpR0F+VsNoZNhkycvvxzR//9cHuiAppZDVLHbzkiCqz8YBLyCga1dBR03rtquYpTVVAj2kDuxFAg6gx+okUekbinoWRgjdzdWOdkNcQDWLGRqR7R87nIr+3rx7YzGywvXaUzidz+DUQdVV3hpjRMjoybqwA0ns887zwm4mJcu9aGSY20LuYxDAZuJmvZ9yh9kXC5aizwv70myFVLOOFvCxiBHkLCNI5/WhgUHDLj0OIWDINPQKqpgu95yzl4ZWC0cM6uMF69rM+jwYMuTcQhIRBS7vbYU8g/79BCggVuW3WjGORBXUFg35NamPedzfISUWuNO8MBAM7BTFslOCQ+Rq2Txq7pYCaG2Yp4mHSB5xeu0apmnCZJyWYtLkFCJiSEghdoQjDcIDvRG9C43319ObAwLHKVDs59ki1Znfs0wzEARHR1ukmDAvM4O1miJEoNaF48mY6RHjs+hWkZHR03ytx+r+CcoRQWkNjx8/RUzJxnzBkDpm5oiQS0QkQAwZXzN8QqAKp68NYVBeTAmbDT0OtLJSdLKhTQlMsu0j2LoWOjEDaKYkaoaQ8XCnAdWAWgr2M83MKOUHkhUmdAF2j1oYdG+HS2vsWNUi4a1Z4XgKa3PSBCltkFJEKZSpOvG9YU0FdgIyVLiHWeEsIN+jOaJ42EwdNEBe2NuDuxYlhmh5Md2seekaVlWEBsAKIt+LggAprKPDHARi40h+Vpgcl+u8ThOW3a6rNojCCBDQ+ULjuO3j42wmhfM8d2JxygmtMb+lE/Qbr68XcNPM+yVAL6gjvYKhurqe1tYgS0FQQdbY9/sWlK7btn7z5gjPv/Qyrs7O8Pbbb7EYDKGrLyEBWp3EPkC19iJ10YJpmRF0sr1P+9rn3qQ4u4i4ceOGjfS1N4Mheq6V0QVg90rQ87hKqwiI8Ns15gRNACpJ5wBHJQCzolJbfXRUGW/CRpLj7WHcEg1qTJiPQh7ZtCyoCJiXgqurHQQNR6dH+PDwIp4+vcDb79zDfr8nGlYVIhVAgNaAuVUM40CBh/LzLQEIiCZQIPLsBqQpRfO8+davD3RBEpTk0GoHezFTLACgC7HajIsHQyeXqqczVtS29AdhKquTKw9WXsTW1s6OShWX6lLyKUYOO3z5+KeWVZIqBgF6lxUCUJU3kXu+jXckrZCquAQXJo1lJ5aMxOvoSvB8GPXCCAZjF7gjKqtt66T1ADUKsMwPP6TExhXAtMw2W2ZREY0B3hA68dYREYcOQ+AhGmJCjgF1LijLshqcgfNk50S01rDf7fp1KWbaxY9gqBRcZeGzcXJoaEbE3ye+qaAZYRl8fyH0+wdQ/QIAGgRFaazmvh4SHL5lQbEdRkgIWJZCx1SxQtXXgimyeOBFSAT5CO5/oJ5jw0OxWYFbSgEaiy6rpoAoqKioc7X3as6Z9ntaIwGydQSAo0VOHilL9+tVW0NICZtxg5PjE46ISoO2hWOjQLRFgpAoFQSi1plbEdI6AsEyOCWSb1VAt00h3Cx2aEPUYhLi+2zMO5oYDK00+WorRp6E/z5ex1obLi4uLTz7/b1VR6da6/LPdYwVQXvy2J/VZONEORgBxZQxqKBPT2zbqEqFWkor+bOaw6xaAXhoFCgGEK71gqNvJCj7KCcI+QEh0EGYTY7L6WEcKDOcK0CxQgFYP5+IUKVhhZE2sPFpa2Nh78C4NIoy8xD22Am3secToiAvJPQmhHEG/PtgEtpWix2klm9Tvfmg+kTUOS4ZPVjYnzNDKqDcletSMOTcO3RVpdOz7afiY1LwupS2cv5gnim98JNVOUW31WKImo2YbK3x8xv6B47Mw0Lp+/G1a/hwinjr7beg84IwjM6MggYaTEpjA5PiWrxVpVjAEeqYzATO1tJ+d4WzIDg5PkbKGSoWU2L3k/u5IJkiUGxsHc2KPlCshdZoSzAOGS0EVGuknKdDNYsXMrwmXXVl/+RIBVs1rpTY2RTSDIVgMzZst4ONq/dIWbDdDLj7zE288dbbuP/gfkdJkzVGMQraPGFe9kinxxg3R3RiFuab5ZapggpETEYb9X87rw90QVLVOm0BKIVrK+N8seIimaKETNG+iEWEfAiXW4kHQblShJWrB/QdWhuzKBCMA7M4qqkSfMat2lDaAjf9YRe95nR4qFatAHwkY30ItGGazZE1kG3PDpObQIxGmLIxizWb2C8LxDw3YJAew5Z4MFYVoAoI3/I9hQDzTcioxD5oBW4/5lDS63uZzyRFVltiKMgvqR5QZTJCTpWpAQO5GzBYX+xBgo1tFpttAiZptYMnBOkbAUmGPo7i5l9dfWAk4W6Sp0QPvDt3PxVPS02J76mUBVUKYnMugHedAmmCkirastAUypULFqvdiwmsiiqxA1WhWMsvI95VclQePXrMrsE2nRTd2deInhBMjnZoQNBon5GkNXbANPpyRr+CPhYr2qMIKVgGC2fbKWbksdma90LNzZxWVECFPCWigK2PxQTRkJQGRAAhQjX00Ypnx2gTLJUI4jC4Z4fxPRo389V1FvBZ/bIsyInd1TxNPPQNhSDAwgLJ+VEw2XywTTik2P1OVBXzNPfxZMoDBHRBpcxe+0HuDUnTRg8LK8RS4iHMwsgMxFw5F4lgdHRWxBxs2SRQ6l8NTWNh3Ww00q994Gd3PhIAU/MYGiYrKmF1ad8rVJiNIxZz4c8eSZ6NVu/259XUJWkcDQEQJEcRVRmaFqTz8fwVGp+7EGiGqMGVQD76M78abd0hNeRgLqkkbg45I4WItjBra6lMmI4p9T1RTdUkpjaKllEEJ1+bH1AIsXtbeFilNoUW7Q2EopEPFwNCTv291EJEtpUKEUWwz3FycoKPf/TjeHD/AZ7u9lgqh/5+JnihpLDCCIKUBiuyqz3dgURl5RqtteLy/By1zLh54wa9h4ScxwbpfB0T2sIF9QDR46BES/2++OeFGFnd9u1SLBdHArabwUbO6sA7mzNlirR4Q6pEmPIwAjbGrDVgaQ2bYWDDVJhLc3pyihefex5fe+01nD09h0K6EV4K7MzOzs6wnydsj44QTYbdyoJFG3KMSJKx+iZ969cHuiBx5jXzLdjdlMrMCEmBFrYAPNtChQoFJznCIUIY3BcTUpSuVohBkHJEaOwMiuXFkIi3KmxgxYIEmHMmzckcJo6BWnh/aJy8Wqobt3EBRaHkK6Shz0/FcFdHPdyITYG+WYSUkB3VUKIZKWUMeaCSQH30ZE6VzcY5tknSnZFGR6Lo/Juq7DqB1tMx18PXZpnCufxm3EIkEMVZqsH1YjLbgBiHju74fSvq6ZK2wdi1VDQ0CQgJHA8JZX3JrwcMnWjaR2B+CMGQhCC581bo/VIoS6VlKQAnNQPAmi1yaCmeUsI8TTbrpxGYe2HQoMrt4T3crHRnXIRgii12LSkPaKF135ll+SZX0GIkPaFia55nqIXlhSxdnq6cw4GyYosHt7VXGzfjIWfzKQA3B0P4FMDpyQnyMJBktywodVn5MIlrI6Zo4xf6nDhpsS/1EFG1MfPH1gR5oGqjRW6cKZlXh8KQRxrJlVpZiNtagDnA1mo8jBgxDAOdOL3bxTruYQHmKrbGRkQTN35wnWttgGUbVa3QybrlZk6ZxmFJmV0c5dg+RjEuUhOkkAwFocMvEnpqd+3jX667fJCT1GqFtmp8mmheSFyXviapjACaePEhGPNKwPev80wWHwg7YZ7r0VK2A8m4gpXfFGNA0dIJtq2tBFs6JxO1dRXLCvTYf/v+qLCf3yzziAVoEeOfKIvRpiwOonXGmCZMV1dIR0fYjAMgGbtpYvh3IEk2g2oqsee81Ir9PLOZEJPnw7ybDOVmVIURJZuhbwoUk9R7wnOtFSElFqNS6Eyb4wGfRrG0ipgCnrv7LPLjp3j4+BG671RVk03bWLEx1PTo+BhzWTBNE4sVcxVWLnQ+w7Vif3GG/TLhzq1bONoeG6pmrsQARKOhXjD1W0VExDjYKNxQcgkBCa5rG9gwFAsRVSCHaK2XNRHtQJYL4/ZJJOm7NWgtNjUwRAkkjiMGLGWx51swbCKeGe/g6PgY777zLt56603M+wlFC2oQSARCGqAasJ8m7PaXePb2LSAETPPMhnUbcDRuIPL+CcLv9/pAFyQN2omTThZNkTMridEcCgnpp4MK0SWXvjCgihxoq+5dG/8JXQrl0kEgIGYrSMyfxJ94/jzC/h7I5SgG0RaXbbIgQTQynAjDAEOEgBwPxsnY5mEz7P5+rYMiMhGRxBxDA7vjvBlZQddqiiIx2I3vpeerhQiJZqIm5Ik4JEvnUT5fzUhwIQhVRdWUK+ZcCDD35+joGAAwTzZyERaJfC6MN3NwTUSoaBIxjwcrTtTva4idaJlyhtZmRmC2QaijRgluZNXsQBFjeBMd4iGUzJStGMzs3S4RldWYKMSIcRiwGTdAM6WKdetNm815k3X3QIRChOhFKbPhK7F3ewgeIpj8Dhp5eS1GfPTDTc3M5TSQNFTMSMyup6cbQ10BY7HuNrIp1uGUWoCYyGcRFrOlCFSNhDdNcEJfM0WOqiKrF3M0vuIo0B2PzelXGwubWlFKQwbn5RDFUuvB5rgOXIKFAapUSPIChxehNsU2D+jwnCEfq4nVanQYU+hFYCkFYgTkpcy961R15U82V1COTBQEdyQIQk4YRj6n8zR1fpMYX0BM9NSswXA+F+8v/6cs3Hjd/8XRqiaANjqqjil1FSDsJwQ7YEIQqPga5XoexhFBRuxNTeKoY0qJKg0jNlofT8g/AKFpN8oLQVAXUyslHlckimofdXWFmD8L0b1vFtoEwLpsBI5P7LmNZkmAxMO9mcINtqfGSK7aeHOD+WrGfr9DyxXjdoMQI+ZphirVNby3/NwqAh+v8dkgMhxjQgJ5Sk78FBF6UIWAYRzw4N4ZdldXiDGhVsV4tEEYApaFe1seNwixWNEi9gyRB3W5nyCNooZbN27h0dlTzLVA7AF1FM+RuhAjbl47xbTbY9rveT1bo2lkM9uIJMhxQAgB+2mGQLDdbt+PygnoF9OU3idmSAilAlOsMVYollI59rD1RfWbPUPG6YLSTyZERUhm7GdnB7palBEPagZupdizoiBh2praaqq2shScnh7j2vYjuHFyjFdf/RoeXTxFAAscrQXL0nD9xjWknPHwvSeQWvDM7VuIUXB1tUeZq8nMv/XrA12QeKcSU+h5M24ww8LWNhCD8dV0+aJcCCpqm6SZC5nVuz8IAPXfLsEKieiGz4h9o1Sgs6JjJAM5hdwPOvIyYl9ARCZIAnIZWIyhZ3OQEEvpoT/kItYVSUAcpHfwfZNsLISSdWlLq+yAJ0KyBhz3wk2iQZJGaG1KR9EWm1XOBsmqb6IG7ZtUMiXrDEEp5VzosaEQg7tZdOXIh5hdn3mSNOmcFhqoaZdgOvqAwBm+F3HLzAIHpu7wKzPPE3KmbbOT60iaZEellhILEPpNid0YlBwkGwAggIdc8FlxU0z7PTyivhoqJMZNgGAtaJyYhmwSUR4WnQdTG6aZpmGrg2Xo90OtWFC2RXAL/tpqdzhsYGpoCOwWO7IuAokBEYBWM9QKglpYH1QBTY2GAckIij2MzXhDEgRIDGwszaokYb6Kr30fV9GkjteyLAVLqXb1zEvHQhyDBORE5+JaqbpBrShwXpNxXQqhaD8Y+yEZpJP3+njP0RehXJiFVQGamMxcIGrR70pFTkSwZ4fv3R4mpJQokYzBukRTrljhyWeDV14E3bW5ulLOu1eTY0trTIC1DT1GgTZDQcBrHO2ghSEMAlPJiUDy0BOtBYKUBwxQlKsd/zs698R+f4hwVZWjd1XerzLjeGg9VIlukANUC91HK6SvK6ZMm7u0Gj8NavC/7aHw/Bnz+4Chzc0CKWvDflqQ6gG5NkYsrWF/dtGbKj63meqvZvtdYJM35A08Z6pWcl0kkAtSl9J9XcizaKgA8niEJ08vUC4voedXyEOGDMy5cmkzxwbm1aHkhUnoUALvoQAxEHVYmmcfgR1+ACRFXE47xBSx2YzQWjEXjpyhMFUkJcuOQFxc7LC/vML9+R5OT05x7fr13uyyQAmISRDUDe7854ihxmJcpmYu0wFpGBjIWUoP0mQTCAs+ha1bi1SpipwiqgQEZcPpadedTMyFY88s98KWCupS0NqC5+48g9s3ruNr3/gG3n7nXewXkpu1Kp4+eophM+Lk5BgaFzx8fIYUA+5cvwkBsN/t/4dn+De/PtAFSQqcVwaQw+BdHdRuDmUuEJ9zKw7Y+ea9YS6VhDaFRUIrqC6V65W78REOyKsKh3ht9plTn436nNU3Mz9uXSkQwE3dZ8pBvdihkUz1zcw602abMYSxzzEG44j47J/vY5mpHnG0w5Ue0ZAin8c2HwF4sRV8JGRSYPWH09jSsM4YDJFrtUED3UK1WefQbH6OFXlwvk63xw4RYoFzXr0X39xhxQgAacG4KGYSJnbFGzfAGFlE1lgwTVPvMP06AEC1qtzHJhL54CcNtiF7ocptshTYNWeX7AgVxBjxCrLFO6EVEDTUaj8/S19b0YpWX4s+LmstAnDbev5sSgT53yTSGZtDYL/LagTjmhBcaTR/Ei8UgGBdus9rY+zRrnTjrWoooidO99rDYP8AQ4uhWlFn25AN3eL14PtJIfVniVECSzeXU+G8PaoawgLkZL40lYqUpsZHMhjeXVV9TdtubddhtaR2sq8TRmPMqOBmjWTk0OYYhklUPWp+mq0AsmvTChKoMBrHDWqld4y2ykwVpfSdh5r7afC+eGAe3w2f76INsI6TXWxCk7Ye5kpS6ziSg3Bxedkbmwj72VxRqG1BTgnZDlNxvhVgBmDsTolekS3VLQX6aJPX0DGd1ryJEzvkmhUD5mOifJ5t4UJCZKHbOJKwHQyAJ0J3zJYIkPNYjHRMJKWCnoW2ngES2jcjmw+jm0oIHaHhenWsy2z2Z9qYo625PY6GQhUnx8dot5/BgwcPgMD12gp5LI6oEumwDDG15sfCVcXQYCibn1WQZA1YpGngMtGw7aJd4ArAxdkZWm04OT7CZsxomfsrOUx7FEOsxuMjIhLLDGkV282AJgHdft32LChQqu2nRkz1PahKQUoRm2GAX0wNlB3XhQ1s32ttv6deiVyoesCfFHPn9fPKFn6/RgpXQQokU94slW7Un/nMZ3D71h185Stv4OnFI65LUcy7GRcKHF87wo2b17DfXeLtd9/FydERjo9O8O28PtAFSUwR25EZK74xwipMKy1ttGFzCnHS2JpO22ox6WhAsLFA71aFi5627sb+Bk3J3G01RCbHOjwGcAP3maDYogNsnAOwADD4GSE5+4jzXIPi/fOodWz+MJNVXphBYQ+VE5/6oQ8WLyHK+5wT576BwbrE1X4eMB6NCmCHIj0SYs+wyCmhVhY3IkCpajB/6yodl74SNo7QGM1UB+aJQRVDqQVaC9TtvQVAtardr1Vn67eulCKpS/p4jeoloe14WAszCJGAdXOG8SM43gmiANx902TGtumGENBC69dX+sbADZB5W+Zua8mdUOmHE8c+ZuMOwugxRXqrWDRAVe/GAWjsvgVZmAO0LMW4PCzyHLkJIrS71wUKHnBNrUBBQG3kTIVkc/468xo2pvUGCf26JBtTxphYnNr6YicOizpHv8YkG/P/zqVADopx6HpQaCABlIBDoBspyG1uMFWcf593pyIY82BqjgqdeZA498RfjR+mH35qm2gvUoCOvnnXGAI9XFJTQBnS1mpBKwsQA5rFD2xzZuJqM1+aSiOrcTN0xK5pteZAuqwxGNJ1SKj1IphOwaXLZTMyRuPHpBQP9gY7LG0dlFqRQkQex/7znC9Cflczi3oWI379S98YpK+fPqZWMyT0eq8RTcyRwY/uEaQH+1VOCVqJOHIturwdQLDGA0ATSnjdH4nSdUrQS1kANRbcAUnT7x+7dbHrIShdpsxCYJ498oHE+9Yag/5SRJOKeZpQ6oKTkyNIvIt3799bAzNBThYQ1tG3miOqj5AVnUMTBGiVx0U08ro2NVSSe5LUhv28kAtWCsixU9y6dR0ibtRpVgCNij/6dwTM055OuIFii9aaBeW5qm0tzEIMnbsnMZnb6WpNr+qjHxbLrTJbh+W9iSJCooigcaTLrdYQSATkmPnMWXyIGu8KWo3WYONeo0G0xpTk28/cRIoDvvGNjMePH6NpwYKKMs84v1BoK7h9+yZuXL+Op0+e4N2H7/4BJ/n6+kAXJOOwxTge2ezezGQcRod0Nn0nkoJpkuL+BzZaGCxZt9ZGglmgnpSSW+2bXIwByzxDS4OomqulVQo8ndbxEEANvwLQFW0psGwLI7aKbVSqDVTc0fW1NY5ZgkHrwcY18LGJb+TWucdAd8qcBzTl4lpc/QMqAI7yBgAPZrq12mgqdIFzH2M0r7C1rVLFZoe28CDMg6AqEONA+/uyPrTR/EuiGXKVsnADAwuoWBKvZQO6SVZcO/BqHQ1g8/ywFnFEcLyPA0K2XBowkVMGHuANPMzdVK428hsCtcLWf1HKGkQg2QvRdbRFDxCFtBUWZQ6SdaMxQfSQaGxhYEWs2FhNmyRY9hKs89LWlVQ+JgstUG0yMGDRCy+IXxcSHBFYIlcthi6sBVhD6OGHDJpER4+4UwEIhO5LayhtNjxBOs9hhXKts7TV5gdiV6moSz/RixNtwbp3LzA58qpWuGYEzG0G5QJcK6en13iANsXV7oqjn1YRJFlisHOw9L87OPk+7d5AkIcNx4bDgN1+B7VnGOAhU8F5fNEKLLNt7jZWQkAcR3u/FRCmx9bGUUlrdMMEWOSlkCB2wAZbpz4ZatUD8IIpohoudpeYlqmTfWPkfaU0N3RpL1RR1cdVwe6PFSvLQh4M7wi8weU5w8NIukKD/2yPjhBzYhhbm2k3byMyOfhp3Dt5jZd5QXWCeqndsTYYqVlEOsIAOFrHz5xTMsOwBrURC5op8GTlBdXK56ApUBfCFCnQOLKZWm0cMyRoN3Ery4I6L9BxhDv3ZvDan54e4ejoo7h37x2cn59hGEcMMaHKWiz6BSNBWjtS647BAR5SSim7tsIRhh3wjijGYOMRbdjvZ7z55jt49s6zGDcjBj/olft5bUCFQONIo7IKJCMc5zF1/pY2oDQ2Yc7TE9h+KsIxfKkIKSDn1GXzORliJ4622rlnjUwe4vuahlobiu31RMkESpwOIgE52X4UEtpSOudLW0NI5I/cziNu3r6FV199DW+/8w7qfkdUaW64WC5x8fQcLz7/HF544UXs93u8/eZ7/90Z/s2vD3RBUkvBfr9nJ6PWraKhLnX18YjcuFtd4KME2EGTc8QwZMQYMJU1OTRZ4mZFQ4uWDmyze4CHrPdszr9oNhfvsKn6cdkfdQDsHJqR3Tw4zln0gKMo7LDF5t/ByaPq8i+TA6pD2LCxC82tXJHhplPcvKVX+0SHbEzj3w6D5xDQzAZe4MhItnfGFNambloEZPN3CCFAsnVsnehasLTSJbEKkq8CTL4cFIsW+AipLtVgaVcS2AgrGkHVHqghWxqyKlKtGAc6ny7LAvh1rI6w0PyqNraFS+FB51LmaD/HLr511hTjxZCQMjuZwUKwACf5smOeptk6QXTppXcwwX42Y+Nb7/aZRsx74o6UffzhXBUf18ABd7H16xup+E3j39GoBaQoS4fIuwrEvkebsug2VZND9q688vGYm43xQbMi0A5RLwY7+mTFD0ViVumHiMEk5F44EEVrKKCiC7K+p1oKlAxqTDua4wUrFFRtkwU7Y6AhhtyfHQRySuwGspOrFdNcWHQbuiXBlG3W0dIau/YxXIoZUi0fKQFSWawSGWOVcbQ9Rk4JZS4sbJqRoaM5hop1lTBkSwQIQAJ5brW4GovvNTQWnQw9hPF8bPNHM2t/7lnBPp/GsAYN2suJrCFkO3g8Q4psq93VDsenpzaasqym4Kju6v7pn4dNTupNlvOweowFVvK/QkGCOVaSeyESRUEbeXUqFb5xBlvHwRAxeoVUs8ShM66AhVppzRxiAxroalxbw1QM+coR4mkptSEOgo985CN46603cXZ2hiFnCFwI4Mo0dv3q48OD94CqzOtpjvaaenFeoLXieHtkez1QVVCVLqv7aca79x7g9Nopjo5PcHLtmL5KUpnQDY6bk5Ak7kGCNEjzBGaBLm7Rb8+r7en+vBRuDmhg6GqIid8fXIJfe5FbSzWeInlurbTe3Irx4xAEOQzkdmm0rTWggWRdkvENxYsRAYpQGxYpCCngo5/4CE6un+K1r7+Ox0+eWL/Mz/ruvQe4vLzE3efu4tt5faALksvdDmpdRfdCcGvmpmQNC1YJnf0TY+jQ/VIKLnYT5sUfRgGEVsYQSg5Ftad7pjR0u2JPcPQIdtjvbo0QrVhH3zv5FBG8wq7V9Odg1V+ZL6KNjobjmIFEaHfxhaO0/0VVFPvMbifeLOjNf6d35DzEtMv9EFnwuAcFAFMqSb9uwcmMAHLKGAcLtRN2YKVW7HZXPJgD5adUvnGcBRGDjt0rRvsBLRDMy3qPaifZ0n2xWdHoZN1m8+jaGsR4PSEGSrkbvUYgghYVETzYOGdeSVvqxC8FqqFQKdDiGOAIKRspttQCqVjJy0o2/ryYUR6xbgDNYFneetfad58IpWy6E69D6FJF5xwACtWAshDWtsaGqIgy5yTARkZWLC3zTCfVnJFyIpm3VCxt6bCvihERrcgAvHMy3kijAZsTB71oECfM2j0wITYnAIpugkWNMa8FD9wA9/Nx6XZQ3htf/5TEk1C4KsRMwdMaVQZgQbTZbDBN+05uVviwU+x3ErkMKaIW7aOEGHN3By4L3Wol+LycBccyL5inCTllyySqmOeCEBKQATGBZR9/mpIpxgEBwGbYAI1FX4PQ4wVq/DWOKFhX+TiCTsjREl+RgjUbq/GaNEFIRMZKrYYIydoddxa2nR8WXuavaqRG905qHWTpGAp20x5zq0Y2D528D7gfEMmJRvuHF/KuOvSGBLKiZ666oWJtLTwBYJlpsBglUHaNtYOH/Y4YyQGEMpdlWQr6Q1ALE5HVGXI2mobY+J2NYG0ViEA2SX5pFa0AeRC8/PLLePutt3BxfgbYuKcHewrJq67UTJFIUq0NkiKK77kuqK3cf9FYzCcJKFrJ9zOkKyBiKntc3L/EMG7x0eHDODo6wjAkJCPlai2IIIm3Llire8AkxpbgLIH8qGKBj60Yz0sgyvenlUaSOLjPPkb1Z19AFJ6J0mKmbly7TnGgfcDh+HNVlmnfG1ak7hA9raUhDxF3n38Wpzev48233sYbr7+BZZmYm6MNZ08vLAn8W78+0AWJw5kQQSuFXUnyhtdMyqzz9CKkm0Fpw7IwFGmaK5pEIFiXFW1EwKcPrZoMq4Me1qlGgVRyWQQ0ZvJDkCRGI5oZpM33aze51d6hKiyTpQIFFU1j3xZcUqbm4RFgsCNBYbgJWYwRsx1zzkdgx2ZljxwQOJWLNfYOF+wMYKz1Rq5DEFB6WCYkm3nudnsEG2NA+uUARx/C+Xv1zVw7a5vKFx5mDezAY0zd7yIgUMUEIPRk09IRINZMCaU1nF/ukGPuWQmr8Y6sHgStrU6w1eFaJ/URimXhQNlqiAGb7QbaFLurmYVU5yAEiDj/hmOt6ERM72Z1JUvDlSlwh8S1YOYdtETOkAGTfYdIU6JWeZACinAwPulEPuNJLEvBshTUetkLbWYCmeNua527QFWPoRzgAaY2KooWtOZkXjWlgf88h+m7g6sCtczwXA2Ij0YNLbRisEM7tVlntqC0ekA4ZapwygOuLi5QGxNDXfo4Hm1ojgYj/ZlCrqlgyJn+Q82UIupEUs7aVYE0jBCdsBjXRYSH38nRMT1f7LmutVBaW4FWJ6SUEZMRzU3eWhfK3lmI77DdbjiGqQsg5Kj5aJgfL7JL9WK1VmYUhYjQuOfYEdv9kHJKOD46xTRNmKeJwWgd0bvCZrvlPhNCH8PEGIFgqGlh7ITL3VtjR740Fkyd+0GaaufNZVexGYeAnBgYksqbeFhoeDEBJZeqwyTSIMHiLxzBA1V227xFaRX7aY3nYIMRzMsnIDQgVufNWWZLVJSldIfrlAeiGm1G1WJjbz6nS1s4UkkJ037BtJ+RVPHC3efwKCc8efoUCiNUW5FF3rnzKgTbzTF2+z1apWrrarfDUipSTDg62iDoaJ2/FedQaGVejsSAo5MtPvzRjyEPGZeTFasqAAEAAElEQVS7HVppQC0YcoJmy/5qfD61hU52dzPPfsBYY8oEd6LkKkxgBtxgzdFaNuGAYnT4SQKizTmJ9mWU1lCF6JPneZn5C6ANrS12rwF3JldwXywgHzBlfm+tbNizBIhQQCEANtsBH/voyzg5Pca79+7h/rv3bcxfsLv8w6CySa5WcA8JQvAOc7bK6lmQjCgU+lyw1gItdF4cU8T/j7x/ibVty7KD0Nb7GHOutc+5ceOXzkgnL102FiCglFkFCxeyRhYRIETJShBgCVlIFPiDqFBBSAghagiJKhTAUEECIyxTQSAs9HiQxuTHzogb996z91pzjtE7hdb6mPv6F5G8R+E+bykyIu89Z++15xyf3ltvn5QqooLFeFxcG2ueJ7syd9AygwcrA5KEunhff7460urCCd3z77hfJkT0ozEFSO045sDb440FwqCrKpqtUU9K/VGENqA6k4sIVeZFtdCr86JLoVj2STi1rwKNHXHNya2BXY2RexEhG2igpiJr5h+TCcveCJdnV5YPckkIa75fXhmkwwji/gaaoDFFGujUNZVPwzFGMxcCLHUJG3Sk2VW8gXA0+R+xCGmCsWqCsS7yOSdeP33C83EuZKTSPOurvGsAQzbKJc/jWHJCM2XR9HKVvdwzq1cpWDxRsky+N3eqwzxTRLeJIpe+N2wrifGagds7foFrbUcCORFjIMbAcQzc9x2+9XfdJovDgYlsUkJBKFrrqNj7WquhqjMN8GCw2oLwAapDVGjzuU7knBjzQFrjiCp5kXUXsjAmns8Tvd+JWs2JdHagpvHE7X7DkGX/OAfMdh6QOZEa9ZkDPXzljjCkj+fB/X7D/HQicqAF933rG77/3e/h8XhDysSueAh7p7Nw7U4iO4YUf2HGAM5A73I5tnoPfBKhcVW5AXMURDQiwAv0dvuAOd70jNVWZKKl4fPPv4eIgR///k8QWXwOoSFGxOs8Hku23XvHtl0k6pB3Rt82tL5hM4OPhsfzUFFkK3jTkgX/PE6IUoUpp+vmbIi86f2Giti8CLslCqiGiuMEp634+ux1yBFpNXd5I8lUL5hTM2X7ju5LYZaSMjczxHkiBh2y26aE93jXeDp319Y73DrmgDxBWCx8/wffx/d+8L2FzG3bjrZ3Oftyfb29vcHT8YMfdGy3fTnmPo5TpFQi422lk1dzx/dSZppjTFgGvvfZRxzHQVv7efF8FqEXCTRH7zf9i2oI3ykqnfUukt5HMafM6bpIuETuC50c4PtzJa2vPdwdNqbGtVhoUwTHlTaDo3a35UnFNA7aDxQ5eKo4peqOn9FaYrMOO04GZWLiD33/c7zsG27bjr/4f/42lZjfKGr/xl/f6oJkax337X0RgHWYkKS4XTC1pE/sEBOhzIZNIw8CepUSjGW3rKsPLCog+Zs4AKjL+gAJ+89r9qkX5jXjfwdzuRt837FtN46NjnONLzKCm9ds6e3ZuVDOOVREfWN0AV2ujuVRYWZ4Ph7sWoHVVQHAumfdMK0OGH0vMxrrtIK52yWFhQ5pGGFApMidrqySolgVdCgPkGQHUexvWwTjymfR50lbzxQIjagowXXkUrpYkVKt4OyCn1W0JTRi0/gpAmklk57q/uoiYRBbmXAVmmZOD4NNZmpzTsmkhZykEjPliLpvm57VJYleMQaxQCQenqWaQV10IoVqjVFJI9fPKvrUpRSptCmoiyTBq6tlp86/ezye+OqnX6J993tE8ETY5gh78pCLiUSgGUc5F8I0Mc4n3p62CpgmeL0um4Wk2FKF8jVqtDgjNdl3bRv7xjOeMfF4vi331hEhGJ+foddeqnRqdW0ckxB6ZkXCMc1MyjxDTpTTyakBEhEnwhM2GyzpuUOFBIu/EDKzLtJ1cUgOCiITEROPxyu8kZd0lXj17lx7nKjSmFS6zRGYSGw7TavijKWwgdbBeR7Yt515nN0X7O5ua+SX7xRG53lgTMiUzTDlvAtLFaB0ov1s+4hPX38CgrLe5k5gZyZGDhm0Sa0TasbaZaHgzZenTnk9QZ10+RTVWIDIqTO/RUhlXWTMQSmOAhZ3KbPOsybEid+DmSsNm2FdwEDweTSNCY0jLCRgreF+f8F2u+PT119jzhMIqkQWImoyDtSidachmrtjntzP5/MENqJqL9uO6PJ/sVgjn3mOZewWeY3061yDctH2fcccHAvOCNpTlBJnGaHlulNq1G2Cn125T033getOqibIda65xnW0zTeN/+lL0jchaedYI5cOIFyGkF1cLuAbuWwDIRdaPrdFWq9ftMkFFg2bEOAxHIeexa/8yi9j36nC+fGPfzahFfiWFyQ333AXfFv5IqWfbo0FSIg/QKRC1+nqNIu4dXWbKWTFdWPR6ru6egecbpN1CQy/NmWrC9Mc+23D/X7HcRx4vj31mTr6RpgstaG4JoVmIOmZInShheHlRYx+ddwGEcZ0YLr3JR+MOXAqFROARjMGMx5kzL4g6kHC09AlT45G82LRO+YwGObS0QNYhR/EtVHqzSK1RiSGCqsZQxMboh5VzAQxQSxysREp4Dxdv+egsoeqh8A8BtpOUik7soEKFWQUtmbdPrE7FQ3jPDm2WAeFI42FnXce8mV+NWcsMuFyxExK4F4PokJl4b3WQkxmNbS21tRMk8W1a93QKbcOjkLuWOh1GAIj57qsuAbpQAldjJUb4/rfPLiZ1QFLYJbr7MAYsS6OcnDtW2eORaMFt/cmRK9RZmuGkAdP75xdzznwfB4YEQwaFFn2HFzH7qaMG188qHccbr5zXRqJy8yrTN7WOMgMMwdDFy1wHCSPLl8Yc16yY6L1bY37Kjm01uXMAOYJyHgvxpAZGQg7a/y6aUQIOLZtw/nVlxjHEGpKJVhvXYo5cXFchGEDpZImXpQK/wwiTE0qhJByysxgYTiOJ2IyVM5bw9vXXwkBlLmd9oHBcRxPIkVjoGXIJ4fwe4JryYV8VuEdc+LEwLZttM5XkTTGc41F9r7jrsI69S5IhyCyUf4xdWZw5Czit6kg2jvGOdDlQB267DCurh+RGjeyqchItG1b3kSIRGBqL5X3kMbVGcis9WSr/wNIhqYfSqFKiWAfgooC2LYNCeB5HLjf7vj+97+HOQZeP31NDiGMl/LkaInvCsipyx2OfaOa8XgeGGNcqht3uG9CW3UGyEYCIKepmkCAUuB8p+6DG/ptQxwnRnLcM2PCPBZ2mvO9lF0y7Qg5SPMscIWI1hj48g/hfyLBqIdoWoMNZRORYGZOcyEvEKLtDYmLT3RWvEgqU8gplBgJtK1/gyhNnpvypHYh1G7ww9B34N4c/68/8st4+XCHu+Enf+X/z1U2JW8NE/egOeHFmDieA+Mca2O5X1UgjYYKKhfPw6H5J99vscWL3FYTOXo5EPrPCGx1SNoF1UYEXt/e8Pb2htb7yuJgyBNZ9eM8wZl46uJuq3gIHchhga9fPwG4uB9T7HV2GSy6nkeNYCQpfnfwk4gZi8BkwcNyBi+aVSSYYfo7ZQUEV2tOX0VbaywiIq7Cr7r48zxksV9Q9PWs6/Mn6oJmx917R4TBPRapeOt37Bv9Gro7NnecY+A4D6kk2InNTMxxCPUSpDxOjabAC6Q53Bv27YatbwybyytJGACsiXKnaIBArsM81L1YKBhOIzozX7/H6hiSHQbWM3X0jcgUD7ZGSN9NIXkqyBoPqSpsRJpYfJH6rItMGLkOxDkGXh9PvL2+AhqFmJEYCgDf//53AUl/M2Uxn4bn84nH8w1zDuxtw947HsnvRwSG5WYLR3cs+XFAqdNIOWW+G4dVJysoeyEqLqvzkJ09SEAtVA8JbL4jG7/fPCeAibkeKw9Ll6FbJDvLIpPzAr1GCeXqSWYXL5W2baD8WDyek8RUa33BVxGBaVMdfawI9yNOTJAXVI0KGwkpGxZyh4V6VMH95Vdf4+31K9zvN3z388/x8uGFpFwkuSS6mNEMr29f4yFkoLKIeuMzqnj79+uAn4XFyRyJtm+4v2zIZHJrjZzHmFKyBMwDkJt0ayauFRTuWNw3XgtzTuw7UWZErrRgQ42S6NdDp9e+HHi3jWnl53EiMRBR43JIucIzad86WmvY9o7n48Dz8cSIXP4bIdSjpLnerjFRM+C0iTl56XPc1JEx8fb6CdUGNaGWY55r3XAPERmzRgkrm0DWGJvSqueMVcwvVBAicvdSIWo8p6KdxQ6dWy3Z/Fnq7NBom2PqKZRZhPhCfFt7d2c5dLnw3zdSBMrkkQaOvJ+GzgpHo8pOkuuIhPXQfSa3Iu0TFq9VBLGh3ts7x2sHporJrdPJvFN8zkI2RTAnpAaHoxl5lG5SMJrhBz/8IW63O/6X//kv/NVX+F/z9a0uSAgDJlMog4flHCfD3UrzLvgdZrTFTjm0SmoHJPbbho8fXjAn5VnPc6zZfWo+xxhqbWiwsSkY3kQcLSv2BLDrAk8Iwk+OicIY+a1jCwmytNMq2fLdeEczbv48W78zqkjSbDKFK9cFG9VhaPRRUL5bfHM0gary+UVZrWBwAaSM4rZ1wK4eJelj0DbmNXCx7vA20eQrEHIH1NhVhRcEhzNzIcFRxNY6zXlU5CzCrTke50DEYD6RKwZdfhzVza1N1TpQslmTI6crTqDVJhKJLOuAKN+BGpOpgAW7fX5fIgywjYTBqXeH6yJ0c6Tg4+ZM2t16l6QwUeZpmQmTxT9h6Y6t8eKg+kgckkkvjFJsVMHiaTjPXIjUX/69v0zUwPg+3YCffPETmDl+8IMfImbgfn/hz4Sv4hygn8oxn7xcVSAb5LSqoiumbPu17on28P+vsdT7OIUp3g4SVHoZEQHokkESseydxcCYJA56b1RlTkPJ4GskVBLaTJ3RrEU0vpTCS27NR9DzJFPkZR3uxSXKHPw56ehtQxl9ceqgcMcZaJ17zQBKqlchQLO3Idv83ipNusZD5Bj0reEP/egXEOP7+Prrr/A4Bj77fCcsbxrZsZVCoMzngEzDNPLEptU4VbERMSQb1QMARx0JYIwAjBlD3uZCKfnqXEgSL85ta3Dr5RnM97asB0L7leONIip7IRvLvTBpCZBViBVyk0QAd2NqNHQBJ1TKKMunFHFGk77whiMYgjdBzlLGuUacrc7ZZnItbkItNTibU3wY6sO68BY2UR0RlbI+4Y2/Q874xt5iTpNGJCpCaCqo9Y1cXFA2WBPFg+MR2YSinVip2lCTARb87ow0gDyNgBpHq7hO4GpFpARCoIFeJN47xzNGkcSMBAYwk2vkfrsxH2eczDYSIiupnpzDmSpsrWMRxwt18YtEr1uHZ4bcmZvOxuM8yTkR0jT1Wem/pb0Tajzl3fOzvr71BQkjweWIx1sYZVpT3QsXLgsKGsX0BdMRum8rxAqASFw1T2ZH+34RFk/Em6+O33QYl6dIs0rzFEO8FbuccjN2WdzwrDh9hSTV98oIQpW6a9a6fvfzat22tq2Zbqqz5yLi4bWMfsAu9tavbAybFxkqwUKios7xLh20YH0kPSearO9TRKxtvwEROOYJ03jJvTZryU4vvf37dwFIBprUyo9gYVnnLjs3/v2Krqdy4CJ+mtmSMJcixjQCes43PkDoAIA6qM7QvXq21ztmIdWMzP3e6OKJTBwxMVXslD9AZdKswCs4cgJnDHjr6IL0xxg4zlN/hpLjXsRSvU6uuQ5rwMv+wqCyfV+eJY+vn/jJT74gkz8Cm3ec88Dz+Vwo1fP5hLWGt9c3fP6d7wAZaLedPJTZ4Y1k6o8vH9Baw4eXO1prGPL2ab0L1g/YxCpcI1OF91XQu7eVEL3k3UmZe+1T/cIcLwYvTvNL+TV16A8MqVO2NT5ovYiYKuwl44fViKy4RxMv7Y7RBnJQAmoogzCRy9fZoWNe/KzyzjHtS6JNsdb+KqrBz8pEWyY657BV+OZIvf22IHxz4MNn38E4T+z7DWNMvL098XJjZssQ2VKadLQExCqkq2emEDT+Lpt1Oh3rsDCvMSvDJ0dQKspt4WhGHoHVOHOM5e1T0L9ppHiMk2JtjTTnDP35jvv9jmYbjuOJMU75CWm9Nxf5vDocW4TjkvjXe6rlwOIgrq7fXaq7oW1KFNRNnCYb6NbQxW/jOKmRSBtj3QW8BgLDsZoMc8Am18yiqUAfJoElRzbyIspld85Ja3YEk58N4n5cJF/ofkhgoXZtu5GQq/0yxoTNCcTAeTCja/P3WWt5CQqQ60ytNYSF7hnDNg0k8ttcP/ccHGWX+ZwuCzQA3RrPcuPa18VFJJFqEAzFeSD5XKnEmYvAjqQCsjszj25z4vXxxuThBtENgN5B9eO+4e3LL3GME1ZKiJ/x9a0uSOqQTF061z9WBW1XxwHowlIOSCjNMGbimCfGOBcMX4nBTISUDTpqXsZLyFqRX4cgNx62rdn6YOW/8XK7wYyVtglGC3Ueq6hQi7aKICs4Wf4oQk5osinei1fc+btgpU2pivlu7CRil0mJwyb18qBwQN4KLLKaUAOSfYMbGu906LiIfxkBUCyD83lw3ip0ptlFdC1vBADYW8e+33Dbd8x3ia5b7/j06RO++OILSXWHtiIP43Wd6IAbuAqAtQ7kh1CQPa34Q9YFRKwayK1YKqoIddty3tAZQC1+w3E8UU6/QB0c/Azl3TEzAS+SHtCS+R8WgG8yQGv0mphzorUNP/j+LyCTKbXHeWi2S9jVdQHcdqJ5x/OJ59efyPx/5TjSPDHPEx9ebhjdsO0NYxByvd1vJFWOE2MeiLnjhi6oPfGy31no3G7o3enwOyde3w7c7h9wv91xHvQSSGyL4BknSbBc8wGHLyfh9yOFrTm6J57Pg8oN6I51W+m2ZXpWeyw1k17rTJ15bw2V8wSbq7itp1VZKeeceI4D++2G53Gs/bftO9DkW1Pb7RxASJXSr0BOIGHbhjk7u8uo9c/I91K3kG+VcHBGDyn4WtvUiKgwEaI3JwPxns8T+37H29sDr48H7i8vsJl8987utVuXzUCRQZX0ilIWueb3NcISgRws4P26bWFqjhy8ZNCBsORzwk7DP6EhFwqiYhxEZ4isBI63J63sJyq1ESNOoa4QmlDnmDMsztk8jByrMC3kkwUsM4DOc2Lzhv224xxO76AM3FqnqkrPNBw48yLH0ohOJ4RV+KEUfULN3OkUDCNZnGiy9nyhA2YsOBwwusJR1JDcG6fSeNviIV0nkpvLP4nPjmPTQLRSbBJxbf1Kae5NMQ9qPsZ8Isb1jN7z21jzVFENWFYooP49rf54T7SGidSYDLLQ3+i2jcRIcm6ASSC8i78zNYITSkdvnmoEyg6CXlmMeGgsUHvHT7/6ErxOKd/eWkNrTBX+/mcf8fXXn/DVl1//jW7xb3x9qwuSknY6pMzId3Nk6OVnkGkNQzNg5lx2yEjHOXnptSByQNUN1iVf87Z6+UPy1VZBUCZy0HVbquvTZzQTsZIXYzHKoe7kvZyuAE0Aly9EbWJ9r1IbVNgWIEZ8kQzf5XgAILzrnFnz4BHRM4v/kItnUaQ9kwSMG64t5QAiFwy5ZtmwZUYn5JCXM68vdR/6nfSPH4Ndx6e3NxQfpRQmNX6prAtYW5uPzyDX5uCFeJk3pQo7Igy+0m1rxFWjqio8ZyR9MupCDB7e3LQkaY08r7+7voi8jeOQy2Jn5oQ6GCLpWnsZmFMhWuOypM5MfPnVl/qdB7ybxh7iMownnq9v6/esyzJBBGlqTR3Hc6E6a9G54Xa/4S64nzwf2nTvvUnhkphP2VB7LoOqIZOt82CQl0n72VSQcV9JFVKZIyDZ21QI2jtiLFuya55cMNTI0Lu/UJKXlxvJpue5SJckjLZLhZYch1iaDMnI4QqNPM9z4OX+otwlmrydI7BZU8PI93yOAUQgjbPyBiISGYF9v/E9fEqMeTAZeNuQr580VuP72PRszqCxW/Mu900+o967IidIuvzqq6/w+vaGP/QLv4Dz/IDf//0fw1qj744c9hhVkYTFVT2RFDyXc3GNBQp5KMI9HYzl4ppBQq4+b4i75Abctw2PxwPPxxu23uBtI6KyLno2a1N+LaYDyBwcs9T+xOoJV/YVgv4ZVMxUc0Vi6jyHOnuOFbu4LCnyeQV+lv19BJHYvW9ES43Kq5LvrnM2eWk6jMVGqOEEyd6td3jrLKygz5l1vl2E3jGpQjEvnxRD7/Sf2na+CypJaqRxXdiuNexIEfMnw03rzG4O8sUUVQKT0pMjrOYd3h1jHNdoyx0QWkSnahZCJKZzTOdTBPycSJxAUmmTIj237mj7xqLcEpseWKiBnXNKJFGokYw1DYv7aG3DsCFBAq3732bg8XisxtiERq/7eIgHBRZs+779de/wv/rrW12QRA4AG2htKJMwIwfgHJNqmHeJugnAervC9NBXOB730pTrtaKux4lUIJnbqqeZdptiX0uKFQCgLoCIzdClyNyHmAzLWoTUyMUZKNJt6gDOhEiE9d/2je6iiqQRl6oikzkoOC+WNEPibGnM68vqYF4bVN2eUIG0hKNpdCG0R5ePZfDgXofhhQpAz6Fm/EDxR/jcapOFEJTIgQrCW0WDV0FWTpsTze7qTAA4kadt6+86a+EoKdOeRnKV6/mHrLLrHdbzbOJ7RHUZM+ROmouQy88kzT+EHOmy2fxGx2yhTud58kCDwUHHRzNtMY0POaLmhbb8UQw4ZwjWtAUjuxeHRUoAwammiwuDndHz8VCarwiS3tD6O88JoXMjgC1JyIw50LqIbvEeTrWqPXGek465uhS5Hl0H5AbshnGcq+ucMWX/zsM9y3XSOf+PdwV46xudKCdHCBGBQ4om9858jzlxHE91gHLrNSqFYgqWBhbBGgBGTIxx4NYbTitp+UQEz4WYSTloKp+q7xwNYIosnBhvRCQjJxIs5D683NE+GF5fX68u1g1+cvlOuVKm0egroSA7MzRruN12um4m3YBfXj4g4q/g+Xhgv92wtQ1AYGaF6DE3pblh6zvOswzHatQxLqWKmUiEvPBmBt1UPBBO19rWGnlwema32w1jDDyPA7f7BhOHi81WZwHUSbBE8vsyo5T8J4/gZSkUqMan1hyendwoNTyzEJPtQhaWIaQapqZm6VShnabxxwg06xrLhBoTcWhmXs2SN0pk4xq9hxqoOJ5UB/nl/7TQ9TXJS43rYv0HALYtxDl0tK1hnDy/OTYGYDov1eRkKOdMM5wI/U5TDYrJXRr1d9TCqEpzIXn8SCoivb2zEEihS9ynPBMb5jTcu7PBUJE2ZmBi4OmnXMKTUmczjj/5lNjkWTlq97XHvRp6JJo1qv3cMce53IlL8WU+9XkMMn4FU/1Mgo+fr9T4Vhck1clX5VvjjsVQv904M48pfom6CV0K0wuqT5w5lxxq1uyybdgFjzZdYjMTWwOOk6QxgwOC5grSpZAWQBrGKDgtEV7BUszc2ftVJND3JPXydGGqYzZASYu5Ri604OamRsg/JURgfTe3rIXjzgyFkrPWV1++AHNddqnLcqWs5hVU6Ijy8FG35opkZ16LqbPg+2hrllmBfq21ddkXSx910dulWqkFbAD2zeW1UOOfq2jj/+bmTBARKm+N3hrN85rLn4K23lObsjbTOGt8VjJlzuz3TsLusqSWKsl0ANO3IXX5qmMmaxMGbuDUxceCkOOSOa9Cs7hPbhfyRbkneDCpYCvfgQTwlC/K8+C48DhOFs/A8jdJdYJuoM1839D7TRbn9Yyr+GPcO8BOFq7snTSc5yCfxZuQL66HUii0u9x5z3OtyXmyAH/xDc25vyo71GDyVfBlAgfwuY9BVMW94eXlxgvEDKeKCtR4zTRiERLTNHorXkcG0LYdaYPoV9Q1RH+Q1m7vinGu0TkGjlNyer2TpqyXGsneXj7i9e1AIqQGaZjzqeLblg18BVomSrlXcvINQMdxnjBnRAT9Yh5ozTWmKW4V01l66+h7x6evv8bxOLghNMayrbOIM6ML7hnYC7XV3oweiDC8PZ5U1cwT9/udPAln+NsYJ1Ga3lZhUyhlbx0zyVfpkpG6OXzryFThIoQ150CcoRwkFmyBIoVybZlk1IFZBw0RoeYYg+oUb/xcaGxexuO5iO7FN7uMAt8pKIWOtm3DIWSa/KTAcTyx3e7fGC0ClVx+mZxpmax/diq0ddt2oQhCMpVjBLBpSyXpuneeMSKyGz/sep6RidvmIpbyqzXH1nbkDJxhCGPTFzBmy3SesURO6pCu8yQWonLU6FnFelfzN2fg8XzCLbG1hrALiWZxWPdnIuNcykL4tkQVSI7g923D6Zc9QiFAvXeu9RTqNI2FlxqpMvH8WV/f8oJEhVgaLMldMDNst7v2bTkDzmVis0hISYSFleZkN4sqaEISOb70zMSsSjxZvS4pHrBQirIGNzgyL8Y5vK1LScMTBMqkSgjG5jiOA5YiOvYNZRNfDrNTRNFjyNdBlT1QVtD0sHAVAIbKbOGfG/R6hveOnGTab1uRBx1z1u9mCCtLbgAp++luQMh54q9CbHL9IwOyNqeUPO6AM70YCl2iBDblI4J1abgLz42+jKD6vpF4WgeFtnICKspsQcsOdgaZGstI3z9i6pJlVxJuazTTekdO+q2kJXrbrs26fkd6VVThRHOuq7CzpJy2LvmC1uecOOPqst4fhilGv1mtJ43VdAHXoVGFd2WbcE6d+OrLTziOhwoqukluW8f9wx1dZk/77cbZOAC3So1u6oD0vLOJL8PCNKqTFmrHjGqT6oG/79WxXbB0ax15nijvD4OBRlsqOOWtwB3iC+rmeuD7ut+bEqKTPJCQQqPQobRvhC4aOsIn3DetH0cFBW5blxmi0e9Fz5MwPK3fM+jwGUORrFXkq+j15pJikqNx1kWYiRED2RyOJlVRyfjj4ryU+ibkjGlGuaclvvv55/j09rrsCWqN0MQLAAK3Gwuz28sL3h4PNlrZlgoi69wxjbjGXKiUGQBXJEMfyimqEbKtdT2z0nypOtp6w+aO5/NAmdIhrtDIUPPXnO82QjwcNLQaS2t03HS5rQI+SyAgZOo8Fv+CKey+Co1CdJr2m7UdC3WtBnSpqKTA0v5iTo3rMzeYcx0B5XnC70FCrcI7UchpW+8xMiVVxzKirMaljPGQuYi/GZPFf2sYOYQwVUo29/95BrxvsjyYi4tm0MVtLJRnACNPigHFL+tyXF7pivI+qibcvYlbSLTLZoDESb6noUYO5hgFZawzy1dRR5sC3q0kt+Zq7uuePI+DhfrtBhiw7TsyEn2TH00k1YhzohUF72d8fasLklRFWNBtFSG0Wc/l51GM6Zq1lq8GItYsjmPJKlaunA5ogdRopQyJOD9kkTLKeKdEdKZLP6/xwOo4lB/S26YDqCFiAM3hj4bncWjOes3KCZmPhTY0t4u0ZCSeXmMeHh7eU0VXwZflOulINP1uYlKrSFrwahpCmn/Oa7lob/c7A7gmCZtDGQYcP8gTRu+G1vZdiEuusYceD1BdfC/Ij+/Dki6Sl4EacDwfyMmNXpbuRJI4rdN+4WYvY5/IRRRk1kOgNdpMA7bQKJjBesNe8d0qblLkrsp1YBeo9wg1UxqH1OVQiFJl6MxB1M0zgaQPRLnAJlj83F/uOE8SMDcZ3A1yCPE4OALqvaNs/FnfbbRsvtHpd993ZA58/PABn3/3O9hvO2wVP9UNYUUbGK53UmhPg4z5IG+RuA73MJOCyNdllqGRWWgcIP6Fm1HBJeSDRU7Io8AxYi4y5nk8deGIF1D+CkhUQvWKDNA6ycmxzPkYuN/u6LokykgKyJWiWhcVwFpSuCWusE3+ncpxKYVWIXpwBjbGOPGcE1DuypxMDCbcIunwAaRyY9JtpTpbGiZOXoKYiGkijQPWG+4vH/ApP619mpk0eAMw8oDZG/bbDW3ruH94wfHkWqECLWVal1rTcsRFogW7bLhj2xwfPn4fx/PJkVNwdNa8MX+rLqYJWMvVcTdxZKo5a7qEtQzXuDFAbxhvjo6Gc06GBGrsDMdKVzZwpGcmxEwjqEqfrpFtoXvmJLs/XhOIqWf3zZFqjV9Mjc15nvj60yeEGW4vd16mcu5jcavzYlIeDhGEW++r6IIKCMypMXQqcJVnYdsclhvNKMcAzYSISDwVLFiqxxJTr9FWBBH5sDXShj5H2RYAQLPE5gx7REJRBRqfWKGNU8V+V2HqVPX5Bkss59d1L71DYgsphc6JEKeKqCHv0eaBmUpsV7GfoHigbAxWdlkIrRI5Gg0YGmdtt78FOCTQoeLaEFOQ8DlDEil1qqFEQz30ZV8cgRmHLghBaHlBnpkTT4XakZNgmvtrXqoObOqFNMWvN4eOdh4UlU3iyYXdtg3mOwyO4/HEjJO8ilU8afYKjZZOEXFRnAIsAiUPfBVfTrQHJrWu8fePjNWZRjBwCwmcQ74kiQvlEL8G4eraeYzHnOzQQnBwlKyyfkbNPYHLLl+zVjeUsWhV42kcncyTSgdD0q0wWVlHTM7/5WI7jhO3fce23zgbr4tRhUgRICfiOuTaB2y+kVAVFzoxIli0qegiWuAL9XEhEVpkq6gsA6MItiyUisYir9ESX0WOgYiS0X65LkDyaPiM9u0D7vcXvD3e8Pb2iaZkxpmxbY49L1hfj5aFTGsIM3z47DN89uEFcxwAAh8+3PHh5U776+OkVHKEeBuGsOdizrtQkxpDFvpnxsNxygMnIxfJrYoF18hxwSVgIwAV8g6ia03FPotf4JwDz+PEvvky8ePfFREuSQYcMZGTzUDtoq1vQqUMx3GS2Osn9n6XYue60C8SdV5Ik9lKRuaaudbtMU6tTcC8wZO/r3cWSCmUZg7AysNG338dGQ6qD1KpsqgwiryekaTSkQqcNHa8t/sN42D2SmVpIYlIfPr0CV99/TXuL3eeaVqyocu89659QqXh/X7DZy8v5L9kcJw3ge4Tn314QYzBJOVISJx8IYAgDypUdIw16hIC6TQpxEII9e+MogIHUbjbtokPZFfh7iU2YLFTCEMhjhxj6aKEiQSNBYP31jBOvqe+dSTo8ptgAF9LQ++NfI5muN93TPPFNcM75JHoWqGGXCtj0GNqv9/1c9iINZFz6ZoKoN7q0LuAxrEGEduJf485GJuVRMMCgXkcayyXyCWddu0RohsmiwgiE03o9xgHa5acGDaXvTvXQJmpacQve/wKEq6mENUQCqmijFnnFVyN9VxIU0B3ABoJzRBi7h1t13hRd9R1RhJpsS538N4ZSfbzTWy+3QUJFxU3LlnDFww/R64HVeZIAAhV5UWIA7AULVVB1kHIjcNLc4BqizqEZkFhEOEztcDMgSbDMsFhZpQbsjo+kdlwPg8cQi2aLrc5ye+YIjMZypiIE/g5JkdTSg5FIQ1s5ta8L2YAzeRcGwuGMwh5yERknWxxPZvEksfWInZ39s6ZGMdco6Hu2qiZy8QsBefxMbOgWyc92oJFIV6Gie9h3rRxBMfOieyEyUcwQwIwHOMQ+5sX/5LBGeg0CTn1istTwXeZoM20CgfEJZUs/wmqNMg3oKHZdpUkBo5F39kqZwyUnByCpec81uW7iUlveTmMmtWfBWImnnno/YZGVwakL6Lsxw+77oJYcQHmjrYZ9jvHDjRwugEZcACn5OR10Hhz7N6E2rwbF+m15CIRZ9VmLPK7yQ+jyiBd9hNIu2yu6+s8TjiA3WlV/zoYa0DiItfmOIdGJA33+w3P48m1WghTyafrsyWLf0PiPAb2W8eHz76DL774KUbQ2RMA9m2/Rkds2a9DlUsccMO+3XCCMfd0sQQAKSkyFZ/gMG/oKbRqDNTItFC4JmhudehC7e63G77z2Wc4jwOHPhufdQVtNmxbXYoFeFH5ZNozcw68fPyIbdvw059+ob0LPN8e1+XReKHAHZs3eMp/JE/EPLH1j7SRT+CL8SXGeeDxmDiOBy6IPhBGvx+Tcq/ujApro+IHSFfC9By4bTv2fcPjGTiPE3AiKaG1Usne7jQErNElhOBetgi+RliokdCc6LqSzLA4XnGOReSng6vOGPPlZjzPslmX2/NtR5sTFsELPoEwmQ+GxkZe+VZJT6jniXajSeOYyq9yF/dHxG5n4zFEyHeSblZxy5qAAYDH41jkayITHA0y0mETAp5EjFSMAVyvW+d5EFJ1BpzNFucoGCLVmht5OHWnZSJC3lzgWd7NJXcv9SLJtSxYnN6r7tj2O7Yb9zJHQLPqzbVXIg1kKNTeZ9hkKXKAC33itiNy+t6W42/29a0uSK4Oea4LNNnD4TINcl6MuBQjBjkfMrWJl2zWYR2y41XlPCeNX3TK+Zpfc+6+bzvcp0ifsWrQvl2R0k32zwheelU9Qx0zkq56Y1LnXaMGBy/N+X627bywQqXvQkeiZqrs4gyQ0VrNo4HyD3Fg2SEvtcy7BTXmoDeCGVxW8wA5DmgslmZOSdEgZAack6tDnArdq/j6sLwSi8WO33sXuY0/d9scMeIi2AlCfXs+KA08B47jxL6JTJs1RhM6khdatYlzwp831nMoRMehkURgjWMcRoMfu1w9C/YhzH3JygnpGzY9xyv8rbxlhKjUz1PR9nw+9BlZ7JrR/6YVFpAhDxYguzKCJB9mwJq/K8SFkiW73RDsi2Rn05dMVDLuzGWJzTERBJ+Tte+9EckyFgGWdbmISH2eGKHCXCOdNSpRhTMyMJ8n95GzCytFU28d9ngAGRorGd7eHquwMTO87Dv6OImCaEnGTIzjwG3fYJN5Rdk4ekyhbuUPgkLB5gR0sTZ3oY3Afrsj8o3STa3r3oj42JAFQGssIuaUMZetDrs6TcPljGxB40PPxPPtgdaacqxOjPMEofwppV2hEbwKEuxAe6uGCeh7x2cfPwJJaeXjyYRfXqRtqSAAFg/NHL7vqC38+nwAdse+3+SbxM9+qiBvjdAn5fPkcaUBQ81FoTeqQlWIKatkh4zGdHYMSaALybOyHMjLBwmKeojEGFVM1JnCy7g1U9jhVUwv1Y4K2v12U9HOc7RBaJIZAuSIZXHkE0iwyfPgO93kDDyFdLoIsZ5ANhUl40Df+kIytIHRWsdnn32G1huLv3Pg7fWNYy7TGYJEVXWBxG1vON8ZqKWZQj75uzehiWnXuHyNTjAWwmjNsb/cETFFsuUzJZJ9kXnrfc3zRNq29kGN2yoF3hMivjrMEuEpviKLt+5SVcVce9/U/Pa+45hzqfAQiXGcyMa7tgvho2N5yt/r4tb9rK9vdUFCDXURzqBql9a23vniGbq0adaGxTvpCrNLQY1T6EIKRkzIvAzVRTe48XCijFZuqDJRA+iBUPDgsvtWl+ZCPBCJ1Ow+6pCLuTo8QFVxqlPRn/HqJEAI0FtbCMGmDou/H7gb5foI+RIUH4BkxVpg+iN2KT5yDh7sQmVSeQxR3z/Bg1GfdZIyf13eKdPvnNgU4gbTqKvmz8n/Q5KvoEc32GRWz5gTFg35fNK2XuYFbg0TlDw2/V51AmTSMyYlTSMHMtaMvQ7rMHYIcw5AXhYsDMv+/zLqqkyHTHCT1rhMz7HUI5YJ3zZEMtCPdWMXYbQKIXtHAGUhPeLEvu+47Td098XLGWNobHGl+y4YN2hGVWMH92vNskBXkZAQkZuFYBl0sXij78A4Kd/bpL5pC3XjuurtOh7cDNgMXYaCMwM5SnJOdGxOomcRqZwSEGGcid5vy1xwzoHH65sUL7bQFneqotyBGAMzeVmVk+nxOGBTIx53WLbF5/HWUO1AjQigoMrUXno+n3j5+Bm2+w3Pr0648b2yQG1oLVeadmvs2mEsrAvZev88Mms/JyBiaMbElMrmfeyDJfhn1XESieHFANnst87Z/fPtgY/3D+h9R++BdgbmOFEE2SG/kILtARYEJlXXc5wYnyb648ki1d/JTPVXHO88f2KqqXNB8uKYCX0t/iRcxOSk0aA3qggzE77vLHqOpyKhTCqqWKOSTO5Hb50XuLFBOsYJd5eShYXtUs2Y0aul6Z0G+V383cu5d6KyVEiOV1Gk0TQ5diwgt97Rq4mzUi1KiutCtsU/a43ycibnDszpuN2oVgvvmMcgwpkVzEgDPx40E20XuXXyzy0+h3GMbrahbTzH5zGXmqt+91Ktlbkb+T4TGadGfywgIVQ7hUa7dYSaib0TKSn1YORqy1BsONfBnmnidacUiVWY8s7jnhIPKws1pR/TdUZWA6TKrElCv/0tgJCMc6I5iTxVxpWcc21Wo0YfFXS0DhoIQpaMbF6Vf4W8keBa5FVoQ9rVlelW4OKQT4fx31teyASQMFXlHMUA5klSk7qINRPM1CEqUpULlUld5DBgMiyqLLGn1BlNhU5rlJwuMzT9tZK2AkCI9V+XWJEQrVFvn5MPJVMSRx3cpq4ugzyB9fuqe3fjjNfNcdtvqE6+Z5MkOZg2W6oM1wbIQNRIxMAqH1DxVOxuoCGBOYDel2S5TIrGuQTw63eaZT6kTUv4tKF3W5u/oOZSjmytL+LpOXWQTqbIassjphw01RWc5/nu0jKMeWgezEC9cobsnXwlQrx0/xwKPnODNnPHpgTjZeGv93ZJWPVSpTqpy6N3KqdmKQTGwBlDyJhm85U67BUeKCSrPr/IpOV0CuAqGDZCyTYnzLZLOQSFogkNgRDLIlnSSIvrvYmANwuFM3pcvLzs2HrH6yfKW5uZRpp9IVxl3uXhsDmAKYJmZzcZGikW+aliHpoUEfN4wrpSmvO6kEIFKEc0XJ/btgn5VISB0cY+I/Hxfkdk4tOnB7k/SXfOJk8jR1xzfYCgu5GjQ/8i7kcm6e54ngfXvzXETPz+j39Czk7QKbbtJFBWcm3qEizkC8qpGlMGVgjt6eu9vA/yrMiMGRq/RSwC+ASLI84fNBJRof180sNlHlLqeCO6aiTyx3ESvs9ClHl5WXP4BMjYHQjx8CCjw3MEWr+h9W0VnNd4fHCNBxuWWVLj5SANcU11Zjsv+WiOkPX9PDlS3JQ+fA6q6hyJshNgg8J1O86xAjAj2a68Ph94ezzw8cMH3LYb30s1CTIrdJ0bAhRoLmhYSOMxiyfWMSGyd+8wc5zHuQL35iRySq7diTE1PpdEeEj6H5hLtEFEeKI8aInU94U2pe6rXKiN6Y6QqzZMPjgaKVonYVmor6kAB1gI7VV0yyPqfttIXJ90JAdow1Ao8c/z9a0uSDS1kFJFQUYi7dVijnKLa5fWvC6hBkJoZmKKo+DylMRRLPAs1Q2h7frz5ZbqzcQwJi+iYMNalV7ukJOd0Dkrers6AVuHKat2ISrvLgPM6q4K6iTsWqTVZi5vBpnAvoM1ysMivFQ3BqsRBQTLb/Sa6L3hdrvj8fqK5/NtzU3LpMjf2dWbpGA8YDvTUQ3Y99vqIOdkd1cbpgi0U0hA6iJFkhP0+Xc/CiU5MKWAsExC1dkQfnEXLHExupOFScvLxTZKaaC2dM6JU++yd8qNV2eqIraIt70z5fPjOqzk96FRzhgTj8cDx3Gi34hQ0bxNn8eZqPzX+1rzcHDmPOcJWEOZHQHlJcP3XGqZXF1JHS5VFKozcY4YT615pt6+s6PWnJqPW2MnrTe+Cx5QxQOYqGq25MEKtSnI1+UOqu89YuI4TqT+XkL5Gu4oGWL9/owcSY0yeVBu/Y4yx6pAOX6OYPCeDvhMEaL1u/M78WeWp0tzX7blEkaIK8DsqJd9WyqxQnUKMSDHBOjbxoJRo7F9L97UwHOccG/Y7lTYlKnbzWhwFsVvqveF0OXL53m73WpZkXj5Co6pMvV5mGnCohDKiSG/pYrrOQbGyd+XFu40Y2xqmlxcEyLB7Iar+23sBGAh3tY7BCfnu25Wa7W5CT2amKMhptZeo5nYp6++xjIeE0J0jIHugvKEnpaRoqWvxqwQ6qmizFtDbx2bXIWfoVRvjR1mKk13agSty3Jli+nc5ljalxEmz2+X4VtlAdU6bBxTzssNuG8kDPPZ+eJwf/nlV3BnCnudJWZYBOoi5hr4uzsS296AqQSDAM5gmnVawoMZPfttA8QXm5kqSpQ27JfdfSlgkFjI7/KvSWHOmbLRp3ndlAKykNpqxjg+kk1DjdE0ti11TTWjU3w3nkJsKGLwHjEHeSJeBwaL5qITVOP/s76+1QUJq3weOHPMJank/HiuKpuzs7bUAkjxJIRmusnYJqn2mJIpQgs1g/+s0cZVlTFWR8luM9RZGscM4phkBkwztzpICrHQzaBjumau/J7rMi+zmRQLG1UEdLLNjQoAuk6aYEGOopAMCUx1KpdaI4kuiGBGIhY789bbGhtMJdQWogT46iCrWOPipRS5bJ3fHm/Xr5d5da0qGqCOGihzMm7cvW+43e7weyLxAcfxxPP5pOX0egauC2mu7tpA46DeN3SouMvQASUr54hlPQ5AAWr8ChmjzcgVEndMciW6yIx1sbTesb+8wJvj9W3HT/7KT4R8bCgkxt2VXKtwRZGmeegV+Y2FqAtDrzVRheksgq3LfdEFU6tgKWUFfT5kyPdO619Fy1I2mD4TQJJtBI7nU8hTdbskDTapzkxr3Lwg3YsMHJlo2JDhy/KMhm9d47AAxol5Duz7DmAgxJ1Yce5GZKckr099njlCxl1ySVbCNkckE4/nE8dZckoFSk5tJl2SLNj1fkPthlDAnGT/N12c14jAVODQnXXGsYirqQO+/DTO84Q3rrEPH+7YbxvO48A8JhEDFRZlCV8cM0CITjvx/e9/D4/HA+6O+/2G4zgQ8/0F4TBdUCyYXfxfymenEdEIjT8DiWaFgibtvKGxal5y3vdWBNU1l/S+Onuo+C3o3QFlFqnQtqRbL1jELLdcFX7vScAscOkrs9Yy+FwsiRb4jZyHcwwcbw9kd7SXO0wj3RlDfhxMFq/i3GHX8SQkporBANfBLk+eUhMV2ZkFnuS+stivkVEKefRu8DkWekrvIHLoatRNJLSjvKfW4Z4iofeNRP7zwBZdhmnkJc5ym3UepmaNhVjfcD6fRRZkYcVuGmEO64atEwGiMirhfVNTqs+183cc48RxnhwDp2wTCAWR15WxVFBrn9V9lYmYQ+tSZ1RcRU2KAxgjcWQuhLYS5guJtUWZ/pt/fasLEjMa8kRU5/Ruk0F9ky6ymNqo6gZphT5XN1WeJeXGmav70tek7IsXoq8smuWqqY2TOnjmKSvddkncyga8CaLm74B1QIQ6tFFzS220CKyfww6JVfnWb5xf12/7jnQHbRS3QIQvAuSClBOL00BF0gDsRBt9deTlucAhheTLyIU41GzTrCMil9Pl+jzq7koyW2qSMS+5X1XSyMTjfKA/SSjjOahZpGa5YQ1iU5LprmBDg78zvotVqJZmvjXDSADNkNbw8vKy4OeaoUfMNQ/u8tXgiIC/S9f8HDPx+jrgoJvkZ599WN1ooRlURI11AQEyz4tyqo1V5DlMl41IaGOwW5yBGUN8BDBFNlmE1+iLBZYY/F6HxDs0BADk/tCMXTzTW0+NsqBRla15eYJk73Ss4q/M584xkKjiSNk3Qc7FqdkzYxc0267Lqi69yaYhxuWBMuYhtYJcV3vDtssET7wZSyiMkq6j55Oo2Zg0ozq0fkhE5PuqvJOSo0/qltUDsMGYeXV/HO8Y+VFInS0NB6YI73xWe2/KxKqSmsVH7w2GDc86WxLoXmGGbGQyUQNPPJ6vOI4XvLywENm3vsZxc1QHm2t8MI8DLy8vbEo0zmuRyI3FTupwG5PhkdC+LmQFmOt3/fDhA+aceHt7W+co6UNyPo6U+zJQzqzmXfldDQQWFAMAnpNdKBOSf5dIbVuj3H3r2PuOL3/6xbuLT4qSRnluumEbE2ejIdviaBn3zTlOvE/6TtnsN2/8/WkLDOAaUQUUf0BsAZFyUQWQEdi647MPH/HlT3/KIrI1GmOWM/B8T2RmfeC9cQ3r96h7xc3gK1xR1hPBRqltHbAGGyfCQmZ7RJwwy7qdP7M3R9t2mDXEIcPGQrIsMTFYsCoAsO0sAI4xsVmlLvMTh5RO+35DR6wzag4pIhNAcOZVzSPvmYuIf72rEK9Qf8ag5zVWU01u2aVGpHne1XT8rK9vd0GiDmfKkEiVBIDqMufS17+HvYF3XiSZXGRe/gJThwjndw5GPNcM0DJ4qGjumu7wzs2adUBrfkv4d2Jrba3a90TBZTwlNKQWA0mYhtCsD5YwSSgT9OYYsjReBEt+R1owq6vzd2z8ZV6lLiAF3WGhqYkichZnwbtrDKBEY6Mfi6mbfp8mjNV5xPr37tczJtmLsmjbrgDAMas4JHH3y6+/RBHQup4rXQavajzrSSQ3x7a5mOoq2FoxyuXCmQFo/JN1qSdwu3WMICFuHANznIQlR8P9dsNt3/Byv+N+vyERmiufeB4HHvPkhjYsDod5GYvFGgXUPnQpcJAp4mzJ+ULPn6FuZhyBmAEdl9uvJbvUBllL6w8FEu6JJvJlJRGbijEWWYnoVaxrto93iFleBEdgYuQkp6R1GTVxEXWtYxdUHVGZPIMjmEzKeCcTRRPlreDy6oh3XSXw8eMLXl9B5YA+z7bt2LcbXt8+CVnTFW6GMfnu9/sNMSa+/PJL3PYd++ffYWEtk7arIbm+8h3HayLV5SUSjH8oYjz3EJOW933HV58+cbYvgyciK8b9L1hrzonj7cB5PmlIVXJOKK8IjuYbUOo/oRdffvFTfOfz7yizpuH73/0uvvrqaxyT452jZOrNEGfi+Xyi975GBACWOm7mWIgrvKOhIh18STLreW7bhtY63t7esJR5Qk4sOE5r3jGK3J18LmxoigeXvDyyriLQ/OxdUdJaQ9HFW2toN8e27ziPY32/dZabYWsdZwJjugpaV/8hNAImZLWaOMCNGTYmgnxaIoOFqiPxPAfGMRUiWA0gx4HTSHRu7vjOdz7HV6+fyC1xA0IkdkzYAOIsZLXOXCk14YUlInOiOBkA2LRMvrdd58HWmnyQmLVmshegAsdwKrRy2OQYfqc7bQaR9jkZ2lfmgeYOuMO7Y+aB53nAp+O27auAjKgGUKi/GcyIsiVSPD7urQtmVYZWVuElDosB2aus1zm0dZppVpGuIMs1Ts24eDo/4+tbXZD0tvMQV7VZHTwvCs1crWxwXRV/wpWTUmSv6sYMhoZyvOPPKGdB1yjAjXLAEQUPA4GBGHwhU0Sy4h5+40VEaNMWpAiROTVvLl6BCoKGhkrzLASAf05E3neXmUsFwplf/cBkN6OuOkW+zQzkeOexwF+UF+QQ83pBeOVhUpfpRZ6FFeypShuBLskyF/LEwqqkfV/5P7Y+4rqkEmTcM8zLEeVQWN2GNoe7r+9HB8wAklJdz4DbRtVFAI/HoXeiUQqIZW37thQsCeB1pJ7rZfudSe8FOwzIy6G3tw3HOWUMZ/INEUQsmL7srecYWEGMtdmTRl/lXTC1BooEuW39mv8X6hcl/ab6ZYyBdCpoEvUMoS7vMozTREIjnkuC6M3gawR2yZkLWXFA6p1L0g6hdGlXmrSB77ubIWX4leMkAdhtEVwBRSXInvw8B14fDzzPc32mYYMS3TGX1D1mIYuC7SFCdHf88Ic/wOPtDbd9I3kP+j3FQwh1rQZKgs/zRCF3UNMxTzYQY4XVMQtl23ds24b77WXxyqw1wGgTfxwHmsjBJPI2zNmRen/XQa7OMss8qg4WRxjw6fXAbTM0T7TWsW03nPFQbSFCrDdsOz2FqgNN5PLgqGarbNSLlIgEjnFga33FWxiIMA258dKFeFtnZ5pzlGuuS0ajjCBKWAGERfxl7o6K08nY+nX6JItkSqKBT58+obeOaOUa/W4MoH0AJ2J4nnMpXVLmfqa8LFGf4KCyozVfa8yAZVufIEpVCdbltwKhn5i8VJ/nCWtP3F/uwAPAORFCDJo3qW9ov157bGW8AOvMTcS1n+pM1Zn39iYzM+d7m3PChD7TiVlcHXDMHgigMbOpSe3SzoFPx6dVeJHnUe61wP1+p6LnJIlXi4KoxpokiQHyzkcLQvHIf5TtgtYKhOAvBV2mEEQ1idXUhpB8/Y48T66G55vtwd/461tdkHz48AEfPnxEIDDmieN4rI1XqaJuFWSUqOyZgsZr0bqX2U4FaulAj0DZHVuTcVCW/wPHRIHiaZQhFRYsWHBnGIsBNlQB8yZE5rogqggxwZCsvtkBGbiwm8iSZUQWAC+V1nG73fDhwwuO48Db8Ulk0lgyVuYOyPwrYyFHldLJwgDLVwPFDPAOz8DIgXjXpZDL0t99bsiGv2y/VSh9I8Og0CtJyqCRFBJtXeh1QQIQyXiFCLpdmzPBUQ7AUYBTX8+9mYq+ZiHRcNmKhzvGCIzxYIeQjD5/Pp+LwBaZmI8TZ2vAmy72zEUKc41vikdTceSZlVmkvb+KAMPWt8WXmTLxCxXODMIi+Vic9lWw1dqoQ8IVirbrIuTnnhwZuMGjqcDlc+voQo74s4q0ST5EWxDuZb0OjfuKKJvoCOYDVbGP4gnoQwYhZ4DunhVNzxqWIxxXUFrOgDlzlZ7Pk0iFzKP27UZDLx/48isiO+fk71ZJtq13HMeTF+nu+Oz2GdeYxSIcJ2zlCkUWf4kOynNKpo1E3zY8ZjkgX8ZxEeSYBAzWG0J/rzKBMpTVof6fHmUd28bnsW07bK12zuCLv2SFkgMopVUE99Q5mOvS+4Y0cdk05uXwgZu0yO0JkPStJsG1lkLS4N427v0413uDAWOeeB5n9RDIxs+cMZErPZxnUbMu4y9ce7vUQcZRydT+aO54ud/wfD4I54u3NmMiT56kcEffdpxxEhUAWIjMCczJMZ2J9JyBRINvO3LSgwN2mXxhTsxI9M1h0CjUbK11JEf6ZhzPIS5jxOYNthnmeWCMgbe3N+xzx8vtBTnfyDHMBGKiu4uHw/c5wYaOZ7zrmaqRs0qB70JjhJYH74irkTPdHRPnnPRNclM+Dl9UPe/9dpf60rHvE+cxANkf6Klyj+w7ijOGyNWonfNcikhLjXNT+xwm2TQ/99BPbu50LEZ5S5n4qqQU+OKzkbMzTyGGaZJoNzWMhRT/LVCQNBFYzzHweDwwqhNBkmcALJiOwUJjHVL8kulRJKwUBLjIYACEtEhJ4sW78AV5f4P0BixEY3WjuGbZbHIDrROeXGmJq08XOVdql5hjITsmmLB1wuhTnUo6sL/c4a3heRL6jiApb0zOv8sG/DLIYqJnOVAWoFLscDeXNUKqSyeu0DovzSrmLMoWnhfGHIT7K4qbaiYhBjojmhxD65nlIGmXXXky+2MmnUJV7EA2zeYptCSlvPHFc5ky4KlNXohSoRIzJmIErNEqvcZl7wvC5pzJziKiRnDkozLhIuhJStqugK2ZgXkEmvPQqaDHklhGTsRgVzojECfYDUoFEHqWhcW/Ry0qTZXGfokCTK3R8XE+GBFPspwOxF7qiqvYnTo0aQKp76kDp78jFyMqNZTW89XtvLeiZqaJuE+Ri+z59vqGn371Fb7/g+/zwkk1Bxw2IQcLomvmwP3aGp1nj+NEzKEGIBHjwJiJaVpnW4MNoYWl6jBHACKzQ/vqIgQXSqjjlXLo81ycDTN22oGO0kd88eMvcH+5wzfu03GeDEncRIjW2I2BiDwbSGzOpaKaUe66cjZGLn4Q5TbkkoXrcYhkXt4SzSqgj2fVnJMXpS4Sbw09edapOwHcsfV9jVKalepO6DBSeyUVdSGuh/bs1oHn25POuPebEno5FhhyBLW6UBPLziDn5M9qVF4NfdbmDTZNKGEFfV7nazVXlSTt+u9tazq3TnjbxRGM5XTKs3WuYMaZU3vaVLRITWaA9YbNNEZbo0m5HG9dqr6BeAsW6k5UJ+QPVUVOiPzZ0IBO8nV9raIbHAVa0s/Jm6Nbp8WEkM7UTeO9wxrP6ZETFhqB1746B8Y5Mc4Tt/3GIqdtNPTUfdXyZNzCDDTbhEg6sqWQCRoq5qAPF9HYsvlXaCfErTK5FrOWo/28GqXmLNoj6XvVe0cgFtXAnTxNIia2zmM2bhdh9md9fasLkre3V/R54hxDJMCqYrXQAQBimYMHYx0Wa/yhrjyK2Y6rWEkU74T+ANQ28QAYSQ5JWQszK4Y/fs4J7DceroKBYY6+dcGyG7YmubFGKCovRehjJ7oJhq7I7gTlcec4MM65lCbPxwOAutb1W/E3WGFRwJKRug6gGsdgbV7+bullWU9+Qs2eXd3LjEnIvyyv1bUBQIO/44+os8orE8LMVmJljIHznN/gJKxL37BSjy3KpEw+ESA3J2URXz4hyESokwZoKX5/edET6XRnVedQJWChH6uz0CZa3y+U92NY0skiKtaohHbKKmImOQgfbju2bedKKuM78B6q0V4GLwN3wvcl160LyBqEcJVvSwOUgAz9VsfzkI+EqgW9T3s37ikvDk4qWJjue0NJ1De/nn+ZpUV5WKz94usAI6rIxNLUWjUzdbmB5/Ox1A+wml2/A23fFVvWiNLADMc84YN7bN879tsNERPP8wm3DmvOjvi2K8tI9ZOpwFZA4CLnqTNLJFqSW8JLjn4wM891uRUEX+m+lekT48DWDHmjy2chpFnnh7fFKyj5cCkvUAex+D3uDoyC+Mknc++L48FukoXnOqtEVp6TQYtb6wupMoicrtiDEbGQn807iyQzoi1z4DxPPB4PRMZyPWWDEWrceCH5B0PEJxAxFtJkpfDBUqmQXF6TAEMYG4UESb55clQQAFxKPBg0+sJCmh10sp3i0AHc/6uxkV/H1jqOGQyXQyI7T7ki166Tr7YCuN7diOZ2bzif/H2HxqOtkdeSxxMpB2MW2ixE3mfZIFXY6vcov55Eom9dRejFlyjJe6nuKq29bnwil47N7F2DBNxuO0qunGPifB6Y52Dys7GQymRKeTMTEX5iHg+UFUSZHJo3eBNpXAIAZPku0S4BalKjmAC6K6xSkI33GyLh2dba7q3DOt/ZmNf5UQ3b+1H8z1eOfMsLkuM8YZ2zO3N1A2gXzO1aMCXnMhKHXDNHgy2ypyoPfmM5sqa4JMUzqfnpJYsqlIFzwJrnz5h4G4dmpIUIOJrTvth1MzFiO5lcCwBGZ02YraA1fRxUaFmNXCDZmKVh1VBRi+BSF9RXITzlGMlDUmWLfsdTEdYwEg0BQw5uQhLYBNsKc24qJMwNe+tMzxx0QO2ta5Mqa0gbeo6J+Tw54ppTsjgaVdU4AUGW++vrJ5gZ9r6vERPJkrns1fmMKRui74h0JSqSeCiomAQvBx60PCCqqLDMtRtLYZPqPi2SxGSvknOxagBvaJ6QKQpikihnziRXgHbUKU4ER7eDbPy1Tl3vLpeCpuzgq/hIgKGRPtfnPMW/IJO/rYM+OcfSWjZEXOm2rsM+FXpoWl/zHfTPoouEwW8w7wGOWDSQzpA0UonVAcN227DvO/+8imwDoeIseIX/mOuqqzBKqgyO47n22L6RA3CCl/E4D8Ab9n1fyFjB0M0dtm2YGkepdhDCkMtIqvgj1eXz4yQA5eYYf5+udOHyKtkblT/jPHEcgxEHZuheuSN8S+XgDLniki7FS2m/7SxyJTm/DBx59hTh1dE04ioFmPhFiato93fW9bo4c+1/+eyAI6IIuf+OSbmykDYTabRGua13DOO62D+8ENEz+rE0c9gYOEQ+XwV9qV50kZX9uekyBMqVVKMtQaVN+TYzrtF2WTKom1ouujMCI4aUkvz/63xeChSdwSvhHTzrr/M7OAoLNiujrBhSI9PthoFTo7ga7UDNFdGqLC5Yc4wnjQ+9NRWo10fXQbmKeWhUxwJA94ex+KyR+oxJsUImjvPEbdvx4X6HI3E8DzyfT5zHsYjCAFFNRzLI7mBUQgakHptM/W0NzRpi0h9o8cS4QSXGYJFH5dFFeE8VhVi8IsCCI+UxGEnN7DOeiBm872p9ul8j+KIL/ayvb3VBUvkhiktBpkh+Mv2oajSgef+mqHJDXSeST06E0kQKwkYEmgGdRzgMTBGOyjiBkIEkmtCa4zmVUDuneBEOGsMyaKwuEofx0q3RgSksSWOGyo4YAc3OfR1G0KVhrUPK9NUdtH5Z9t7uN9zvJPw+n088Hg9glLGVCaQrwhOPF9dmBwrGNdgmKA7ketThRzvkUKfNmjgdSFc4nA45gEmaawwQQYG0scJPkGB1iGBHtU7lB/H5HMegx0gX4pAO7xticvzSvTYOay33hm3bL2g35jo8SIAjytCbI7Nzbi4VUT3LgGGOkIMhHWLT+c6HOurW+1LPFCLpDcC+Y8bAT7/8CfZ9p/OrXd1za13vLYAsG3sd1s3oj5PAFR5IsnKAKOAUR2fGVFHYVmFXz22RXK34HkAkD/UqvMd4QyT9XwDGLTSNcdTisDiCCNEt0dIKzKNBFd+IDvDQATfQ+8slCy1PIBQpjt++V+hfYvF3ahRpVp46NP1Dllxz4MyJbX+BG0cvfRN/yB3WO+KkJNgGrlEUyPUCaK3dnFb/XLvliKkOsopOFU8zSmrq4isBbZd7rDWRElPBbxMzJ6bC2VrrtCv3joa2xrSLr6OVMMo+H0CaizcDnCfH0N0bMqWyyGsmf3F/ZN6YGnN5cQX4tDNdI+M6K7EaNat+LALZacE/s95dIJIFtDdDD6aE84eLaB2JeH/RgeMOym2TXjvaH2m5PkPrdNydGgW1qmqqL1QBYzpvzFLkVgCyaU9xWup53vqG83wiThqpmdDSMmM0M/gmHkqSxJsqDnYYnnHo3V9FY6Wvm/MiPl8fDKx0It6+Gc5JNNxKKLFIr4m+7Yg4metS2QEQYq0MGCTHKlsTB2icaM3wcrvhs88+oDXH2+sD4yCq1xptGMLoCeObyccmaFrYd/ikMrBtXaif1kMqasC1p6qINZeNBOXi1RTd9hvvn8lnPXTPLWWmXijXkNAfy3U+A2D8w8/x9a0uSAiNqesrSWtcUK6Qb1V4lL+1viFlA264vD9g4BzbndVwEQwTq+O5kBGVhaj/DZnO6IO5wae8T8BeZGa5RiYCXbAiL8E5Q3ItQ28bZcVZHep7lj6o+HFfJLapzsrMaSqmA8rdkSqIKgWSM3NuLPlAQp+CGI530EFcJNwqvJqq+VakvsB4HYh5AtmA4Ay3ECdoHFUd6RyDklEQEl9dAv8JqqPgxWFIXAFURYwj8gR1fHy/xesocqiBaMA82Z32vi9PEU9e9BwxVAYEEakUsoFCjOCYGEAeKuKu91y3POF/FpE12mvq7Jo6yHEO/P6XX8LQcL/d0fySa/Kum6s7FWRHQ73yVvGG2+22uujWOnpveDyfeBxP+YKUEgAaz6UOSvniJIut+vwJqJNm0dmBJVuMc8KruK9DGDUymPBwFu51eetCiwhsjfJqz8SIXJfRjEthlAgGHWoPGfhe+DlN/h2Xt8Xj7U1eOiTObfumi5QNw75tCOV9rE7ZiYBalDtlLrInX2AVrsxUKflB84ZMSfYXb6qC9nTwBlNnt9sNt5cXBiWOCWvsoOGGmcB58rO4ca33pArJLXG73fB4PHCe5xpvoGSXCYQR4jqOQN+o6KvIiExbRXmtSY5D+XxMxQpAryU6BhOlqKKWDqT7QkfN60zTYakzwr2RE+cMJsT7oj5oxuV5oTTQfuzdVyMwxT/yrcnan4gPzwr9Do3nN6eVPODKAsCFcsMN5g0neGEVCgLj2Bjg2jnnIPKgDB0qSbjZUveFmZEfp6YPiCVL761h37f1O7XKO6sTMrlnoiUeg6hdy8C2bSQ8VxNhhnTuS5cClPwiFrTFuzlHAPMaZ1dUQUFMtOlPfLi/wK2JhsAmYSY5ia0rJwwcG2UEThxsAsGRe5qxgBIXMgEcg061rfmVnh5C8xr5e+4X8uQwDJwYSePN275h6pnHnGxEDfCtY54nImmUWeoh9w0/z9e3uiA5z2N5I2SU536qEixiKWF9y2RE9SjGc6yuwDWfT8SKrk/wIh9JrgZ5DCwGujr5BBUjNXcrmL8YzFXwt3edYWEzaab5HFGZPocgSLLPHZrJmvHSt7W3Fl+jSu1SfJzjwNZ3ZALHOXCcgyOMCIyZS8/v8NVZR5aT6Ht+SUK/BMq/AZAlshkyy+BqYJ4H2d3wdaiZLqnU4erqkqs7KtIWiyD+HlMhXb139LYDDat7q1yWiCu1dxFR98rlMIxxAANEnxB0321dD8zUiekZZiyvCGRekkAzFV7qKEHX0RGK4jYnRC9XYB4QPNxLsbIOexg+e/mA4xz4+uuvOMa5v1zv3avL1bhqMG+D5GVHa7sC1roK56CtebBjts1I5DRbDqvLFVZEM1VRSGAlL7MTd9jGchCzQv0OHEFy4FLZmDxvZiLbpTBjYaMCLiXZRAIDa5RC4ybZnbeOmKcK4QvdNPmB0PyT6BirOyJCljzcEbxIMwynCHMA0Lf9QpzsIh4jJ1UB04i6uaE+uYkEy3EFoX/TBfdXqwG8GVoaQ+HMxf+hH82HDx/I4ZEE21M8G0lhM4gMpt6FwfA8TlnTJ+WROrDDZUiWWHLKMYe6elnh17vz69I/z1PBiJ21Vb2PFVjYsXVa4PfG0LVvoHpV4AEAeA4s9EUqLI7UyreFZMxUAGQFN9IwjZdkyY/r+9AQr2G733guPB664BNXArv2p95FBf1lgsGCdbE1obEawxQQwbOR7ya9IY02ADbnlfUkQ7TVT8bg+zdmV80MpQtXM8TLHvxRKEn/Zn0JHGDM2umtoZsBRsn30Ij6s4+fAZZ4PN8ox5+OcYw1MmpeoZchxFXnckVUzIlPcr4mgj4Rx1zrppxeOPIEzDds+wYbQt3MxTucaJ3k5DknnnPAZsCHYet2NTAIODpS53lE4DiOle/F/3C828UVdARH0RozwvhZhhLf4XYpjH/G17e6ICl548y8CIcOmMd6YYCgv2TVPUqCFYmp1Egm5+JSO+jvXlIvVQElbcxAnOVtQZB3U2T1eQ6c58HPUvM1oTTwWjzQmKbmxrqUoBENuBF9tbQ6ZPX/lvEZoE7VjGhK0I3zvcOsd85/IyitXReyGSOj0eCDXX3EO8RI1X6hM+wmhgiejn3f8Bis4Df9XmaXsiMFGSx0Q/PNQgiqmAqxsi/Oz/XvfckDHDnpfJq6OHhw8NJk7HwA2YGdUOacgRwnod1mQgkg3sKmPzMot1WWEAwwb7TG84bWd9pzK6k4tYaKE1DkNctvSmdr3EBPkRtn8L3h09sr5Y6+obeO274tbk8vsqqzIJlyTc2cGKOk1KHD7rKtrku0VEGA4OmYcGe39x4F5H+x2G3ONOGZ7KJa34S61HuSIsvLC8EIiEVcpFkA3voqXmKc3G9OlIEcLSI4OWs7WXHDVQxJqh9AOSU7fxFYJ88iPKQg2ZZqC1DsuzgR7PJUGNVtJphU5+QaO2b5WWgPuSfKF6PUcYUihRtyBD5+/jle317hZnj9+mvcWsOGXAoq61t9Q2y9YxwTc5545gF7UBH1OIZks339DHMWPciKmCBqwvGa9iGqICrk0lSAGJ7HYEpyY2R8vRczcsHejjfMc/DqalIkDRa2F+lQRTVUROjxwYAcheQR4aD8mnk26QY0clbGQZNDKzQqr/V5PA+qubqiHpQubNbQaal05RsJtZ2DhTK7liqwbJFda78xnO8ENVREomZM5WZx3Oe1/ut0ESJylnqqb2vk9F704NbYjKTJRsGUJs+ohBCidB4nCdEq0BgqZ3i8PXD/8IKtbXj79AkOpSCPU+NgFWGZ3CDvGsIiO885uJ+c69L3yreiOyuEsJp10OPJsd0MHkQweB6AoYYGTBV8E+LuxIX+5/o5SW5ikoc3QA+gMqOk2ZkWihf5lyaa6B0xOH5tybF0ycl/1te3uiAhwTJWZwDjWBMglNXbpgOLSbDnQXIhTagCaA0VFbPmulncRS7dYukThQnmCAD8WUJBSg3z9va2FkohLPomrOZjCGbrkude0GBzWpFTXgaNkHoh+YAuHc7veOEeJwO+TMdIKgXzfrsz08CpMXcjZGyau1ZlwMNoLnt7TOnix4kIjcBQxEV6aXBGyj+37zsebw9srWPbm2yKueCZeXIZo7lGN2X+5QUTIlFs9dac5E8dNu5dhyYPsummzoKktWWtPU6h8UR/vDm2zWjOlRMJ08yYN/IcJzsdjQBo8z4VRHcgdXKFxhJIEWhVKLjHN0iVdZDVRSHcmO8smaR5u5HTE+/m/ynoObV5IUQpUh4quDoNQGsUQuVMh0MtlqVIoOyV6b0kYdY6i3OiFE+tazYeJC0Wr+p5nsvLB1ZqouvzWiTQGX42q8LU5eXOIn777LOVzhpejr4GbNt6TgljRMI51h6YMS41EoB963zOmcg0HOdEbqCtPXD5dHD1o0Iwx2Sft+5F7b8m5BQprorxd2QTY+vyijnRveO2bWwURuCcJ7bthjuA4zxwEzpoCfgs5IgXvloLYEuMAAYCx7vkaajQSSNfgwVTAKAzco0I3KCLj518azQxKwfVyGQuEHgudI02MuZCKSMvBZY1x8cPH5CZeB6JI8rzouo2WzwbpM7XGbyAYehbA0pxAWBAnIx345+cjD5Y60dS6gRIBD1Midc80zLKsIwupuEuM0GtuQBRM5BrwaZkYm8UEYyQL4Zz1NmgYjqvwoIGbnIsfYcutdaASdTxjJKp8vfZy9PDqc+bhfrGBJSY5SK8682RSPuO94UkefbtlQgHrRgOeGO+zkQuv6wqpnnhz+WHZbauIo5PtqvJGKMajUKM+L9bb6uptjLiNDYeNs7rfC1EJrD+/hwacW7vRixV3dbFV81nzoXQFjhQiFvOKbS3fIYSP8/Xt7ogaRv9Ftw6lj7eeej0Tj18XfYunkDxTBK6cFqhKNVxYqXmAkXckXSt2RpbIHMpVmJeG5MEwlySxwy6s5qLA2YcPfhSMxgME4YyGavL2MUajzWmwGDqJ4uKAdkeADAFhjV8eHlZuT4VS21IGqzpc9fG5MihwxptivvWkGH4lG90C6xKGOCsf7IC5q/NA3FE4IuvfooPd8pdzemrkDUW0XOd7w/RBAuFKsKFPIRIf+7OpNaWtK8vkrJtjBOfRDdK1lndMZETbTIAQ9V867KKnpM8hYn1nAuirmReIjy85OacsLBFbC1S6ZhPnNtlD99756Hxzr9mEfz0+brUF1c6qEkOzAILupDKFZU8IJF+I4gWCKqu/85ZOSPF09A4MCm/K1TEnCom1qKpkUKRXk1prynydXFitOYyOD6sosSF1iEEUStcz6p4B+63FwCOmexC+btqBDqmOq3ys4FGXaF1LVCwljauNT7mBFxIgf6VsVIEL3N5PBACRCAuQqIOawPXHr/j9XOmyH67OGYOw63fWBiAvkGfPr1Ssh5gYKCRt0P3YUPGANC0lq/irwq6ORdERMLrvi0PIva+wPJGAVh1KVwtkkhO69DZYeidna+7kfwaU3ELbSmwyAFQcY/E83zi48cP6LePsNdXIiXi79B+gGTzbb9hiqi5LqQUmlPO2CgvWYABj0QhvfYRkoRY+alMnWUx1IBolL7Shc0WUTi1V61ektNFJtNEQpd6DlguzsvNOlUc6aKPpB1BJZAvhVnmOrdhSrcOcsqQuUarbdswHDielIyzEWFRrY+2jO6q4A7tZ8TkKCgBJJUoQ8IH6/ydrIlYn4peEJJTjWBlyGg78twMfr7K9qnG/DgPdEDnqKEbEb6pfLQxSTD3xnWzmsCogivWWqqUd/6OrjNY/KDJJOG1NAo5iUDK2RiZ5JZkjXR/9te3uiC5v9yx3/f1kMaIVdmfx0SMlNbflIgIAE5d+tbWhWYap/BiYUdrRii6yLIzYl3wTbO18zwwjwvucm8kFiX5LBVF3bcN4xzoW0NL2ctbUyGiQzGn3PhEXhJq04wjh1ma9saslr5P3NXBLBtvM2rYk1yYcj/EGh1Vdkqui6c8FCYmzhk6yAF4kWptsUhjnIt9Dy+5XMfj+cDr8xUfXj4Ak7NYjltKHgqEYHkkMIJjpX3b8EGZIdt+EzIAGZ0xF8JTRVDWeAeLnAcdZOccRA5bu6R/2gCRyU2qw8uKQ5vv7J+Tsl7vjQhMFCLS18VcWQ3vR01Ut1BS3HtDKUKq0ynEIgyr4yvisZnBIjDHwBFPrcO6QDaZh+mCTLHVC8INElVbo5timdPBsA60VXAFL+etb4SxRaC0gtQL3oAOJOC6yLyiC0rqifU7AbbcUNczQSLbhiMSMSaadRTJskIdqruHOri2nIGxECJkvjvkeOyHEoTnpAfQnAMf7i/6yVxYKwxSlvhTxMbLwlouuIGr+0RgmV4F+V5oHWaON3EdZgbS341D0zUeOaWmYaJxROCcoS5WRNlSbxUxWNyZipBgIjWfZ+oZ1vpsVpwJFkH15+qSIocAtA3onaPkyRyi3vu7n5fyV6FR3E+//BL7vqPLjG5Iqo+QXUDwQqKz8LxQ3yTS6Vvn2Rh08DWvCHr6bZQ0OSdHVlsHEcM6RwJwT8D6N9CtiMQ45ypSeenzF1/jFzgbHjDMkxw4jXP0LIlsyDNKRSNGFXKORKChLTei8hCxd83A8XxgnMz9mXJlJXLMtds0Fue2rEKkDlrn71qoQJpQoMAQGuEI2Mm10fomZ9cAbKrhCmQONHSpcFjAV4BkFfNNykGi1kPnUagRIUpj4vV0ayo+YqFrpVCyOtrU1IyYRJvNVlFPwreQRjeMkKGdkQuTaXKE5XJqTvM0pNEI8uf4+lYXJOcZMJ903xx04pyTXVMLwG3itFOwrFUpt7IO1sLVqVYXTiXzelJOaK1j399Vq+/IZt6FdOglLba/NigbZ4N5XyTV3nZuxOhigutyNKC4FABW5zABOU5ORA5Y9gX1VScPVbJ0R7xwPo9cm5S9qVQ6NtcMGZCLpy4rqCACLp5OXXKm8r06gd469m3HOE4MkWpdyFH1Sft+w4fPv8uOA4am3zcT6NuNigwzTBAOtjYQ86C7YczlO0C1h4qv4M/3RaqDOgt2YbWxIjmGOG1g65TgNoBcjWYilU1d4HWJ2OLpJC61yRjGjAhAgYxkj1NibEjI2MwSNi/khnClOjgAb5/ekFPzdBECiwA99axbrzmxFDi45NclEQXk1RB6J9D6lgILAa01HYJWqojiBLEzMnUxELq4JN+6ECOFGEXleehCrLGb+AAAx3TnqaTULtg36QMyguND8nPKJVbrX0VkcaXgJUmfzELxXAoEM8Ot7/DgeGUEL2FvhnmWd0euPCEkZdzs8DkC2Kyp008WVlHcIDUUbJZXNlUp0uYkwfIYA4YgAbqRwM1xWsAjpKgy2MaQuksCz86ev3YAuV0XZXJ/pBdSotESu4OFaIFPHW7AwEROZU+pmG5G7s4mH4r6uTwmGHFwHoFSsLl3uMnrxPMq1EyjuTmvcQKAFqwQbhs9YmblT/VOT4wJ5KxxLR1eWxY6VaRcoNxGYeR9DZHR5wjsFeEhFmpx06gwZIxCnQd8Zxy9tL6v0SE0sphqHnvbsLWmPZTfQFUMQHdy4mdiGSo8zrdVHI+KBwmgvCZmTDT5k0BrrqIgIq6soRkJ7x0dtkaupuc/lddEGB30+gi60p7zoHql1F4n92dTMcH9ZTQ3REdvWIVWQo1byAckEruzEOt7U+FDBKxAKha8Qp6EmHZ3ErA1Pu1miFmiiJSRIt/NtjG+xMC8MHfy6cY88PN8fasLknGc9LIQQQvgZRszRc7hA3SuEpQctiDuxQ/R3VGOl8WFyO6IVo53vDE4z83VRZacLnMsp9iLmMV/P5LZLS6SJ89uwZXvOs9URzcwpPeuGGf+vqmCIm1okb8jCmm+55G0opZnhrXL+8CT3cAmA6njOFanZWxL0MyoRCqybfc1IgAEkeMirrVm2LEBM/D26RV2S6TGLmgl/0u8fnqsA7Bp82YCjufaAGXRPmKufBN3dhxnkX0AHVAgYrAOb6mEVEDEnEI7xAtq1/cq+/yS3zn8QrS4FFiIuZJPW40SYr27WmvbJnnrnAA0ghGhrt7J6oAjcZ5PPB8PkqqjXwhBav6sS6fV+lS3DANKJ9JcCcYoEjaAkhn6xY4nXD10KEKXan2a4olw/u0qbMKIklRmiW4RHjyzVGvsyO63G1Lha4SbU/biRGbWjPtd0dyKgFpqnhpRav+VVbWDXCfC9E4+FQbGTEkVCSEzs2lKpUDeDkeFQueksKpin34plM/e7ze8vb3x79alM4iCLGK4sdBrkjWPebBgmaFLgZ8xYPC+Act/pAnQMkHmudaMGYgGhsMnQDvHxk4yKnEbqPDIQlSy9rlw8vILYUQEixoWTCduKLkmYOY4ZuCrr7/CjMR3Pv/uWiNmfGYmmeZZ6wmxuBnNOp2bVQifkj9f45vJW9wTNAqk39O0uVLRV3Eu5CozYb0vpKqJXN46B4TjPPUeKIWuhGwiYVQHpoEcGqGergYFZmgIzBi8aOU1cs6JyIP8KV3+ucacRC2aGVrn3zEA5h1b5897iydOFVpjSH0JAD1gttGD5iB62eUAW8U7UacTfd+RaESlaoQIFVNrNJzycqr6k7wSgHyyOWp9sYGYBxOKrfnKOapsJ+YR6WwNIWag3N51otSIdiE/NV6xq/nxbti809oACudUgCm0/utOKKuF4pmYMT395/n6VhckhJAmDL5Mtviw2mrq3Rq6ZoEl9W3tsosuEmUKDmYXxkN6zsSsym494LwKBF3OtDWvOZ+pMufLMSto+Lo4c6iGnfP6M4ItEQMWkhSLNFnEL+CCdLXsVlEEM7rbV2crTkF3FiQsMtidH36QtAUXGU/5M0Ugy0RxPEh8vWaH1+8NHmbgwXy/3/FpfMLj8UTbk3bMpt9pTqmB9FwxVHAI2QQ3BaDNK4LrBOWsEETrdWiVu66eaaZklJko1SjPc864mQQrsywvgkshUUW6ZBe/xj1aLwYTAkE1UdclQ4nixPN4Uw6LUcZrVsRzfrFaEHQsxOi+oTwzAPFxSiUGh81L6VU8HKgIhi7Atab4Ipb6qZKXS+1QBEOTBBfGg6mbZuoaKRR/yqLgQn70QiACLOJiHV5ySkau+XNzHn46tTh6m2PtvcqQaq3B0xeHq6D29BQRmQjOZbRV8neWjlCHPjUGqZk2rCzZHfBdPArtB+PPoYqouBeF8NRl7ziVT/N+dMRnU7cDSaYGEpXfHm8rHO627/jOx+/C3fH29grhiXCpjd6PPmo0wDOKv1fT/4ZrRl/FYSlSqqkyX/4bFknzYdM4N8jr2qIQD67trTfsfcPzPMh10cXNrRDorkLN23JWZgP3TeKwqQh0IQS9NUTjBRtjoLUUSsJ31JzeLEQF2AzWfitbBqKIRCjoTt1wTDqmUkbqqzieGiu5kI4q4A22yPk1zfXsqyj2xtyzmVPoJMm2p/g/ZSoHAOXGWgXQXE7HvDtGDIzB99Jb09hKoZyQVQGSiBVkDIdSdlVzilWs2SwSMtdYeVbx3OMvWZ5Yy65iVnAsC8NAIk6hKb0B8LWuLcpqQuesULbW2iI/c2WL1B3FxyQ/5zxO2DD4BzqNFxew9wbPhjmDwRxJpH2CI6CuNdqN9vg/z9e3uiDpfcO+bST3tbqgePgS8cxlJgPwAKrnUjP6lF03AC04oCBydtO8zGpDZUw0NOVqlBSNDngVqJZGhIZkrpo1xoIe38fAI1VsZGo0UeW+A8ZNF6DHQcGW1VW7MyGyacZXhkKZAQstWDh26xgAjscrC5MOQOMFmmhhdfW5mOSXwRcfnzgZEaqKgcDJzlVKn/1+x/E8QEUDIfDsLNDKn4HHDTs+AHIG1PfLWGFbpkuqNea82NQ7bBqraKsWGbVUJ8irE/O+wc2w9X4x9zM1H7+cc0PPnnktQGs72JXE+jkOBxpnpVEjiDGR48SZlA32lFw36m+B38dEZvW25t/1e1dmUMwaPxHyJUmZXAbO8gdCXVmNV9QOUVEjlEk3KGSHS3hVqBxn9PzcQ12pIYHRkK0tBRC5HeyuvXVgDAyt2SICRgSexxtlkEZr6QQvuDlOuHwaMudCxspC3JMjm97FOahUUDTOnMs8S5es60Lqzs9Z6//5PLhuITnsYOfW3XG/vbCbP0+pLC4pvIHE8tfHQ3wuCIkJGHyNWBhtoILk3VdEYu8m5OSKqphJXsMPvv99tNbx1aevGdqGIh37KqCqSDL5SJiS7mJOqeGAeZI8SQIpL4xCdzvoEtxaB9tproXtdsPz7YFD5OGtQ5w4x+effUDkC2YmBiEzXTzkPGTmN4iUI0QGVrHcmhCRqNaLe3Tfd8wzMI4B2wz3fSNgAo0NUlYJoXPB9RZy4hxxjRh5JbKh3DiWHmMizit4UrQIZLwrIhIwFaObG/beMSeDGs3lRhqBW+8snGJy7OPGwgnkzYxR5zFNAAvNYk/FNc3GjLyNqTC8Gg8DuqTlK1RIUKHMvXd62Cg01XX/wKTIVJHOYp1jQHsXDouKNlCRPOdc9viuxhHVQKJQUj7r5g0NuM7O5FnGltKWerLCY3ln8c9lJmIEvvzya5HyadYYk6M3940IZ06N1qlwZK9PpPT5HPh5vr7VBQnvyVSXp/wC90VWdP2nlPbVmVRRYCIh9a1ptssXXt06UYjymBAb20s6qJ9hfs1iVa3PDF7fOZEIGVI5eucGYmRMMoYzy4SKxccpmaZZItchSrCdjpyXqoNNGw+pnGWERZa6w5g1EIEwqWiMqiQ0QnqEUhVvrsW3NrgbuREaSRUKZN5RZNXVXQZJoft+0wHLjbltG7L5sg9eElmW4dAwaBE+TSNloYCo4K9EkUhJKBwxdAgZmne45L+R5MHUz6pnM4LDroAs+uGEcqOC/WyN6coOnoTAtrp7ExRKwtuJEZQ9pxsiSgnjS49vWeM9FXmTNs91aXMN4uIC1SMNzpt56ZItv20bUmJS/XKosRVdbRl7UCx+M74FgOsy58Q8RV4eE2OQjOkGbN5g2waL0Fs1ETaThaYbvDds0FxZCgN0XzP9rXd4b7jtO37y459wvBGxOuG6lCxEskuG5237Dts6Ho+niHYNZlMqB96D9D9xwELS+Mr50TgrWKQSqEkQrGcuxzymxn4uFDTXqGIMprEupZatNkQo21wojKEShK/QxTG4fivLpYqWYwy8PR+43e7YzoPcAVxqBQCrAYGQl7JE179UgWCADyr0ko6tQ/yV4g/s+7bQmzLEc3e0fcM4DsQ4se8NzW8LFeQf53iC75tdLszB6Q1/n97lBC3FUf1+lkzY5TitWnjDftsRD66vU+OW4uIkgPKlgc5WFrVYakQqYfi/ua83cBBARU9acfz49y/CbgPkVDrPCWCgw3Dbb0pO7xht4DzI/apoDazzM8XNulDHZhxVmH7GtnVQBcl3dNvlpnzG4k+gxtGNfJZCGbhnKiGZ+wvJDCF69jVymEACMUeWOjeS796MKINuFY2eq2nGkquvkX6qeKkV7ZAVwsYiacYaAVajVPdcjU0LkU0ENt8WXydG4JwHsN+AmOgNF4cqchGMZySezzc045RiHH8L+JDETFa4AY1M6N1hgCo3vZK8UIlIcPwiKNM0e2tWntk6dKFFog0aAcyk3TyLHFbzqNEGIOiQo1TUjBOAZVsdWgq1yYT4DyxYelMYVmoEFDRuK1Jj741jqXXw2CLtpYinJmY6oIsoWKSMyZHMy/3OjtQZpHceBzdyFBEXAOhUSuc+wvzeidKw8e6so8DDurpegEXMfr/xXkXijCkpJNbiN+8iUZKfURkk/Abc3Ibrn9VmLrUUUJ0330H995KlAe+6XuW+iAw5I/A26VjJmG3DOiAhuXeauqiATci/RERayCToGJgZaNtOOXRSLTM0hskMJKGOhb6VeoEBd1xBpbJACinKRGLCe8fttmNvuy6HjvMMkdNM6Jm6shTKUQeYAvH4TCQHBA8t+jkI0bOO5o7PPrxQFQLCs2O8i0DQel1tIgTzyniqbxcHxkAlGJC4b/syGRxxHZLckyyV+rbhdr/hGKGIBV5yZg3wWPsaKuiiSJKuzhCFOrIZoVGexkFmeB4HC1QVtiYEpJqSVvvXxMwxbshCQUtuD6tCgQgBhAo09+WEWWu8FGyf3t7Q9w0wKX0WcEfeAuJCSTg2KTi/zqky2KMipBQt3A+T55KxqGq9ENzBEXQZc+0dMQbeDiaB91aeJ1hjUY7sQIjdOFZkXS3rcFOXjkS3Dhg5HumOx/PgqAFCI1tH6xPneeD5PLBv2xr9VOHqGwvnKs2KCM3/fZHQKcvTONd8ZQWVCixU7BORuM4F8lsCeB7o2w0vtxekG/b7jtfHGx6PB57HIUSNJzilx1VA8AIvxBQ8otFWs1bjdbmUbhvGnBiaEztIYM9v/I7X6LG2UUcTh4xFb42uKISwxdmZ2g/lmork3VE8yChFTmCN6It0u/xdyGalKmczNdYsqEKNkAsZTuSKXajiHZMo+UAgYyAwYQHM44D1HfBEriTtXIWr673xTDNY//lKjW91QVLzsPLdiEx1fo4KW8sMjHmiVAYBA8I0cuGqn1kHFi+NOtCtFiIKPFCHJSla6dd14uqCYHXSVhULZA4gGswaDOqGWMSCp0AijEVDl9V5c6AloclIzoCNH32pgBavJEriWiFtTmJRo/PrtjF99fF8Ih6Ml5+jLO8drQHWr3l9BUqNMXhBelMWEO1/Ur9Da02SsvKR4IG+DghtulJt9N7R941dhZX885KaDhRXgCZCzRva3tXt55WoKf098kIC6qvg2ZKUrmj41nDbNuwGdBmiUe7GMYY18iuex+MaLwBLzmjAyg3K5mhpOI+DF0pUsTtkxNeEyrETLrj+drsJjeL72uSlUoUYtP4A+l7stw3jnDT1O09UPPty2BQvB5Ie12FAaNzVQNlCqyKVu7ExkZeBYxNvzweO8+Sl2conphAHFdXmiwNS5fiY7KDcqe4yAMfzoI15FXH6HM14OH/ve98jLN0bznPg8fZ8lyMElB2/GTTim8iQhwwIZ9Ns6XLutMbiorUOb/yzo9Ky6wZ7VwRU6X08TxZVtoHqLP6yc8ylmIDJRK51oDV0SyRDkeRTcxWDizMFw+NxYu87PuUn5u3U72bGIk0S1gwaxJlUaVw2+r3MkRPyzCg/IjYdkYHnc8IO8sHqMxB5JBo6nO/seT6Rua11DD2BtV4SIHAvw6sIwJge3WAY5wBy4pgT223Hh89egOfJ8MlyuZ7nQlfmHDh1+xbCFBnodgVxThk2wt+NB8zgQmZyAKYzgly1xMTA0PdrykYCVFypkAgERk68Pl/x8eUDxhw4Px3Y9hsjHwA8zjJvS2ydnJYzz+UYXEVEeQKdY6DcYZsQwQbHOM8l+a28J2Ya8d6ZymbqrVxgi6MHTHCNRXLfRJxCeyvXpiOfJ9WcnaP5SrkuQ8g0rvkxq+itBhzvRm2+wDhmVZWC7ioGQ/4ha4CoRn4k/bwApYD3juPBMWkkTd5sNOziV67iKorwv11cqfPn0/1+qwsSa+RrzBxy2+RGn5g4zlzeEFWvjkkb4ko9pPseIWjaq79TFiyoVT/L+LOqEySJj53uZYKlUYFIRqxTBIQLeQFEyvoGk1+jiJlaPBrDjPPadJE8JFzQJhJT4u4qoIpJSXoB9f7H+cTr44EyzaoL1BJo6pK9CcptRBra1tdlzdyQisnmCGrN1N3EsQE17lG8mOsdFWLV+k6V0btZNbse/i4wI6RPwEHdpAZuKdUBxFdwJ7QvuLhInzFCslVfh2tB7S8vH3C732DNmX789raybEr6NwYv/ioirFJ0F8ybYBZI08xWF7RX5PzUxIs3ehVFNQxo3nG/v7BznIFIOsxOdWgRgXGceo4Tr58+4fE8yC1pBm+U0eYsJ1cIUbpGDnSlIu/mvRpsJhM+7y8viAj8/u/9ZRWcPNiIukjuGDI0E3KUyaVVDPtFlJUKJMKomgk2BM/ngxe4xn0sGhocwHGc2FrH49Mbvvr6a/Rtk5kdE0zhjjwHgq3DQkIK6anRXQRVFEh6Y1D2eynCWnOck/tjSLFVox6Yw/qGiyHEZ0bp6CnCdSGovtRbhealfsaYV0icthZ5ZADiDLSXGyF3eR8Ju1ykenaXRL6yVonxfGi+KQuIKqbeb5jK8XGNrkYMGu5FmZKxwJ/zFJpzwe4zBzwURAe6E2/bjchrVHPAFz1m4hgnbjtjD5BtWbG/vR0Y8eniuklSurJzmiOtc0yb7yzvZ8IwsPWOzQ1tazLrqt8cMhAzpBtu9w3H8cR5DCQayrm5o0buqYIzlZXT0XpjGrXUbK+Z2Pcd5zEx5ltV2fh4/4BjnCunxjS2IK+rSOkcE64sL2dhYY3EZ2KZ9PLYxL94PB9sctU4jlLBjVOILJb6jmcga4Yp6weizhNIjmG3DTiF1nFcLDaksYhwYyI076Rgom4VeS4vmTD0ZldTJ9+qdKNsPyGUsRKo5TgLLNJ/mew1b9juHTEbjoN30xmJeSQ2mZBaXudO3ZvvvYp+1te3uiABNI+fAiMNMmTh4UJlRlu8ETgXG/kWhPTpfaDDB/nNy9ZYSAwZ4mRWV6GCwlut8QVLG4jyutcHckGEQM1wTK6JqM247vCLkzGeT8rIhO7M3tBb0mwKKhz8+vNM+9TvO1PCcgOMDp20t6/I6kDXWMYBbFulWl4Of4GBKV8O3m4qiuoCK2hODHwCu3kd+noZXMhM4XVrNJlKMC9BXXTWfF9wOOXRYEFQt5I2Hp1eQ8TYa8FHJvq24Uysy92bo3tfgYOvn14xkTjPA+c4UGONGYHzeeLt8YbzPPHhwwvuLy8qSkxFyWXgZfKwANRdgIdixlDRmQs5e++e+untFY/noehvW+tyzoExeRFOFURZvhFWXI1N6xSAEIgKY+M/8kWmo3usK7Ld1gX++nri9dMb5hh4Pp60BG/FGQnM9ag1Filzr0yRabEQwNURQXkY4OE9Y2KLhMnDuw6jGYC1jre3A1/PV44TzXmheaKroHJ3EIzXJ2kNvTd2qe6Xh9AkmZWfS4RzKTtMyFFXIVlHoRcq5kQTMxO9HJLrd9cfTpRjs33jgC1ML/S71vq7MqnYRZ/jwAd7wWeffcQXX325UMAlHaeqXIipbOM0tpj6IK3fAO1nc8d2u6lwzDXCaQ56h/BgQSaJ0pbOPidYjHZrUrDwGIqATMiayLW2SMims2mIR9X2DTbZIGQMnM+nDLlotDirmFHj5FUMg79n4Mp3cgD7bSdh3hWLYGzCmg7TOQfGlth6Zy6Yp8iAF5E1x8lnqEC3JdkXF6dUNTgnbrc7HsdDFy5Ro48fP+Dt8UQezF6iSVwT6lXPtgGp5w0V/1Yjr0L1WJRYAltS2TXnxP3DDe6O43ksd+tW5xmvHRJgLQAlcmeNLC3FXzMguMaLJzLmhBkbSlIKHbs7YgPypOsurzpD20jOjxzXSK7WHxIxDp0PJLTPOXFGYEveAZVPVdMGXouOtrPpHue5RmzH8WSBJPTIjIKDjFJSFbr6N//yn/1H/sZf/8a/8W/AzPBP/9P/9Ppnj8cDv/mbv4kf/vCH+Oyzz/Abv/Eb+N3f/d1v/L3f+q3fwq//+q/jw4cP+MVf/EX8s//sP0td9h/wy6EL53bDtt/Qt51EzN6BxgCxIybOZNrhcRICS5FNy/0vk4SonLkq0FT/W92j945+YzyqeUN6x4Qj4AgTH6K5JIx5ue3BtGku9LguX80NMM4T53FoMTMJcsyJ4zhQSZCEUUX+8i7koa2DZA5Ka6vaZgdJdKWcKGPNqbk8ZoRSgQPnAGaQRvY4Trw+ntBkSd2IA97I0J9zFW/lqvr69obX5xuOceJ5njjOQwqYqzOMd51YjZnq+83i3IhESUQ7L+i+5qF1u+gwp++HkmqPp37uXO6Y4zzw9vYJn16/wtvjDc/HczkuzjlxngOfvvoanz59jd4afuGHP8B3vvMZ7vcbUzPdtQYqS6QcJCcocNPISSiISfHkYv0ndNC4/p0HzjjwPB749PqGr79+xdvbA+McHG9JRUJpI7Bthv2mtFKEWqxcD4EySqa99sb/ePNVDCyOhy7WMUjw4/qY5BKdJ46D/xnHkLqB/I/nODGR+PrrT/it//1/x+/89m/j9etPiHMgjkCMdyZ3vUv6yVyS/i45NYPuj88x2FXp3ctIlh3/GDjHSRJeZxHbN8e2d0Um4BsFwvsuLMXjqVFO+f14ZyRC31zjNBW8kAlXzrWuKsNk27oIuXj3/ZMBj/NEzFNGY5dZWP2OmY5zcLz09nhVUUw1Azky8kgxylqB0O9WFwAWad4M6/3VXuobXVj3fcfLywth/EZ+x9Y3bL1j3/ul/KhxgvZb5cEA5FqNwVEg9wTNJXMEPBMxT8x5IG3AGl2Z+95UcMxVjI+gjTw0wmYxUqTranW430YogyWArhFFjegK6bQUuT+DDVKrfa9i2B2phgR22ThMjd8vjiAVXxEnPtxvi4s0zhOvn17RzACR7uk4KlWXnHr5uRzdN2y+Y7cNNg02mPAdqUIbPLda79i3jaF9byf21vHhdud453linlTKGZLJuyjFn+O2d2zNsDVGAmRQDWRJjxzXZ7Eazeq98r0NNHfsjeiT64gI2Uq4l79QFljLteZEOeccmHFyR+RUptS8FGF1dlX3g2uvtE2o/eYITHLppv5znpjzJJUA/w+TWv/cn/tz+Hf/3X8Xf9ff9Xd945//M//MP4P/9D/9T/Ef/8f/Mb773e/in/gn/gn8g//gP4j/+r/+r7lA5sSv//qv45d+6Zfw3/w3/w1++7d/G//IP/KPYNs2/Gv/2r/2B/oMMU7EoQGGup/pc8GfEIpAsleQjxGB5aTTLhiJ3adIS8ZquLpDQEi4OVuS1qjXz8AY5+owylSN0r3r4jrfzybVBQVK5UIWciEyvGYHEZw5Cam2hm3bOZsHC5r3Bm0lB+NI4fJ7KGlwVfVWjYaDLHvxKx5HqJA4sPeObeuLgDjHXNkEao4J7Wt9zbg6Zj4qlR9mgpDl/BiEqL2+QR1eClTzJst1YCExMwjcV3e19U0oiQqb2iB18YpJ7muEM1WoDZikkbGeEf9uc8f9fseHDx9EduWYz5HwZMeIhA66vg5cegvUyORScM3BjTwwGVonAmnMRGCgpTo8Rbc3Bc7FQle01vQsaz1aq2Axdejgy6x4b290d+Whzsvdkwqb8tyJOQAhBN6ui5ax8nye6Y452NVMFcWvX3/C4+0VGcBxPPHjn/wE9/sdf/gXfhH7yw3nkIqgAzEDt9udzxplWR/sEod9A2UzQf3FsQnJzc0de3OMKQfPkcv2vPslmTcA9/uN63EMRByEtReSZZJW2rKQL8QthSCeJ8dfW99WEbf3DWPS6LAXGS+rOy6DPr2FMF2QbY0rz/OgweF5qmGYC20NObU67z/tjVhdaD2HmGO5ugK8XOpZlToI3pDpiMERYPmyNHFq5uRYOc3lepwsss0ACzUVdVZIbVK8r2a0TB9D2UccXfF8+IDH87nOBEr6hUBliFviGMEjts4ZE5oxIBJmc3Rw5FdkdgjtrMLB3OlcKoMtE7dmu/kizTpYaK44B/CZzmSh8Pp8wE+NJOfA4/VAax23/c6WIhLb1tGbreIIUohhhsZfvMQ9gVAoojkLEm5bWk9sVZA8Dxyvx0J0UOVZguOhQsjVEG/bDZVvNgYDTx/jwHkMnv/3pjHXxJhEXF1qmGpgXSo/xolceW1tb2sNFgZBZIOGkKP4Sc4m/hwnwvi9KqqE5xfX73tvoL1tyAakUWn5fDwkdJAlf9sAKIfq5/j6v1WQfP311/iH/qF/CP/ev/fv4V/5V/6V9c9/+tOf4t//9/99/If/4X+Iv+/v+/sAAP/Bf/Af4G//2/92/Lf/7X+LX/3VX8V//p//5/if/qf/Cf/Ff/Ff4Ec/+hH+7r/778a//C//y/jTf/pP41/4F/4FErR+zq/Pv/ORiY+CxBKN9sWLUEoIMMdERJGKYkkHAxU5zkW/3OWELIwyqMJlDmYNRERU9rTm5DUA8A1yCFUhug6Yd7wLvOu4BMFHqYEA1IturWHbJSHDRM5TFa5IYMAa17TeUBOiOYckrL4UHyiCpnxRzFQ2rKkRTcpuW2e+gf7dUptAvEDxASphtjJ/qm72Rli3OrA0KghCB3WxBqujMQB764jG7upcJDFgDhF1QxyggEZhDeWTUehJPQtfcOhc73eiCL+XyZVbW4UqiWoN976xY8I107VOFI6UCRFp9WLj/WXxTsGVuNCIU9JSbyQbl/tuoQZmDCT0BE4x/tdIZBVk9H2pfwVwTTUr23WAvAFmqqyXAX6P90TtKQMmrhX/hrlUZMLeWV2bAY/HE7/3u78rFMbgGz/3tne8vr3i//2//a/47ve+jx/+8A/hdt/03Eiirp+VQvVq78FSTo6O86R82ltDL2hYX6mcnXEOXliIZV2vh06LdKmHyrm1kBHowihDqXow5bHRuyzEB4vI3prWt9bxu8Imi0ycLADLNZOoBhaxM/SOaT1wQfxQs+PWaG3voRwREMkwYGU1gJ+BducnvJH06CC59DkG/MOL8k+wUNHQ/hox9bxtFRf7CukcmGU54HrvTu6Jid+FhjUaJZKcDKMcPKH27Y77hw+IAL5+eyW3aN+FNE/Nr3kJ773BQHv5kiXzcVxoZ3n/hIItaAhG5caYFLtXZELzFFnbYJ1qtaGMsm+qyqSg0s9JJB7nA+VInEHpKn1uyiQzgK49MYl+Ff+MxG1f77warCLlDjVViUv95vuGnklTMdhC4lnjFNeGaDel/w2tbXBLGE6gcdT9NJr5xRz03eodVHbK5UXrsjyCMudClDm6piqru/JuVJi01sRPwUIpoTuNr09KozF01rIAjuB50uQpBYFX1dDfb3cW5OJjMlWchP6f5+v/VkHym7/5m/j1X/91/PE//se/UZD8+T//53GeJ/74H//j65/90T/6R/FH/sgfwZ/9s38Wv/qrv4o/+2f/LP7Ov/PvxI9+9KP1Z/7En/gT+JN/8k/if/wf/0f8PX/P3/PX/Lzn84nn87n+/y+//BKALvxmDMXyhu12h3cRMo0PP8ZcRKuIwMApu3bO7poX6RBX51UXBsSGFzmvxiZ1aPPLL/a6OtluXPQZkkKhgtlSDoe25qrlO8COYOpzy9ugNx1sgSMCrWaBSZSHkru2bM7rcq2vpm6h2OFcuPGuE7kC73prQDkKrmqeHRJ/liug6+JS5Bzw5AFX35P8k5KN5TKWogxURCndUCV/JZ8nUXwHoHwf1MFnrKIPKhCrm0jxMKq4KPSFunqOQNLpT7H4FPXumubtBskchVCpy5giGVc0QFosl9hMYAQJhgupqvdQc24dGBUcxotLJOd6B5EYcUkaIWRpFYJTpGZckeKt7WiKBHgeTyxDPBSKdamvMkhka+7YnJd3JlVgrV/jxbNUNkkI/O3tDT/94qccAXV+7nx3ePWXG+Y58Ptf/Bif3l7xyz/6w/jOZx91uBcbhYVUbzzMxknIfN82QAVJ8X8SItlpPRLF4ksa49QYoFJDDeGQORXRhNaYu8KgxRT6hoVcVshfZlvcoADQGsvW8xyr4G6943a7kfRbcRI6F8w17sy51pN7X8WHOeDq1GGui12eFGbIbIs/YDLHM8HqtY5aI6EyMMkBEYG+bw1znhgn7et7CtUB1OGqEFkoJeucl5cXnOeBx/MNMbmepxWyxy3TjN4tBtBnLUDOSOZVSGjEcD6fREVcSpM20TeqCAGS/2OS59W6AzaRykQiSZgtHusiQ6JhnlS5dIXzTRGSt32/ztpg+va28bMioALlEgPQuK0csN8rB7vkRIaXj/eVblxW6rXnXGT6XkhLCzY5UhDVOmpC07j/5b1xngidIWxQO5G+MVns6/2OyTBDKlFuQAKvzyfOObA1jW62Hfu2Y+snnseBcw7M+YRr79POYIqAy59XSp9eNhK6KmIEtq3TpTaV5aa7I3Oio2MakfX7bVdxrpBRnU3FQTE1pHPqXjB9H4g56Lacwc9z4Dzf0Pq73J2f8fUHLkj+o//oP8J//9//9/hzf+7P/TX/7nd+53ew7zu+973vfeOf/+hHP8Lv/M7vrD/zvhipf1//7q/39a//6/86/sV/8V/8a/75OAcvUneY7HLZT/NQNjGRTQRKNhEay6hJyHea67p8irBVFtbIVMfKhVmVN6c+NEeKFAxWnZQO99URGBeONz7ynLYIet1p3vWMEyMIn8KAsOrqeHFTATHEZFb41RqVgF1jIwGzi4tQ/9Jb00xRf1TkL7L9CS2kLvWS4AGQWygRCRI5RehNkKcT7+b5OnQLFSoEx3o97xoh2FICDUu0ZGfjq6rnIVAZMlWcQT/L2nVQkjMwOb7QJjMVRr3RH+FCJHiglJ04AOydc88CVQ3sztPE+6mGr+Rr7vAopEWqIT5ImMUqloY6eIdyUJwXeut9XbjuhhETVdSW1Di5mJahXMypbkokSzB0zWZBzFVoXfA7UT+w8G7GIEE44pyEX+egV4UI0VtvaL7hp198gZ/8+CfrMuXnAtVFUuLUf3wDNnc8zxP/6//2v+GX//CPsDXHeT7lhNlQwXFN3VuNRZqk+i8vL0BSFeFoV+GMQiSMl/KUJ8M0okz4pkw/szpFXRLgAU3nX77dqSgGQ6W1JtIhhcJB18qZOJMEydpnBbdjFnIDeBq6ddy8vBY0es1Ek3kgi3n+7eVt1OjWOefEpnFqDf3XWNRtFbrgv8ExTny43XE8n8vdtzrV7pTe0V8FPP1aQxgvw3MObPvO8ZdI16ZnCxX87o7WGeBopoyTjCt/S48hYuKc57owxzjJQzGmd6/CNWVh7x23+51FZZ3M5li5PRGYJ3A+Of4e54letgNCrQNAjkCkIUs+KhRqHTuuTJ7i+C2+juzL2wa4ZNnJ5GjMBLIvxGMqUm8VMVbclqaR2cDicbCLAurZuZN/o6p+WTMYYM7vNWcpPhNzBHpznEYOU9s7ngf5d56J+77j888+wvdEdwCDJPVzHFSsGRGWvVMCj4QaKLoTG2Q/YORqWXAvmwreXGcxzxVXJhHvQCCDTTUl/Nwz3U1u0yoaz4GnjBLLNqLL8dl6cY2Ikh7j/wHZ71/8i38R/9Q/9U/hz/yZP4P7/f4H+av/X339c//cP4c/9af+1Pr/v/zyS/zKr/yKsjIm0FihHePEPHMdEDkG6nRbkl7woE+IiT2mIKdrLBF54srRqIsMmlMmkFOZHzptdDmZLsWy0CVLnzLaIlnVxVYIAAouNEPrG0KLPsmeAD1JLulpzWN1AgrtufwiYipkTD61ZZRWFztdbJ2jnawNmgvqz9QhtzWaIelrESOX1XKuoqZ0+AYVHl5VM+CtY9tvsJthHgfmcVICGUH2txvOkWs8VJ81YeqMNaM+h5o2FmFU8FTKcR2wRXTk02hODoEJviJXoozcqD7IlJlShg7CtmDdy3oZS1N/QbeFQoylNMoo2Dix1YU5J1UOWydyICg40xYSRuIxvU3q85v3VYDVWqnnO85an1WEKFsn361VI4LgMtwr63yuHdpkf/3lJ9xfbuje8Hh74q/85Pfx9vbgAdTKIOyyfF/KCZ7S8LbBPdHahud8xV/67d/B5o4PHz/iu9/9wM9VRWQViAacceL5+qQHRCEIWQjSXM/dDIhZHKOmjp/FWuqwMzd4OsY4tcjbKtCLf5MwRjuoymBHeynUKuwR+hwolCWhCIgqxuQXAwOCF02MAK0n1CnbtQ5To5d8dzmRK0LUx4zrwuGYCJy6UDyB3rkeatzbOyX6rTMhfGYAQfJsN45BVxOQLFa33pGReHt9w9x3FkzBwui+d7TeOQ5I8q3YcCgpWahDNSlTY4uA3omavdu2kTweA3mwQnD3xRc5U3b02w1xDry9fnpHtOY+HDMBBDkHNbrzxMutYb/tGDnwjAffuxBjlgxc6I46R0UEdgPE6Umh3BX5gAhQP8HvgBILaFpY7soNWA7GeS0oGbJBpogsdtwTLnPBMcoaIYXyqKnI90TscsLBIhJ7a9j2jajcOXHMga9eX7Hfd5nfsbFd6LlI0KkBFQvzKzNpnQducDTUqDGNnBFA/kwpbWPqzJ5cr5yYGvlhYASFKRcuGjDNkDE5WrfrTBhRSFKs5rSax5/n6w9UkPz5P//n8Xu/93v4e//ev3f9szkn/qv/6r/Cv/1v/9v4z/6z/wzHceCLL774Bkryu7/7u/ilX/olAMAv/dIv4b/77/67b3zfUuHUn/mrv2632193BjVm4oyEg+TFcwxESWNMduDQhVQPZV3K1VHluwUp3sGQ5bTZepBNIXUohCOx7J45esFaZCRZlSGNXzbERgw1I1Y7XvUAwAsEbdPmMjn5iZdR311S3QsNeG8/zu87E9xRupjMTRyDqwKmSoBkl8qZoe05xz5b6+xylgssYAh0dQhhU5cWLwcXIrNv+yKYjXnAm+MmY65HBt7GyQO6EWXJNaKCuohLAmn1UI1FXgh6ipobiDnO+SafZ+jCal6+KFNcD3YOdDBsChcseZ80/kK+zIDWjFCmXEFLQRU60Cl5TaAUQAkEVDwaq1sy1YOmVnLLHXMuEzxHmVB90zX0fZdmKEtmKaaMKAtVVu94DnWxFxF7hcpJAm+FBBoSlIQ+HgfatiNi4Ld/53fxeDxh3snDSvosLPIdJHPMQg6g78nPevt4BwL46qdf4n/+X/4/+OVf/mX86Bd/kYZzWnRFWhWkdF2eRTKv3z7fFaZBfpPLyJC0C/mQ1DpJANYwA2j9eiZQAVeOxtXtj0ltlJmho9QoQIIOws6gYe6bwWwZPu+LlL0pUJF+PxNeYGQCblwXTR30KUWKmyGdRZmn4Tio9iJvjmt6jIEmPwwW1I7UTH/EJLIEWf7rfXDpkOxahX2pFg3sUEdM3Hcqx47jQCaJvGaG53ksQnVvtEhPufrGWp+UBzenlfs4T/SeGtECmTSjq87NxOkpZChm4Pn6hufzQPkKbduOfb/J3IuS1kiNjwHYNFr0N0ezhrSpdSPkGkl0yIiIo8tAL3XhZ5HC8xtE/9Y1ktD6NqjRUuPa2hVu6rWUgAsxDKI55hyBbA60jVEI3ieezycOZShBeyRCZpRGPpYZmDauJc+xvzgyjev+OAeOd0oj+vWINlDJ28w1xnI4XnsLtfAlLWYzFhkwWdOr6hDhVblrdZ7MGmdJyQgWJ3MCfW/YusNsg9uUj1I10td9xilF/f/vHuTf5OsPVJD8/X//34//4X/4H77xz/6xf+wfwx/9o38Uf/pP/2n8yq/8CrZtw3/5X/6X+I3f+A0AwF/4C38Bv/Vbv4Vf+7VfAwD82q/9Gv7Vf/Vfxe/93u/hF3/xFwEAf+bP/Bl8/vnn+GN/7I/9QT4O5Z0iE03ZlK8mWwhGFR88pIRS5NUl1z/jweOUI0IXcRJqq+Ji2ZpbKS0A4Oq0+L15yEYo0CvYnRaCUZd1CpGhpwjnlSUh5Ivl36gZJ2T0Rc7M9TnYTQv6N6xDd8YJcii6YuGnSKMsZlKdTEVFL/t28EBYjrXVITSiMVCnyvAsh8mAiR+cfBtvjt4Bnym04cQ4rplt4EJ23OU/4Bx4smMsAIiXxaGO1YWCmJNQRohS3gdoCDM9a9Mhzmc+FRlfiFrOwP3lzvm/JOKZNNhz20QCTLlJEg05RXSDutXQRWYq8ByE8HurSjAR6XAPJWpCMGtgnEOjiUTrl2ts2aoXBwAA5ZZ7UxaHifmu+f0YeD7ZhbneYXkW2Lt1y6/L4pwBdDvaDPzWb/0lfP3pK5g7Pn78oCJEHKWKprdcheeC+tenfMe78sTH73xEnIH/8//8S3h7/YQ//Lf9bbjd9qUSuQjeuS6rbRPpbsF8q/xG7wpXNJI9EYBtDS6PlNbZoc/z1N+JVVSjFD2EB+EGsMHlmWEolEWjqBCiokuBz5+XRXkyQI1A7fUZgbfziY6Ur4pQVVDu7xgw0PArBosD12cJSzyfj6XkIZon3tQMjb0cHixcj2MggyaDNWYgAZFjSPeGfW8svHHinFfE/YzAcxy4bTt6BOY58bRD/KDiQXHp8vKHCOEqQnVuuBmsd4TF6n7HGCslugic65wE8Pb2hq+//ITz+WD+jisu47bB984ixzriCcSYFCnMAECBQjOSoAsRNQO8F0/sQgabXRbtABDKJPJ0IVj8fIaG3m+gKivUKEIEKaHYajC8X6TXWrulNsl6542S123f8fHDCz5+/Igvfvr7TD73DXVQ1Li27iMPEnAzgVDYqylgMwKLRD/mgdYabrfbCsFjT6SYkSkUJoDedza0JYJArSlaFAB0Uwac3itOsn7YpIGaczQUEavYIy2C6/8cA+eTpHCDeGgjAHFa+C64Pwppvu6wn/31BypIvvOd7+Dv+Dv+jm/8s48fP+KHP/zh+uf/+D/+j+NP/ak/hR/84Af4/PPP8U/+k/8kfu3Xfg2/+qu/CgD4B/6BfwB/7I/9MfzD//A/jH/z3/w38Tu/8zv45//5fx6/+Zu/+XMzceurOiHGxpePxbWxLtioo8YcNXooy25kzZ+n3EuJUqTMZ2xdEoSf3Tk2oDQz1sUJ4FoowDcOLfed3x9QlVpdIfhBjZyAiImGjkQQpXjX7U3ZAnv6CnYtlMXNsSVTKKmCufgbqZ/qreHe20KNalbPi8SukQxAMm1efA8zwqKqv1YxY4JhSBzkQXCME89j4sOHF7S24/l4rI6sFqbYK8tm3cGLbyLWgWLq+JHA3jdeKwV5xkT4NU5JOELpn942HiAAIimHdDj6tqN1wZQu/5RMxBhcd7UTjKqnWd4oSCSZgEBSIjg8Yd5kb++LpNu3DU0yN5jBM3HmifM8iIQEiweqH4C/9L//H3Te7B0vH+/47vc+x+12kxTYYU3yGgDbvpHPAyi/opQVkpqzUkDbKuqclVKNHiMTYVIKwfDll1/jL/0f/wfGHGg3ShXDKriNBUmo4A+7Lpv3XWXB7kSNwJ/fqWDa0fHVpy/x5f/8JX70Sz/Cxw+foe79rbObfOQDpSgrUmeImV9SWD5/FfpzovmGDx8+4O3xhnme+O73PqAZie/ncSCSfx9pdNR8hxSnLpju2ztYm3wlS+6DABYCyYK5yNW+zPAS1cYAfWvYcqdEV4qCTBIJmxP5Iv/iWtuV8No6xwifPn2N+/1FvARbirB5JtAFGMlJFnIPNtRZd6nySIjl2NEG30slzhbawbOSyPZ8Bm52EwgpTofXODUFdlyjoIgJE2EyPDhCAbC3nT5MKlC8FUmX2Uivr/QnSlD18537Hdv9BleQpTkD7GocU+TiUtwVRyOFAI0I2DnlCVQ1bIhoa0IHa/2WLDcXAioqPW77jnG8GxHqtGx28bGuywaL9xSycSikt/dtNQStN+z7hr79Iv7KX/59opsq7DJJkO6tYevbQvrGGHjO2lMqiHWBz6GiegLjfMPLy51hsEEjQ44AicTGnDjPucJXD5m09a0pIJD3nSeWpLciOCISR5x6pnyoxZkzNa2RSRfvmTgrkkNFeqYt0cIq8Aq9zmu//Kyv/587tf5b/9a/BXfHb/zGb+D5fOJP/Ik/gX/n3/l31r9vreE/+U/+E/zJP/kn8Wu/9mv4+PEj/tF/9B/Fv/Qv/Ut/4J91nOcihlYngNr0KKQ4kXkCeUWZ84sXzCWJNXZm4iiEFXE19b0NbeuSjMnETYdd6Ka+ip33ne4FdfO/HWVAUIcwu1nArLN4EgHp+ko4eNAGoG4h36EG9X3EYm9OLbpJ0eFdJMAg+ZOVlvw6WCQVYA6Al2QC5QRaKcKRAOZ7w+1YRQxKfSCi2etxwiLwfDCrhDxLvSddcBFNJknKXnFeCoXWmEYt5K6U/wPk9VLkVF/FH7+vTnBTpxNEK85BS3aOEAxYjPxTQXG8pPgrkrjcd/rNxJwcnz1OogV5qaZIRCVUOVNeHwnNaXXAmnxMkrk0X335CZ+++oQvfvzjpRSxLww//vGP8fGzz/Dhw2d4efmIj5+9YL/T4rxGH966rJ25yxMdY7CznJnATIRTcluXaiFicwTGOfGX//Lv48c//jHcgZeXOyH2d4dQLVUYuQDFZUF1v36tOZpNxaW+MpOU1HFrN0Qmfv8nP8ZPfvoFfukHv4DPPn4svRDu+wsP6bzGn5OyAZh38pziIlu7AdvmdC+eDOW7bXdknni53+AOHMexOvMFE+t9uZGzMfLEOYauHzq8uqsZAXlYFy+IayFD6bJeDQLfPwusJp6JyIaR63JIpewW0sD/SrmvpuB7wxgH1REOcUlYCMYQyd7IlZlSPLiDF91CZK93QFl4BYOqkKmCBBVvYPJK+b/I+7NtWZIjSxDboqpm7n6mO8Q8AMjKRFayiovkD/KNfGj+ILuzqjMBJKaY7nBmNzNVFT7sLWonejULeI1VvlYmgIh7z3E310Fkyx6a1D5R8HPP0PPk54R/jhkxxmBURtG4LgjDrYvXo7GIueN0ccRB/IicE/JEdVDvYOOXOOqcZzqE0uOkoXvDttGWPGlUlbRHvTfUrf/sAh0H8s8KMH7eCt499JvBuEyniUUOm5iIA5FcWycda1Wi2LXXUVgmBU2iV3q9dBup8euyYJ4npms3g3sFQNsIJBb/5o7D4cDU8OeFI6tG5CXOuoi3CCRoOZ9RW4RaJngix6wYYBFuZ0Yvk5JpFBkGaTnxzwldNgHbkRLtThl8yRnuHFemRASpvWiiU4poSkerlDUjZ6TsalulnBP69PeiI/q8L3uIX8br7u4Or169wv/7//X/xOl0wUNXCykwgbB1DtiCfIuEINyw+/bx731E8/6fP7xc6HESioxYMCx89k4lwpaKkJSA+cJauo+/F8ULdvRGnT2QkNI0Zu7mTJfMJe82DGGRLEiGExN+XhdhqbcOD2WG44WLZZfzn40O+mebwChdHuvIXwwRdlXxKMAAIBnh5RocELAuaGLOj0vNBLXqUDALNncSmZZBUjFzL2LMB+eFvJrgR5DAGHkzyV6M6EBDqufzeYwIAPJ0pokhVVD311vFfJgRJLgyeEK0ryb06FieZAaVDNvLmXRW1oYDSDL5UocZJLi6UUL6048/4fl8jm9ZHaC4DVvDeVlxPi8oKeNwmHB9fYMvvvgcx4tLyj9LQe8V8+GA42GGpYS72zus66pn3wEj2dJ7xzQHZAzU6kB3/O73v8eP3/2Ai6sLfP7F50DJnP8bduvtVBBIy1CoOZE2FhExG/VhocEZu0YaLqQwUzJ/Pp+RuuObr7/Cq6sbpJJHimtcesPJ12wPRYRhq6vSrmWf7sDz04ptq/j0009xOPBiWJYzzsuKmI2H+bOZjWTr43HG2jYsy6JSLYvPRC8OS7aH/Tn3wsu9Epd+jABptmaY5wPMInAtxmmL+D91nDfBe0GcAkInu/hfRRk7RAmKVjIbjbYxwK7kgpDx+Yv9PpV5jH9ixPgSJdkbFxvImoEFTyQV06HWsG1tR5a5rDGVou7bdXnu698dQKeyKNKG3Rl0N4zRtOdrjCeEsBVJ2M2JoJyXBVttA3HhXpgxz/OwKqi14unpiSnPieMHfjcQOs6GbVk2RJhpzpkEW9OEWLy0McrVsyllGg3h+E+TKVpk9uhMrXXbx3pKv+ZZ5BqzbTLQfDHKFyKETjRjLhM2rZdlXUYezFAdxh1lNlC+WEM5iywuL6vWfJzp9gKBifPPJJaoW6PySGsCKWFVbAWgANeB6olEGxxDnXfx3MIHrEwMhvXe5VLOPV1yxvq84P/zv/wvuL29xc3NDf7/vX7RWTbuuvicEiQWh+xsovvnF8k/23qE6xEuzQEFO7velJMcVF18Dh+XX+0VuckTIxWNOdIu+8TLUQYAyPIde9XocTMYFTXccF1SNhKOCCMbLO2wYEGCT4UdF6IIcJp2IeBGoHde5GETDWcKZyS/1th0+huDC+B7OjGVPeH3oI2Y9i47D4lqMNhlTW0ca0Qn7fq8JHSHORafV210YAwczxJtxbsBfdvk9cHiphmfaVMYYnTzNKty6eIbqnwLaKLAw6cGZyHZUEB57/TliPC3VuFNl4s09s9tgYGW7OYdqJRTuoisCab5qhAIo9R63MxG87HeXaMuQwXw47t3eHp6wuF4UBGqIla+JwlA9gnXBzrH3t19xJ+/+wu+/+EHHA4nvHr9Cp98+gkAdpdTngCj9N1zUUaJujFxaJ6fn8E8I6FNKeE3/+k3ePPmNf71v/83/PDuJ7x6/VqHKB9fby+KU5CnAH0e6OISZUAGVLqwVYSNMDA40Qk45uMJ67rgD3/9Dp9/UvH5p59gLhnNK8LzIsFRK9caZb5A9TpybGbLgGbrTX/u44cPePXqUkRF/j64EeksHI8VNRKtbfDaeKHPNOIDoIBJjroITVdEonKcJxZ8o5/tde63dduQpwmXxxMcdGhlNZMAU0ZQoLbAXoR2Ni25FGDbyBMydeCwMba0BKCFgqTAFKkQIYdRSK91ocIvhcmbAchUOg3jNb7mkuBJxH/bydO1VszzASn5ICpG2neH0dVTF3xKVIp5c/StYn16wu3tRxzmA/JEFU+a6ekSZ06ST09rmz6no5nBuvKInIRhx148dTjWdVNyOfdZOUxYzvrsnXyXZPEdkU9XLCGlA5VjZN6iVY4353liwdfpSxXr2eC0ay8yuwuVVC5IE5sTiGQedv+1VzWIFW2jy3aoIiOlmiRcNkGRNJ81IlxaRS4JR8zo64atSwospWI2If1CoWSzMqTGW29Ap317lLrNgV7JOyPXJu6yzL87Z9TaR0OO1lHyrGJzewE2aY11AGgkvJsD3pHQ2SSUGVuvQo+k7owpgUcK998XDfOLLkgAHX7pBYMxFpa9gP4zL7/WOmiQpT+aXF2qjQefkNHESg6iaPzM1iOtt8K7gRYouxySXQ4PL4/bNtHTotWNF5dc7xxQkFrXn6QZTzIWJAOFiTmpoNcc3RT/CkwkWUBMbhVBw+AHNv5u0pgogwdhmHS5oF/aa5uQpKwLF+C65QURduQGwbZ6Rk02z925BeLAdPBAzXrO3fjcI4odKi4Q2Q7i8rjkd8kwOrFpOjDQq9OZdAyORmqnAYosX2tFbZQjtq3jOJMIeF4W+MxDrEq54gCwYNgk161j2xYcj0fkfBySwVwmfv5OD4GwzXc4mvOiC/v4jN18aF03fP/dD/jhxx9xc3NFWNfS6HJ5gRJpKFOBJRp8HS8vUKYJD7d3eHi6x3ycMM9fIFmhImnjzHcuE0pOyOINbNWRu6EZYEb4NTpLM/IevvrmS7x6+wp/+uOfsDw+4vLiElmXV0YSWtf35xsjHY3DonCNasVV/PMVUmEWpjklwIF5mlCt4f3tR9w/PeI3v/41Tsfjvr+0h713HGYSGmsVAke5GN9P68iFvI6pZNS6ChanBDJOwkDLUjKcjjMeH9bR3Z4OB3hjrENvTeRifbeWhnEYP47GMSJeM6p9R+JyzliWFcfjBa6urvD48IClL0hZYwkYiNVzP9AOAMgqtkthdx+5TsmMnh5w8ZNYFCb59xgSTa6wd/VJRVzrG3puo7noWp/sntto1LqxCfEwvwIAY2wAnGhlb6vOO0d2KIRRMlOhZmgdz89nPD/e4+nxEb02bOsKywmnixMOdoIrCTaUTcfjjHUlF2NHP7s6dgApYx6xHUKRQBLwpmdvAA6Hk/hpHeZEkJJRYReGdDkVnI7HkbnlMYOBCSCn3fs8TUIHde63kPNzzJ2yw73tSrwtEIoyLN1jxFiro2scRyltEx2Arsyo5IY1WRfQHZZuw4fLE2zh+CaSslioqsERGrSPqciVczi8dRLrg0PSFhacKbyYfHxuIND8tCsJk8mUz4kAE76Pvp52GS9G59koajA4imz9a9ttyh08u0OC/Pe8ftEFyTRNyBM73VSKpHesXMPQC9rEzR1J0c5Q5dudDzUkqLXuNs3R/cNCvdBjPhOIMLo3OtyFKsDYMTRJx7iRNFIxA7qjesNIrOxUcfDAIA/BUlHRQcMsAPtIxtKAkfcS1hRl30dRFgdpUtZ1MgzuidmLzkvmOkQwyFMYc/Qeh52qHnDu3UVy5b/js2DzoWIGGF2QJSdlBkWjJR4ErW06CDWrFzrDrmgnk0UB5Z1Wy6b/20ci0iJp9AVB3TFTtygmzbBs+p2toxQiMeG82nvHsjWknpH77vTYG0mvZZoFQ/JAL6XAs8kQT4em0B/4C0MlJJyXDT/++AHL1vH6zSegW1lwe/g5a2+svLJxVMa3jG3reP/+HaZS8M2vf4VP3n5Cr5ruIgl2zsT1zA/TDJgjVx4ytVbk2rDW/RApJQ/p5uXFCZ988hY//OU7ePgr2G4qFsWWpX3UGN9LIGQeuJ/ZMBILTg8XUmOuUSBsQr9aa/iPP/4RVxfXCuK8RO8r95vCxgLFewkbs9NjQjAg3wWEyyYLOw0zEPlNtQGH6YBSJv6dZCMjqtbK4quxm3RgKOYgpNUSaLnYA5Fl/k1OCWi8WLbW8PHjLT55fYOTgty8b2ipSYfPZ1TyhFJ4wiREAAV9KI7HIx6fn7FuG4mEaqpNMlCivWkvhVKGI/JrMsnorQHKX6Is20AyNqXnnkzhcTQEy3nCti38fhO/27VuzGGSASEN4+j3FOqwWit6dTw9PuD+7g5eFz711FAOM06Xl7i+uUaZJ4yRNNTUGa0cFqzYzqvOy4LmdRCHdey9GFdIkquCit9LGqm+HMM7ttXhRSM3ngi8jGWyWIPrIoUKCwGRPoveXwskVZLYEuR9R5L5oesIjmaxWx9cDMtUo/RNPjMpyxslrhCGuSJHSCD3Wjd62mDOSMpedLChdjBeh0pPHwhMSoYqXl/KE0qeJEjoe2Po2z7e9nD4TiRIqyHsL4psckiIDvdO75LmzO8iP5v3nWV5wIBoTbGCbJXourFhY6p7Uzjk3379oguSi8srzEd2vkkFgBswz1TrtFp5iLhjbQ3wjTBld41FZNanEsRyYWeuB57BUYOuCF4kHsxmdepDMxJwsevfkVENkw16fN2+H+4WMmSxsIfyxgLy4gWX1GGq6gEgT43oQjs3RVzK7oxeZ2ZB4U/vhD4j2IkpjLw8giFvqnzYWZiQGtdlLOOhaUeFAgocxRI0y4yYbYiZDse6bDJ9g5AgwHMangPkD4hYO9CpxHyHkscst1fpPFSkpZQwlQNLSB02AMmNtQMpdSzromKT7qX96Qmn0wnlUMSxyeiduSpr3UTgMppeoWPKRRhoB0pRWFzoTWR01+kYDHD++vR0xuPDGdvW0TowFxYL3SvVOVNBcDFIRiU3gPBuRbaMj+9/gveG3/72X3D9+s3eySaDeRJ6Rei7NaBrzDT4H93g2ZAdQ75OL4kE9IZsjq++/AwXhxl//uOfsCwV83wayh7+KilPgtcTLHrsJOhARABKioML3jvDEQfxyfRndSltdcX7D+9w/3CHX337a1xdnJBLxjTJoAlCN7V2rRjqxu6yS5Fh7khNRRNYSA9kVITybdtQa4cnFteemNCNUHlpTBPGiGYch2WNPrgku0ZL/Pwci+YB4XtveN5W3N45TocjplJQt4qpsMANQ6tkhkOeyCsxSiunlLANLkPXGGhlmqqQmd7rKBTNJGu2zERV0IF1miLWIQpzjX/NwbRVEtNpm0h0OOWCbatIptHjbNhqdPu0OO/yG2q1Ik0TEgx13fDx3Qfc3X5ASkZCas5AN7z99HNcXF6KQB88La713sQNKxNsmoGN7y0CMatGti24E6xiBvm19vj78kUpReGJfMYQkX0qeRQe5kJuc0Fyw1a3sR9q3bBuG2prmGeGa05mWDeeV603mGTVzgNH+yKO+w70BHMbgas5ZaQ5YV0oKy6lwDLk+8QRIMyxriQyYwOQfKiGYrzi8hVJuQjZAcqEwZfTwkSyCUBnNMO2gjdaqK+I6vVW9Rl2c8cYt+dMflbvDbT3p9w+6S6CJSx1P+e9K2oCNN8LWbFBOVVNDbDu5ab4i7/n9YsuSC4vTzicDgOeNQO62Qjcs9qHLwVaR3b6jBjYxUZ3t8uXsAeOOdNDACIObi5HWB/dvGWqP0bHYgCQfqYMCIvhlCN0LhQL5Kk0g+SNrFApb9QMr0saCxqVkajKSjPIbCbuC18OszwOvrDQHgVWCntyeYqolxxTKe8yrIwsDhUooXIIJGMgED7UCF0QvnUpYsChVSpFHh0J7QX5dKg0PEy/tNGc6MecikyaEoCuDjFJ704Ylfk2mrV6F7SdtMkKC87WABMyFRB54tiolIJUKNNtPfwfHKuqedPFs6wLppTRHdgWhnI1iywix7asOG8V5+dnbLWN91A3Jt9amQW5dqQeiIq+MpP1dxf8a/SbePfhJ7g7/um3/4Sb1694oQllmGRiN6SyvitUWt8G4c7MYAquMxjmA9OSEwzoVV9vx+vXNwC+we///fd4frzF9fWN9kHfs2N6SNyzisG+fwY3cm3ULToU/Id4Hxj7KGzKg4ORJl4K//vv/huuL27w+aef4OsvvkC3jRbxyXA4TNg2pVsbYWya0gGN2bF8fuEVog6RUQnhsRH5Jo7eC6z5KDA8Sc4s9DFrzs8DmkUDUaWGbFkwPLBVoj+tqUB1x+PzM57Pz7g4nl4QrHWbcIsKmUjYNnE7nD4167ph2zbkLBTAOepMgKLnXpDFo6nJCdlJDt7NvxLM2vjNNpqdNoifJpTIjMha02eNOzcCOiWgh6Pj+XzGeTH0reP89Iynx3vA6dY531zi4uqSzsyHSQZciRwhwSPmCfAmCbzQp8KCLPbbtm3YateejMBT/ojEr4uuw7WJRKnPC7m3Ot/7BkfJ814M64xLBrqNdo3OCkdlrTe0pWFqhZes8lwcBe6JkmR0jXnEOXyBOA8nVsl8U2GgXBCzu+3k5fDjcWfeS62NTbSzoAc0evcuKXT499A924QiorvIvxkFGdViJBXrhae7WYKVBK/0YPK4p0D13xzjSI1lLBE99Loi0synRH+S2rfo4tF7x7ZV5g95NB/A8XgUMburEWwDSflbr190QdIabXcZt7wzgp/Py2BD99bgLUYPqj6dkFcFXniIyMnVJWvSZRz/LmVdpmmvjLt3uJQLXTBVEsGRBYCpSt/Jt/BQm2CgHq6QrYiBb40Lcf8SDatv+8hIxMKIInf4yOb5+cuHTDGeRUD33GzOuPmQPiP4Jq5ob6E6lkZ3PdQvpVCyKG5ObRXPzys3zTRjW1dMORNVgJCM4M/o4gewezu4+DxJhaKLhaOLxGNUpu6CluMA0MUFATtVSfjCMA2tw1qna6YQp611XJxOyInoUTeHFXZ+uTh6FaDeHcuyYt2eKC7S4VbmCfN85OGeDVM6IF0YEm6x1hU5Jzw+PcGsYVmfYbZxhJj45y+PF0gJ7Nxl+hZOmcuy4vnpCcvTgt/+9h/x6Sefwrrz0NZ6KTlY7/rGG59fkHK5TPiNzvJ6GOMkjQs7iNR1Z9z56eIC//BP/4i//PUvWOuCw3zUYUvEK4EZMizeE6yzIN9lwipMBadD66ijj3VsQnayRg1MSW7Ihfvq4fEWD/e3MAC//vVXmPqETejWyIyqSiRuHWnKY6+2ykyiXChNZnedVezqaDZwzNiUBWQMxiMK6CN2YSoTuUR9fWECyMO9tj5m54FoVKEJ3DPiSj0/yZ8ioQ/HN4zZfzjQugccznHpYZqx1U3puzESIOLZKrvQ7nvODYxk05fKHX7XcnntjZ8VzBmJZqWDPAEae0XhyHVSElU3TbA/JANezgvWZcH69IxtW4HeMB8yTqdLXF9fYb44oXaNj8Oo8mfkgThQkxBrOmB37F4pFgWHBcxmGh1Bo9sC1+XYVh9nC8CxjNdK0qeKUNY6pkwjyPXVdeZy39dWOWpvXB9bk9qER40mYCYScR9IR8psgLK4Z911qfdO4z6pCSFUvZszzNF5d3mn9NzgWNcFxQsOaUZUVt73EReN+Yiebk1S6ZyQOgsTKjuTGh8eFGHmFihgmQ3VqPha60rPJhWyvfJOaHAatomQz/fRRzaarSy+SxYpGh0MZieCnMxgnnGaWeRW27D6hiUt+Htev+iC5OnheRwkrg5nRFB7G4dkKDJia0QmAB3mw66ZlzucBJ0YCySLbjQhzG8os+vDpjlnXgTdaLEMM7qpik2dTLM4zaEBjIo05zzKDhYC1HHEJg15YfLwf4jJzX7IxwWRBgLDhZxLYV+lqhwQNyBm5B62wfuB6bYHQXW9z1R2XgOzD2g7fZizoPeNbOv5gOPpcng+5GSElFsbjqZ8rkQWWNlTQTOqfkAIiOa4AV+C35Xbjug0sdED5rRMoiN/lx7UBEWU0z9m2yoSEh4eH7E1RznOKPOMDhUF7thqxbqsWJaNyc214lAyyjzzu1NaZsli3Sf+/svrG6TnZ3z8+BEQHN5b46VQHR2rupCGeZ4wHWbM6Yi6Nfzl3Z9x9/EjlsdnvHp1g7dvXuPy4gJ1XaUeiLBEdoBFBcpLS+zBV+oB18r1Vodra21A34wSbxoP8ple31zjn6/+GR/ef8CHdx9RvaKUGZYyNpGIkzhYOUcCNnbfD3VNDVKRiMOEgM717ADNsvWvmVDdkeVI+7vf/R5bXfGrb79BJJICzDZqNXgGHeiGMuky7ZJWe4JbJVqGmJFDhm/OEURvQ8LIXCvf78ouUmRngdN7h5WC1nYb/q5iyLSHgpxs+vsOYNMIaJpmzupFSOT9TklvF4rRnJ376XiALVTGwV1FrFRjKcNKkpIIA6klkgEAkX3l8g9y/bMEnWaSbO8FQoyUu+/PITxGimzKW6W0c1tWtK1iW86odUEpCRcX17i5uR6Baq7U5QhVbMFr0xrsaqJ6MnEc8DO0lAIFkoQRF7HWlqsDb+JbpVLIwwC5fDlB70ONHyA0mcTSaKR4hnIU31tjweMgX6y7TMlE5NaZ0K0j993riEeSzove4cnI+4uzOiXUJp6TmiNFgCFZQkkFXmKfEr1Y1pXurzlzRG1M5h6Nduxx49hl3RYc8oHJx3rv00zXYvpP0XuFHCkAlmlamIF1rYAnNAcsZdQGDII0wnCxc/TrwAjudFCuLMSLd66KHksaDwFr5Vh6KhPMC5IB83yBv+f1iy5I1rrCFmAcBs5NBw8Eg0FRpZR9LKCxCy8/VuTzJK+GzjmxZ/l4gDDd0F2LCEVfA2YWtF5R5gOTMvvOBXFTlSlkmNd4gmV1ZrZ7D8SlwiMExGp1n1IsMxgovJiV4pty0jATHB2EeZNpEalbqbWSvS+eyHDetEBVokjaCYRuprEWZWcjHl3dXesNj8+EY7skszDD/e0t3B2n0wVW12jCAvTlDZQTg+Yo6QOTIdOLcDBA6oIgF2t2rg6Fny8PU7wx9jGNfVIa0K0lw3W+Rr9rWJcFUy4Kq3OSDpeG7fyETf6N3mkh32pFXVdslbwbtKbuz3HeViRjgcBZu8vzwfHweCayZPx5dA3tqL1RCmyU1W1PK2hhXZAt4fnhEXe3d/jV11/hH//pH8U7YoR97YBtVCJMEyHkWqvms21cROO703jrZTZFymkgBgaOhxp4oWWRA92B3le8efMGZZrxv/1v/4rD4YCr6xu0LUhpHd6NPA7XBa+Dluv1RQhfsKkTTb3iFUik6RCvWxQ7QDnMcO/4/vufcHd7j6+/+gqvby6B5jgv5/Fz83DH1PefO6zTCAtCjxxOlDLbCzt48hAmYBz0AICSkBqVEdUp3xzSTjjatmqd0ryL3T33UskFXSFjHV37NVQ/9IrwxIM8Wcf5+Zlkaod+fkZzWsIfoBFvSShZI0kjomTZSdoNZ2qde0UjpCIeTdOlCduN7MIfaF1X7o8CTJP2e8aQvvP4oVOu6WeczwvW5RnhyPvq1Stc31xxbVs0YCTzp04L9wie8yBsm8HQFTjHNPI4s03HmEmyvXmnI7XW5Ta4FyyqMzLjHSY2k2zSmP6bygRoxCGBusqyNBoZBPpiBqCPixSQI7P+vHNDyEFaqriuvSTVIRzoG5s3mqDxcu4p0SxMa6XrzDRwbU6l0BRR58ZhmlDbxpiLRD+TNLNYqNumMavymADU1nF+OuPieEkSqvWBRtPp2DElgxlRReuGXoHjxUzlX23wunPgcqENfPIEb1I+KVyTzXgkWaehmoubd4yNdQ6g9z2pvDtyLizM/47XL7og2fqG0pXFok0YFWp3AIlk1RbzSqPihi5yVexpDGWGqShxKUy6DvmHkF1hNzWKscZUZjRX+J2FodP/wbJaVW4AJGYSVLrQAHSqR0aAmwoE/f2oQGPUY3DJ/zCyRRwOFM4FCbNz/NEbteNzOJE600EhmNfckC08DoAg1rqKhVr7KFQg2B8aq/TxnHgQhSupIeH5+Zmfx6LDE2/A9sThmGOSnNjRlO4bxQgvWKp54JIEv+CewEJ1QQY5R1iz0o7p5IvU8Lws6A4c5sOLap7M+a6MnypicCAHdeWcujce+uczVQSH4xEzTqh1w3J+hpvDu+Hp6Rl3Dw8vRhfsNkzFr0luHVOnps5pW1dauteGT968xX/5r/8Fl1eX/BkNQgBdPgBcF1HQojd4q/pZGksKqmWB1/TsGQ7XGhG4jARf1/1CdkdTwcOwuI6Ly0t8+tmnuL+/x3J+Qt0a1mXD4XhAmWckDy8e03cTkLuKTAdSmDuoAIGQLH0I7rumNW2ShPMKh6WEp+cz/u3f/h2//tW3uL66YnhcY8c3iRhdQElzJLlq4xMhmmIcGJEBOy+qtoZshYTH3sQb4Zqoa+UoSYZTXWu+CXVwd5gurpJ40fWc9+/IOZufhGolqBvH2PT0WxFp1rXvWuOaZsJrlgljdKyy+0ZIeKvGxM59q/ehH8YzTNOqqEtbayMGftL3UBJThA9lxmb0fIkxknXH48MD0ZG+4nA84PLqhKurK5Q8obauDDF+FpMFuSf+YvZN5OR17+Tk6eeycEtj1Dg8X1TUREHVnN4ru+9RqF14OUcgoWvtUYZNeXn1jfuzbQwL7VIyGsbvs6ImTciQ9125F0XNVkmYnecRxbgrvhzwysYvSNY6XQVEizsignFw/4jWZJSJTQ2aY1Kjtq0rWkqY5hlzScig4yvRsfA2ognaeVlwmKYxjnONSy2HFUJBzePkgDkl5QbD5uSvmO4Uax79AzOkWkMotLok0d2SCP34mYWFg2Z8pRRYoPGrwlydY82/5/WLLkhCkuqdAWyR6hqyzZKywuZ0qfoeWOTu9M9R9w+AXaDgteEaOTAEHwVJEF/dDFujigJG6K91zdmT0YcAjggd8ubjQN7jyNVhcReAS6Pviz0q1KzZuIhCtLFm3kUfJ4/ItgHfVwBIjMrOXGAJMVsOi2IAsUGMlyQvekPtjgad8WLKB4THW4dk0lwYCJUGXMpum0oAbu7oUKBPCONFYiPYi1K4eD4mpINXOG+z3uNg7SpCs8YU3Cxojpo2dlqI3BX+ncPhQJj8BZLQmL6F5/UMuKOUiUQ4AGvr2JaKWjdsZmht5eXUOuhKG2MnSnuXZR1oxPiM+r9INxVteRDFtBDxcH8PbxW//ed/weXliaiF/ADcdkK1SZbpgv3Jf9nVWcF7igOVkDMlpU0E1a1WbHV3eAwI2kWarV19d+/46uuv8XmteP/uPe7v7nC6OMCM9ugpJbTA9MzG57UEpNbGWh4BkJmQX1jEd4/nwGcRnatrlVTvI3b9z3/9HvP0Ht9+8wUOhwPO5zOORSOr1tHRdZFClxqRhEkJ3cv5TJKfCoogRvI9cX/26kN9wE7Phiw7mpA9GBBjD8e3TbRMXBShknOZMBUavvFMIaJUUqKKDM4RExIcexYNQ88oj4/xqgOgeWOggh1eVaCH1b3Fe+GZWCX9thjTwcXXSS/I6JQDt96RCbew0IiUam8oGTgcjnjz9i15Ghqp0sqen8OQKUttjTvPmSGWJ1kYdMCRSGwFRyI0LHyBUglZS3KkjvFY7P9ojLpDTrJCNS3OFBrptZCaj+ZK3XoowZBFiOfvsJwQauNoWACg+QsbiO40wCsZSVEJQIKbuG8OhGtvsiTEkoWJmca3XpmTA4a3xt+JQjP2KtSIeGuYphOKOTav2LriL5KhmKF6g7cNTXtrDs4SwFGUEX0e4s/EROySkhqUjpJ8PH/2FPHsTGq74KXxfGjOJclsLHGVdH/mMo3pxFizALZ1U0P3t1+/6IKk14ZeyBUJF8m4bAAM+1rhB2NsE7NTxL+3yJLZiUCR0ZHUXcIhNnWTxz9HPg0VW3OR6/IofhocoykCVLnnoXSJjj4lffHehnY8IbHR6X0UEITu9zln65wPItRFRBN1vEeXRKixaMwUoUqQ02MUPNBC23q4O9L1sUpC5wiFjqr/xvKCVtpUicQCdql46gigErfDVEAKGYBGWDFWAjCkvCEFjlFMTpr9BnrSNSdPQTYe2AMNomrFulUs28oRTHe4ZaTC7zz+bJYF94VdEI6UZfz94y3W8xnJDUUHY0lpFIYG2sBvi+P2/Ts8PD3hdLqASacf5auxgdNz2Dv1Lp4CiZwPeHi6x2//8z/j5tUNPn68I7fkMCHM/XihkTdf9dmDO5Rl7z1QOINSZlmgZgTHplPa2snsnwth5ZCUL1vFw+Mzams4XZyQsnhChxO+/OJLXJwu8MMP3+/dlHNthi9Ia5tGggpC06oHMArvDnaWvDs6UvJx+A+Ex9mVMqRQSCSA53XB7//0J8wl4+b6CocD7f/Ji1FxF2Oj6Nq6jz0wjS41+BSG3jcV4J1J2ArSY7GfBHbsaqIx8uwvmhpgdPMeo1o3JAtVXB/PJcrkyPeIYrm1DWVOUpWJFzL4BTYCMfn/Au3huMj1BqLQ48OmWmO2jKdtxe3tLd68fkPn0vmgkYOQOwsSdI/yGUDHtp7R2orpUHCcLzDPM1Iu8pjgGWHGvVoBIjVGQz2+H0n8DxNJuD3LYlwFjW6reLbDnLLxrJySyW59P8PRVLBo3QahOmeGlwY6PhDWxP08lWnnzUEjwx7rjaOenNk8MZFZiJNnZCQUo4Ppx/cfME0TJmXxWDSQQt9M5iTDx8ZlMBk3gJkIzDa4QbsTbkY/A96aeIhAb4beAs3OSDk4gvFZ+JxTSyhTJhoEnbsmT2nL5HsJ6Wjd4FWoaSosqLKNws/Tvi457ss7gbt2oWfaR7XBjONGM0eaIkYg9nBWA2tUjv0dr190QcKEXEpAPZkktDp8axuwWkoJJZxsICkoXL4EBjhzSHJJqC6DGEuDZBkOrdHVGm9y/aeqDh24cEfr7ILCuRVmTEDNmp0m8ijagLq70BWMRW5CTHjg6KJtkUvBjnYccZKIQeRAIh8qGFJUHlCXTSQk5sWsemWX3xuD25x+GQMeVMpsfE7zGF2xQo6sjCQlU0CiAOgP0RvceKi22pAFE7u61ggItKKO6wVxlUtb0qbRkcZBxUPl4uJioCyPz880JeJXATegzHz/3guWZUF0tFDBYDmhLivQafT09PAo11bOVeFcM6UUzNOMDMP58R7eGpa7OyTveHh+xpYzjheXJMkG/yDGIuqcaAIFoDvWZcXF6YhXr26w1Q0/vnuH8/Mzrm9u8PbtW8yHSejThHVdsYmca8jo1dEQl6dQhVb3C1WjFBK4X7q0sphtrcJAD4qf3n/Au/fvhaQV3N7dYZoyjocjjscDLk8HfPLmNdq24cOH96jrwjygnJXNwg4Q8MFR6bptyN9iEdad/jJUoWldsk3ld4m4DAxA2/ePPmeD4WlZ8bS8Q+uOq0uOcWgSRelnF1OWEQoNp/mIdV35z5pGqYmF21Bz6Rmt6wIzw/F4AsItWQVTkkwW7qhrp8NriiJWEQ7igxggBMKwbA1eYhObyM0Y/K+cJzw/L5jnjMN0EPnaladDf4t4LuSwYey/lIv8OpoKjIxw5DQH5sMBhxO/wyY0pXggRaYRRR+KrcenJ5K+9XyOxyNOp6PGg4ERc1O5UKQyTSpoeMaQG8NCcF0XICcGGoKpu00KDgDkGjSSd5OeGbJk/caxNC0siGIE+hCeR5TYRjCcq9hXY6LCJJChUPHEKR5nTE+B1nHdJZ11DiBPBSZE3VLCzeu32NaFqJpEEyZlpRY9KcTJxVUEutdRmMarCwlyWTQ4+PdTcB3dELjQ1hqRfjWmUTAGmlZ7Y7TCFlltXLIO517Q2Zq0lOPcd5P7cAlRiO6RqHzH+xLlIc9I1lE3KtmoEiLaGEVYU2YOx/Ik81tmMf73vn7RBUlKZHRHbR+BZqwnuKlM1eUgpCKgOx9EPIDQeBWjPGDkZIldzwslA9W9Gtk4WIEiRgvY1SGRO+Dx3kI2KYJUSby4VJC0RmWLyzuB1bsN2M8byW0dUcSowk78fL01zZSjoOGle5jo5TE6Q3V2tTYphNI+AhBiNOWCDBUz9uJ39A6kNIohctD2ir0JHdERAA0Qh5LHJUfzGGU1kaaMnzO/IPvawLX0DOKUsGCaEw1qDpzXVagMkZG4DGMwMk8T/UAMeHx4HOqoYMVX+T/UdcXz07P+LnlGCu/dD0Jz3D3c4vbDB1h3HErGpkvkcPMKF8pEmaZJSpQ+1g/HRbycz8sZ2YE3n3yCh6cnPJ8XHA5HIBfcPTzg+fyM66trfPvtNwNV4f3Nk2+MnDrkw+I74pUCeg54JmBrdtbzXNC3iufnZ3z/1+/xvJ5xurikfToS3OjW+XT+CLsFro5HHA8HHI9HfPnll3j/4QPuHx5wOJ1YiJgNdLA7iXuWAuXKo8vtMVlT4cSPwmdTpHrpQjRInK5Dig6hZ5bJrfjuhx9xPNzhkzdvcZwplWy1wTWGad5ReleR5qOY5xexNxs5vSAG2+4kG81FIIH07HDtc54DvXVs5zPm40nqCXaYrYZajt9DyCJTSuTJGC/Xhobn5zOWZYPZE64uLwEjwrSuG/q2svM0KvuisCyWkSwDOaE7kYgeXBOQyJsmhgaWqeDi+Amenp5xXp7gXZeKlZftFXpz1NqxbTTrmueZLqsii3rf997Oo5P5pP5HkPoZikm5c1UhHd9tzA/ivcaZ2uADNYYBclBCgdGvRWOiHZ0RwbP7eEY0rFPx23xclrAUp6UKqfg/+a4g0rj1nrTLsnH81eSofXlxxFMUN3LrNQsEcue35ExUvfre9Ln5cAKHs5DKRb/JicyYzlTWASraakOes4rPuo+0VSyUxCKv1Yqz04Rtb0SFmFp4YCWkRHkBPMm1lgRqdI2g4vfqPxiD0khkZ6IXAPKGppyFoqgIHPy5HQzY1hUlzzuC9zdev+yCpGR2HT1SN6QuaQ1TSH7dQVdELjo+QFa15EqqGgx+h9s4vAGwkn4xQ4Y2EBAoQBqjHv7+zIAykWM5baHsbO0dvvHAzeuGsq2jcIi7o1d+4Ug7RMy3IeKiSFc8JDWacUc3prkSouZlUFLBxeGSfhGhtqmbJM+soIe0FhgR90o20GGcR4Hn0AFkxtA7kMQWXhAOjMUJdV9QJe4OpCk8KMK3JQqkjq1GVLreiwnqw34AucWhu/sLtNbwvPiAfDv6eC/RRaQ8odaG8/MZISHlDdfR1hVoDBhr3oHMfJQYg3Sr6B1Ye4O1DbVX3D08YO0Vr17d0LskZ9wcjpjmC3b/0akYIXE4OTUGzo63dcPyvOA0H7AsG5AyThdXoCqEksfWOx6envD+wx3m+ciZM5ejNjufcUifU8mAmyLsJfSMSAFEZ8lnVErGuw/3+Nd//VecjkfcvHmtNQp0eSfk6YA8z/De8Nwanu8fYA+PuLq6xNXr12gGPD0/oSiLI6XdRpB8BJJFa9/3ZcoG88yE1BStgNY9QlxmQkUaIsHU1BG2gJXhQDasreE//vJnoDZ88dln6L2jzAXTgTygljZsm9xvwRGDawSYxQd6yRdLueBwuhjPKcLrYAw0C25XNzmEdse2NNzfPeDy6oKcFH5YCXoc0KUXqE0qZSSR98rwQzMidM+PTxqNZEw5Y20kpxKgiBPO6MOh4j9lzvBbtX3P5IwsdC8lQ5VBpLcdeXQZFzWv8GrY1oqMhMN0HCRT7yRfMxumjrwVmA1OGoP2HFCxFMZe3Mb6GWrOLMf+5t6LMVacIb1zzJ7U5cOS3GeZRDvQZNUlJWdYZVZWDHbIw+wq/snHyUjoztwwU9PWvKFLJeQJ8NphUa/2PhrBJMJwb7R3mFLGeV0xlTK+VyppxB8SAuQasSYh7SVNdEsVCj6lotrK0WvF09MZOSUc5wkrFBQqVIoJ0hlZKqTBqjEpRXUuF9ARNj5DkeyqRVxJMiQPTk/V+QEACdkw/IECTeM/z9hZJqCbuQOetKaSI1tRJEJRcUZ+Ym+dRpPbNoQaf+v1iy5ISuIIpGrGD0BKDJL9snT3YYZWpnnvtNV1Btual16H+Z76GbkEIc0anUEIeQfXIaRgKohEWrTMZMqwQHZ17jZQCSXNVkgjnuEWIyBWmiSD+Tjwg0BUSqbuPJCNzKq41jYOHesbnp8fB5LUUAVaSB5mSSY/PGAMkAmQ4N8U+TqSqqWEIhSKXVn8ojQ2ZTLOM6FxVKid6hg3vID1+4uq2cO46oWKBlEIBrfFkA1okqBFsdR856FEQRBIQcC5bWW33WRxlXNGRvysjmSZs2EYDvNBxUHCVivu7x9Qzwu8F9w/P2LbGl69/gQlF0wloycDUsLWN2yt8lJBwl65cpTWe8fT4zMcwOF0Qs4Tlq3RmGp0J/JnyQWtbvj973+PTz/9HNc3r0COsNAjjYS6ipIEdsQpEX3iugkPBiIAJdGz4N1P7/Hf/vW/4/LiCm/evlVBb9jgg5dAGFrZJ1ZgE7+Xx3XF00aSaJY9ej8vOBwO9D3xTr5LZB51eeCkRP24BZExRiLQvhVpHHvRMEautiswAnkwoZfT4Yh0Srh9esL79z/hk0/e4rJfaoR5gYt0MXgBWd1jXKw5JSoCLCMzQ55Fk4HQP0EncqnkGotOafA0TWitYT509HVFbRvll3B+T1E0gg1R+J6EZ4l7xzxPDH7rHRkZy/k88nUoO257To2CN5lgvSJiIYLkmYri4LcYiUwIovG2rljXTXvChtNu0mXT4chTxnSQyqNuY+xCNLNBYigAcq11qGveDfE6eAHZIKODybk6R6J431odqscYUWeNHltV8raKereEaUoiZHbUSo+WKRnmnNByQQSs9g5Y0fCudSCLg5UT0NPwiMm5YGsNvgFp5ugq6Q54yQ8iV0qKrWTotfL7qhybc5pH1sZUCtpW1TRJpeSMKChG1+nT6YhtrYNYz2wwItXPD4+4+3iLN69f4+LtDc9DTYI2mahxbdpAT4KvN+WCdVngIqhyzAd0EX+JiFcVJeSdGXabiHBvM2PD2wIkSRzvYggwQOqDGXIxrJV3Xe0dta+Ymotjc0BKhhUbUnGYb9i2/wlIra1t8JZpXgXsErSA9MNwKwWkJm8Ag4ijGs2kLJgM1M3L3Kx7H6YzMToAMAoTgIuf8sd9TpZSobW4B1zfpMcm1BqupwCLA1PVP7TtQg26EB43wES0NR3o3U1uk0Q2ug79aWZei+kgz5m5UvzMGWlKaC3TerlwDNO0YBmwRx8BS1mHRFi9R5cLPVteH0FS1DQFkWhMBYsuZIeSQruq84BsMQ6lDowLaYS39RhPgc/f92fuunRhkAujemlTMWi2c1PMOA/uHWiccxIydxLfOpBQUaYJ03zAVGawaElI24an5zNSJnu/tYapFH6PeQJS5s8W6deFbrhRlkdki5yl8IM5HU+Y5hklF428ILgXQrzoDmql4HS6xA8//IC6NXz5xWeYykRiNbimp2SDSBvzY3No5i5ZpUfBXfDh/U/4b//277i6ucH19TXfs2EQllOQHI28BFfxrooauWT0bhoL0OTp44f3qOuK0+mIeZrVHAgqT071Cch/yIPzoTGYumZ2lX2QvJNGn602IGUUeYhYKipMwPEMQDt+dxwvr7BsDeePH5HMcP/4iPlwpIqmdUwFmA8MF6y1oWikkSfmsAQ/CyaUVLEQWeuzRTKwHRRESc7ENBVyjQzyHRJpXBccL69omFRI6p+XKSNVPWIAbd0Qox4SoSWT1zoJ6Sj3ARGYffBsWFtH3VbkrSGXjNPpCE77dIalrA7WsNUu3x4T3ynBJJWmOmdowbg7Oz9gjF9JkgwlWIYrXyl1jKYip5fp6kSQm9OksNeKXERKNwafBvIRxFQASq0mgd46m7LjPOM4T2i9YVk2Ig/uyAaUacJmAHobTV34UfF5xhNL8LZ/docksHG8O5lN4aDNetJxPB2waPxCJKChOs9Tr33wKwi5GIPlVFSXmTEIvUPkUADJcPPqiondSYnKhLHIcTEfCDWfpYizasqY5zVhXRum4kwmVrRFb21vOmFI0fRYjNBVeOn9tb4h3H3n4zTuQf6uJNQtw6qpSHRxtCC7hGiweSaWPKHXNqwY/tbrF12QUIaly6CH4dOkAmKfhfl44CLyaKNhHMIh8wrnxN0ldXA+9Eop5GLBM9EBCsGG6thdJDe4oa0a52SOIJIu16FbNwxp1TAHcw9jEJhFhLMPqLPDsK0rUBWSZ4wxn+eJ3Y4sw4vGD63WcYA2c6AkXF1da5zi9JtYVwRhzQP21zPsTlmgtRfPUjs3fGBifGToKMmAbrR4T6Zlz5FUxNkbwKRfxDjBdO9ZfHSGYCEJlq4IPkFckilH5+ND8hZIVDghCrqSQRUNgZrCzVKhxbN5QW+VYYQab1ljUVHdYSUDrTOnoUkqWDLXX1HCJjq6qTuMtQNC1nXjATbPM2ZxHojCFKmTOMYK5+Hh4ZIMp6tLvPvpRyQ4vvn6S2Yna8QkTRVq7cipA43yaBglhC8t+v/81+/wu3//d1xcXuHq6oLfq4qnJLi/dnbRfRTGGAZKLwtxgGjC83JGN8Ovv/4KP/7wA26fHnB9/QppKuQ4gGRuAwb5OUPqnhitSWrZ3Yc6yJSXIYdv1I2oS09CxpIuaXE0qPIqWGrDupzRasXpOOHHH3/CeX3G+rTg888+x6vXr3CcZo5tjEqV7k6US0TJKHlLIkEzpYQc40LHUOTkkpG9cFxh9OFoCju0BDImEYoSk2lc13PnD8spIRWgVY4wq6SheHEW9M4YhUFIFJIVeUqDQC7yd+/hEQSsSTyGVLBtKw6WAMvojXvUpAAaTp3BSUrMf2q1K6yU67PViuM0URXSGmolYdh/Rjj38d8bMM4JmhkmlJ7Rcx8juO4N1oFSOBIJ8jFTa11nBDRWM0wlo0wJ03HGBMPWn9CWFZaAHA3nlJWLswgh5vowNxE6XyrBeFbkMsN907lHlJjvoY4xUO9Oorn8elIyIn/O9VoyPT4qdv5fNFcp7cTt2qtGUxr3F8Ph6qScmz0kNJDq3gMFUuMiLl9wX8pU2KS2LoK5nlknQhdmNG6hmBTW6sK4wgJDDSXDGDVWc0rrq5DUCYWxCMWxLAumKY9YAzdK6GNU/FKJ9Pe8ftEFSev0H4hNSUkeq1wHBkxF/boWNFyVLxQTnxAESnehVxBb3clWp8TQtChVefY+TGW4qcQuhoviyi/CksHmA8yZHpxJgUZMlociAlCnLAjCyPyOWPD4Pn0cZmSahaBwKgWHwzw60GxF3A6iGbkwTtpUlKSUsG0r30UD1vPKxRxkqF55KaeEFv9IutzgZsQMFAJk2REFRMjRUbDA2aGnfYwmkpMngyVexKXMCP8M6BlOuQxkxFLe5cP6PqOzhvHyC5Mmeq5EcQK0vmGeJxRPWBHBcoYylUGUZJx5ZsVvEN+DRLxcCpBoYMTCdkIuB/45B39/i3BCKkmycVT1cH+PqRRcXV5hGEGBnQ5hOdsvHzg8keR3e3eP89MTcjJczEfc3t5iKhPevLrRWEF24XB4bdi8AdM0RonbugXmhL98/x3+7d/+DdfXl7i8PonDQ78PkuCYVpy7wiKdYzJ3wKY01h/ErE/ZsCwbnh4f8Q+/+TW++OwTzIcJy/mM7/76V0zHE/LBkScmb3fnBR/qn5BoapqJoB5B6ikY90iXOybfUocJnUHsaf4bPk3fFROlzDgvG/7Xf/3vaK2i5IIyH2FlAi5YyBznCUEwJSLGBObefNint1qRnPu0lY5mhtYqmm8o+YSEAl8WrOuKeZpQyoTe+TPCx8gR8vUMCyN3J3LEizH/TNHnyVV07MGdAGXYy7rArWOaZipaNPakeVU0C3y+28ZL4TDPOB1PKLK7L6Wg11WjIl4BdavMJ1EnjY5hsAgA8zSzENNFy0tIl6K+vyCDsjHROenMlhnOtBDHxR3uG7kZKSGZD6XjWNsa9yVQwRXKupRnXFxds3tvDrcCYBUaGOtBLr363yWTxBtJ3kQM9lfOIPpLJwWEJTpRHT7/1EEOXqswiCsCGVB6R23OZHDnxV5r2yXEKkBdQ+MchaSI0s0BF4IUhpMpZ/TaB/8qAeQDilyaLMN7cEpIZG6twyr9UkrJ8MxGuzdaylNBVVAbBQqAyKi9Y40gWkBFHL+j8FEyGMwTWtuQQTnxcS5YV/JvmorgLtIszFDSNMw7/57XL7ogCRBkGOZ0wmfRqZepDIt4Fw8hlqHBOdLBPnaYCsOGcplEDmQnWqYi6J0bZF03SnvD6VWHu8M4FvBgPgvqCkQGO5QZs5mxf3Rohduew3g4uxjjKlzE/6dbZZkwz4JcM3kHOsnJ6u4MFhwSLP959PS2VSEJGCOt0Kvzdzh6q7DhjxDDAUevfRx+ALvcUZ8AsiInsWxKuy/EMJZLL59DICUv3Aw5I0IP9ChmuioefybrlllU2GnDRYLV4QlTsJizyGgQhE4MHPBOhUkgMDD0bjifG86Pz1iWRfJG5/y4O0ohctN1MTYhWuYWfkJ4enrC3d09Lk50twzzLCCQIOiZElFLYq07qBgCOi4ujui943R5gWXd8Ie//gXrVvHlF59p7YueoegC75XeAqF66R3ndcPHjz/hsy8+YbFmceiKyMsFgRzYuju7fs3P+RXtnBC4Y1sbbj9+wGeffYrPPvsUKTkOxwO+/uZrnC4O+P0f/ojHpzOuXr3l58pZLpL8nrMV/S6tSYsxB38/94CjauSZ9N4MhtqrnqE6UwNilNk2dpcXFxfoXnE8HvD49Iht2/D4+IhsCT98/x3MHZ++fo1PP/8MZY7UWElB100cE/GL3EfBQKFZkOJFIneT7fkeXbBtG8dqcdpo36cUKIwNTkwY2nGy5qNgMaP5IS8+w+l0QCqG5/MTRxuSicZFbHkvToIIXCubsHnKOB0OLGjQ5d0CEZBtqBIjwDJPiU0yTKMQg02FxV3J5EmZYesVT8/PQ2FjlsV9cF1kXJetdXQ548bXdnd7jwTgk0/e4HQ6DJO1JP+VFiF5YygJNBi27liqY544Gs65CA2sg3MHA7J+V+20gYAazhjbR2PlYJNXl1WFIrv9nNLI9nH5H/E7p+iA6FxDOUwj8XatG+8YFSI7yp5HI1K3KuXOfi8wJiCQ3sL1U6t4PhodQenHOsPJk0ri2O3FfXVJpxuLbCIefSCSPawqEMiiPp9hRIwAYFCpCqk408gHYPwCKvdCjSiDcU4TFWPQXtee/58AIbEXhYh7H+qROKxqpxNopCCaFDZcJCwgoMs/Z3bL8zRxsyWFp+W4Mzt652KqvcMbfiZ52vkp3IDLsgGN7GJyJzrG6oOIaNnGn0ccbmC4EguFOCHU+cBlmc0shOPxiDzxgq+1yueiYa0NZpTUthppquSFINGmvG2bci2IQEzTNA6KnAkZ11p1uXdWxh5FCDe9vyAYAjowwvMiEVUoWpity5lQo67ufcDhVdkTTSZS87SbYq21wZAQyaUxy+yBNhVeriy6dqO72BxJeSDutIDuTj+E0Zk0eiEk6e0dHetS8fT0jGXZ8PjwgIfHB8SFnFPC6XgijC0y6x5wJz4LgMfHBzw9PeL65hrXl1eyj08yftrlkia0jhwUDJ5QMsPN9RXWZcHT4yM+3t1iXcm+//Nf/gIzw1dff4WU5NuiizskzYc5k5zrjj//+c+4OJ1wcX2Dj7e36CDpDr0P/o0rqwfge+D3Sch2Jxiry/OGx7tbfPXZJ/jNb35DxKOShNm94auvv8Hp8ga//8Nf8O7dOxyPF7i4upIDJEYRSm+FQAfjd4S03mTbPzYg4iHvpOdYe7xMQ0V2c3OFeS7I+YCpFLxab/Dh4y2OxyPROhEmn9aNcu08o/aqsWSiGg4Y5k69Va7RuBoMg/NFI6v9EB6cCXf0tWGrTUiGo7aK4hOlqRqlDfQSLolyfEw9F1BJE+fZxeUFHO2FRYFckBM4rnMWGC4VEXrDuj6jFMPVfE0PIJN7q3HfWBLfiKt8dPUeNgmtYtOzAOiSenHKKEdyqNZ14yXoDqqRuVdZpFCBxXXlChslytW2Dc/rik/fvkE2mkFyrNeBTK5St0B/4mIzrLXh4eERlxcXWBfKil2S146GXivCHNIAFCHXTZ+196p1TGftaAJ7XNpCBHIi1y6QBEDjjnHxiqOxNeRDwjzPWOoZW93Y0M6FtvYejQMTndvGEZAH1wouRU0UohH10EiOF/qQx3OsQgijSgjLCxd3nKPBwQOSrT9vMf7GPGX0rQoZJmJOknRF+Aa1rbKwS0z2TSoOXWcWQK+auZDg7Sma371Jjbsnv3iG/6PXL7ogmeYJ05RoZmMh/yWcqdYCp9OJlroRYe0G3xznpzNnjK2ilIT5cMDF5QkXxxnhXpnUOdTG+fW2VZzPi+Z8LH7MyUvJeUJS10+WfCTsisgJQs9dxYgBcAV1dWOnbAAs7V4hngiRZRpLoKTMcDhl3rTWsGxtkIoALfppYnAWgHk+YBL5q1ZmWazbxkLFjJeO/E3SGBdRQtyRNGPmCVwyrYmbLKn7uEz2PRtjm+ZUtuScEfU4+QH6mZ5IsBrzGFf17YAVQd57NwozeNBHTMhWTqh1UyHUR0GYXCiOS3rWMWDQUFxBnz2pQLt/uEd3x/FwwNPTM1rvKFPBh48fkMxQ64pcjsDEdGAYxky9wymZrry0WmUEwds3b3CY5zE7B4AyxXsHZ/BNh+0LQ6esCygj4ZBnPLcHbHXFYZowTTPasuB/+1//v1jWM371D98iiNOAgtVaQ6ob5mR4uH/Cw8MjpnnG3eMTUiYJF5CySs8jOhtAaMPPLv69w+ne8XR/j5vTCf/3/8t/xdq5npaNBOGcJ2y143i6wj/85jf4/LMv8If/+A88PT3gdDqxmzOiND66LhdKKUVbjB5SwVzS4IiFJTgRNEfkBsEdz+cFTw+P+PyLz3A4zKMbhRnm0wmf5BnruqK1DZOxaOhI+Lff/R6fff4ZPv/881G4whhr4I2k0wqa2JG7IrO8DFgxoKZx2aEnwuWZ3KJX04yPHz8iCbFr24ZqXcm6wds0TLqgo2PmxZgGARbiO5y3FVYSjhcnPD+f0byipIlNQ7IxFkgpITvR4iAsP52fYSlhng9CUqvWjaPVnRfmZffDcDVLw5FX6+Hu9o6qkeMFlmcGVtIwDFoj4sbYJG4MABhRTQBW2EV88gmNxqo3PJ0X7SmNucUvKSVjWciryGoArTfUbcHd3Uo0urEIP95cIx0OqFvDtlKNY65zJfhZvQtRjXOs6TmQ+D4fJhyUmns8HvHw8Y7PUaiLXMfYWCU+t2VdkBIRq5vXr3B7e4tt2zCleThJmwFTIRXgeNQYU2dW09lOkYGruGJR4vpsRAjFY0riVgEA6kC3oLEgzz/ujXXdMM2QKqyTk9N5/sylcARZ26A3RHPF85KeNUtnPAhRQxsFRs4Z3hoOZUKFkaj8Qjrt7vBaMR8OKOXvKzV+0QXJ6eICFxcnHA4zIm0QZjBB+AYoTZUHfAvosHXMUxHDv+NwmHG8mEgM0ndrRudLr2Ac/bqhN5IHI6IcAdUDaEJQlucodEgAMstAEcEpSQEjglJIi71B45Q9BRMm5U5Xh9AbmnesrcJRePj0YE9TrWAp8fNOnO8FNPn49Mhk4kGMtZ/FhIcHS6RREiZNYw5ca1NR0LH1XaNOp0QASfkyADujHMZuHb32nRDWaMRWcpF6xjDPVD1YZ0feNsfT+iyokXAluZ38nYEmJYWZtdpRZRjESywpJE2IGFvHgZwIF4NJju2d8vHr66sxrtrahpILHu4f0NuG08UlppSw9Y7jcWKn3XgYmmSUaOyWSqYce8JMYrF4E6318eeLDsQpG7k68lRxsAiNWXvX5Xi6uEReqGL5+PEj1ucnpAz85S9/xto2/OM//SeYVExUySTKe398h9vbR8zTCR9ub5HmhMurKxZtScMvTqx0QfbhE2OJZlIe3h9OH5Dz84LlecF/+ed/VndI/4pkBUgNniaYbQAacjFcXBzwL//yW/z040/46af3eHx8wuXxhMurS0HQKsLA57ttFa0x5ryYfCqqCnqRzpM2qDtHD3WtWNczbl5fYz4cqZgTaRXu4nRUwfD5Z4hUhePff/973D7c41dff4uUOIZAp49D34iWNHdsWx2Kmto70DqWbaPJoHN2b+ao24aSEjwXyXpl/e5V+SGSomstZiNfxYoYQU5Dt5RJ9CWvhgjQ7e0dPnn7hhLSbR2cWTNDmgoyfFygGdMutXdgWSvydJCUOw9jLBaEaX+meg98L44w/gjFW8rA7d1HuHdM04TuHUvb6NvSO6MinPsh5TIK2/h5QULvBkwHuhpv2yreApUvaKZwwwRknqU8Bx0I12eEXJiI7nlZcHV5hVcXl3h+esL5zALUQP5HiA5SrH/bTd9ap7TbK31spgMdai8uLnD/8EAkKzhQEK7h9PFwN5zPGyxR8jpPB2zP92gu9OmQcZhnnWMJsISpc+wZ4zNHD2B/j4MA82HCoRmGQXYPhDCkzIOVpnN1SOudAZ7IagRqA0C7+a4zkqrGTuK4cT/O84S2rRoxy9RtorowUP1kCR0N1ciHQgNHcpk06a6R5Lpuo1D5W69fdEEyzzNVEd0BdUutOlLng61LIAcBjbEBJ/mQfydljiJab8Dm2DYSsAzUnbdK6GtZFsB3dU5U/a03jobaxvldbzxoisEkVTBtJnReAN0FI3ZmEXBtyfdEcFeZyvhsZNrvI6HoLMntgPgkBWmilXTrLoIRM0aWdRGKktQ1AOgdPcVcNaGoqyum1lVSr21rOvh9dDDQSAGambf+gneSCGAng2BCj6kTeS0vZLeArLVppiHDLErYck4v0lYbWqvjd/E7COM7Xpqxgd0EZacEIEH/gZInjcXaOBRHGJYKguaG27tH3H54D1jC48MjSim4urqCAfjw8SPquuD+7hYNHYfjEcfTTF7RtuFwPOL5fMbxeMQ0HeBulP5ajBc4jlh7lQyVm3fKNGhiqihHYcgRHJhwOF1gPlK+ejzNqNsZTbLVh/sH/PE//oS3n36GeSYj3rrj/u4e97f32Cpw/3SP08UJ5TTjpc32gHxDpQsTGiGmvw5vHuIJy7rg44f3+Kff/AbXV9eoW1Uwm6N1ro3uhq21fRQDWu5/9fWXuLy8xJ/+9Ge8++FHwDl+MIVfhrzVlOKLTOSQIWTiBPXgOnB9dQMh+7XieDjidDzxAuoi+HWiUK03cZ4wkJ/WWGznPOF4cYXH5zP+8Oc/4nQ84vryAuYN3mV6KF4HJ5PBsMXYm/SJ0GWtPdUU+x7eDzTHykD48Rh9L5PUWkj8Pey8dU55jFX6gNB769iWFacjnVTXjUUcFFrHQEJZAkjOmsTLojkg/SB6p/095HhaUviahLOu4MgkQ0lIgSU4tLWGx8cHvH79BqeLI+6fHmHe6OloZUc+BZtYIC7icoz9oCKBCisfppSd1Kpx2fK9NTlZx6kuQju4TnureHx4wLos7MiTuIMGjh6VZBwFKRoFCDB5SrmjbSuqG46XM8cZYBhdrX0giCklVJkktt5RwZH2snAEnpBQphPN5iTC2moIBvgeSik05guJbzLMh4ljLY1mwxtlqKgSic1NPEXeG5RIewqTSjVlcUd0Q1VBUbIGkd1HRAqNI2kG2RoR3pR4UbrR76oUNn+D66TzgzYNItSvm5ZGNIP7Pc1MKcff8/pFFyStVqxmaB1SR2xSksQoYf8yoWo6gq2KyWtA89jlvMu4wtq61wbIh4SjAwxvjMY2FkvfxyUZYVTlukwAwIVM7KQfdyAcl9nF02fBQEmhpQSkjuPhgFyyOqaVczpgEDKDr9B7UxS3pFdRIbsBNmNqAArRhSknkkwzL5i906Q9NaAD0F0OfzlKOXbNvqMpWeFcu+Sa6ZfoHRAZC/JiCUa5d87Vk+acfIzhC7CTvFjtAyOdLv69qvP+Is46p2nA/mEbb0kcHD3jnCd0dHjPkPE/nUx1+boQnuXxGbd3d+itY1kW3Fxds1toHa9ev0JOGVvd0LYN97dnrOcDpmR4eHjA+XDA4eISrXR4X1FKlpFVJx8pZcL98MHKH4nG4erKE52b/cXmT8nglnC4vMbheMLz4xOe7h9weXWNp8cndPyIT9++wuXFCU9Pj3h4fESaCpanR0zThOPpgC759SA2B6QNWbok5QvtRAbyJnpH2xpuP37Ev/zn3+LrL76kHXjn+GFrFc9rHZ11RDKUTHkgybWON69vcH15id/NM+7uPqL2DVbJf5qmCbWHeVmGo6nI6VwfbB31XnWJNcfyvODicEKZhAaoGVkreRRRfAZngC8d9OIZzIcD+VwZ+PjwEU+P97g8nXCYD5hypmIhU1YfKbkG+SAZCcnrtqB5Qs5HcrkIB6BAwWdcvsgo8I0pvpZ2aWiaqCTZtnXwi5KI3qFASgloW8Pd7S2enwpev7rR1xRO0UQf00TDM9M4IpBRd4YIllLQ+sZngkBkJMV/cZMkxSC4GyPngycCwPKEtVX8+O4duWxGfwoGA4Zvqo8xiZkNA8PUI3FWJoZye22tD/TYIf+O4DB52ALwPGxCESEux7Ah8IbnZ6KXIXZoQaZXIeVN3jY2UUXYiFR0OAmnQnWLoh9gYAIxL5VRw0cx4+LuLUtF74bT6QI9ZXTbnW23Sv4bvKJulaNcEUShZ4POxrJv/LO9SZJfJqSShcAmTDn2FPcAqQFGdBKkCuTCUXvKianMrWHd1uHZhUGIJXo4TzOmecZSV0QlOM8zem8c7WxVRdiKWnXGqmBmqvPutIuWxrOfhVbXKOT/xusXXZA8PT3jeBITfyV0lgKNgGPOYWWrggJRuXFRGRrU9ogQR+lnF8s6SJQsYTIgyV6MCFJK8h6Q38TY4D42t/cOa0p+9Tj4Q7mg9yIEJEn/z/l1w/3zPQ7zLKifsHGHs7LXz86W0LrjuW1634ZpnkZ4HHon+pEpQU2C9tpWYc1koOUwHVorDLkQlsueldhYMAKhutNjRPPvWnmwWRxB6iYRxWB0JO5ydwDq1gesXsxeXMoyRXI9FzgYTsViiFwe32eq8VUm41waO6mU3y6fR2tOi2xd7hU+DvlpmlCrobYV7999wA8//IT5MPNZpSNubq6xVVb/pRRM84xDOuJVppcDasXT4yOe7++Rzws+/eQTPDw94nC8gBlwf3/P+fbxREM0Jcp621i8qmO01NkFZnamDLQidwjOTrfzfkLOB1yWAisJnkG1wbrh4/tbLM8LzssTWgfO5yeUeUIp4uF4lxpPklOws3R9N9AITgAaDxvj8/vhxx/w5Rdf4JtvvkXdNiVpk+bZtFdMCpJi/C66uqycC6zxoG/NcX1zg62teD4/U24qQnVHgldgmnkhUVVm2AmXAGd7PIT7VnFxPOJwOAzkg5LDWIOG8NUBICJ102VFaXzOGfNcGGuQE46HGcvjEx6lkDrOMz777HNcXt0wwdrIWSCiaRwtlQT3gmliGm6KSAcAaS6YpnkvCHwb4xHTWmU2lPaT7aMJzunFn1FjZMkYppYyzArmKcH7ArM+imh3lhq8gEWW1H4COEa5uj7h4f4RZsDWeNm0Rn5EKRPl9inpUpY6oxsbJiOCSmAeeHp+Bpyj13kuXBddcfVNf172CuN7csDr7hQaRPdYfDkl1Y08RxpYzAighTt3N8+ArjwxmYSBzWRWU9R6FweusKHYVrQNOMwHFqWJCF/JGa2x4H1azpgmBe3FONjSbnZZMqYshQmcCJ91bO2M3GgINs1hPECOSpzr8IZtPQ8DSDPjsq4ufxfdT4l7kuNso/y5kcPkyVAK7zxvMrisXc8ySzVDbhslz8YzEFEDpXiQ6J2FsNnMJmqjws88KwKi4/LqhO4HnNczavNhgZGQxdMxiSFAuXmHmqiXBfPffv2iC5LWGy8pjQSA/YPzC2hSOzmt+3XBOuT/4Ts02tqmC7ePQsRHSqpGBVYFL3YpPbQ4FUrn2CVZUMHStLB4mCYYImtl35zmHfAkCI2bnI6YFeflzL8bUizEBqXnStKh3RsP2mniwTgVeiosyoCIYLHapFSJTkdGOxzJiFQXGvyBUvj4TFkIk+n3tyZHWf29Kki11siM2Rnp5HhMKJO8LzQPDW+SwcZ+oZYxhPuqDwZ+yZzjd7mi0vETo4ujQRRGN8dsGKIyw8Za/hPJEkoGHs+PeP/hPco04XIyLOeFsu+EcQFkXSKlUOaXJqCAVvOPj0/wnPG8MDH28uKEDsfVzRXgTEXNid3NHiAnaaeJvJsMjFi3QUYM34fwrYEBXaXv6eJiyP28Ox7PZzw8P6H1irpuOB4OsMICM6IBQj9iOvxdxaD7/ryBnbeznhfUdcGvv/0Vvvnma2yVcHKP/ycgMEzEKC/fYeMwSHJQnfHw9IQPH+9we3uHw2HG4UhZ81IrpulAlKs3ETlpuBVOyYBQyA6sy0L0IidEbgjs56goA9ny6M3MEi4PJ+RkOJ/PXM85KX69oQsqj/WdkmFZK3569wFPzyvMEo7HGdM80aNBP3ia6WiZEtBrxbasOByPQh95WSX55Jh1pBQOzpI8O7vUUrIclhO2uqKbi3Sp6AQjP653jgg/fLzFq6vrgS+2RlVdECVzznSCTY51aSP9tdWK0/UlvNPCIKeOrSpWvnccpsOeEq41BzUO3tOuenlxhnHM4rBpkkkkn6P3cJyWo6xuRPoVBeqyQ/zhitqdviRxJqXMMMHgTvRKS4NYf83jkqRKBeKp0dHUAE9j7BD8GawkigfSa2bomdk/iRAcKLf1kemyWzLsFgapN3QLNKZh2xbM04R84F53sGAa53iaRoEaVgj0vGkjx6akjMNhFqeqqcnF+G7NmEYcgaeUoTepkXZ0Cirk4OQJuYVLtlAMmEzeuKbKHJEkQF1XjYcctW6Y5xlt033Yur5kh+W43+J3yOkXTExPOSOVCX/P6xddkGytIrfKL9nVpUdBYtEdOa2MdWkGkQyN1WeMYbjMRe4SxBz/tL8gTUIXxEit1OKAbOoNKhAgdM8S3Jpm4wZ0IQK6gDke4XtlXk4fxVIOOa0O+hj9cEPL/VLEPoE+hObqSqWGLvGtVtnq29CHozmyioGXckYzSKIbZnG8DIJkaQbUyMWAFEVOCVvqvERihKOnNUYEAAuBVCI1MiGVic/NsRPUkksGJ1Ky5t9djPOcfBgeee+ocLHy1QP2Gt8yUaXGDjSXjJLS7lvSSfi6vb3FH/70J7ReOYP3gsMhDmOTWVNCzjOmcsAw4jN2KnM54e0Xn+Pj3R1SyjgdjwB4iRzmCSkzywIdCPv8UN1Ep4zOyyA5R2ZFhUp8/xioDtfO7iTGVzfX99wHpF3m407Ec8ByYtZMa1I8QRcK9rWtEVnReOD+40d8+/VX+OqLL3nAVV50plFGbVRr9clxPq/w3rE51Wdb3dglNXpO3H68w93dHR4fHwAzXFxeAsnQ3PHw+ITHhztcHE64PJ2GH0sH3VnDu6O1PWxsKpTnd33bQ+qpAi+CzqwHWtBwuJzx+uYKP/74Iy3Hk+yuewSjSUprYRXA8dr9wx3ef7hFzglfffElPvvsLZEAb8jJ4AL2cs4sZltFkhlXb20o0qI4MwOh+Ym/JzlIDu6O1J2mYNjHdVHAR5HfasWynvHwmHA6HfV+2dl2dI2fgbkc0JCwoUoOyv37+PiEaS6YE9A2vqHSO6p1lDxhnmbK/g0vCgcfXjXOzmV8ZoBw/VYrLg8Tj9feOWqoVYhJBHYmSfRZIDHhNutC4yiVVylE7s0owd/r+zniqQ2EIUZiMCERKgR7byNsMKSxomljrSuKAfPM0U1K9CrylePxjIKeSCzuDiRJW7RV+LuFvPROvHAqmUqmqQhd5vM2BOciwg8zlmWFo44mtndH3zYiKooYORzmkUBuCLSBo/vawoAPg+yfc2bel9Q64jMAahA4QtOaBcY4DSmhgcrIeO9xLjV31KVi3dT0lkIhBhL5Ys0xzeTgEElmNMO2NaRmgGXM0xF/z+sXXZCga46Y1BH3jioznqwOWL0SISod4n1Up32Q/JIqiLDIJpwWTpa8QL2DHYq6AXo4hHENQTWXdpx5FapbkNFdlbXFgRRyYhB1+ZlSRPk6vh+I7m2YUnFTsehhZ019e5lmHI8HzFPBWjdCky26hv3z8xLUV2+JFtIw/q7ooCPS3pIcAWN+rB5a4VUlZyRPo6iRxuPFpc3nH6MbjnRU3GRuwvBjCYRqWGRHwef7ZoSq+VrroJcQyeFhUUVaHd0LQcXxvrv3UMgi54SHxwd89/13mA4zrNKPpleXOoDFIkPr5nGQ0JCtoYFSTzfD5asbnHvF87LgdHEJFiQkC6dEqLinTollQPXR9aAqkM4BZ8ImVMzG5ZLN1GkDHt4bfEgwHao5Z2y14t27d3h4eMDdxzu8ff0Jbl6/0iVQx3oL8ln8nJSYXttaJQn6fMaHd+/wxeef4YtPPhvw8k4GJR+mb4B3g28rlnXB+RxQN30mNgfu7u7x008fcH93C5jjeEUpfpaKxMxwcXONQ2t4vL/Hw48P+PrLb0TqDCdMZiCd7++Qc8Kr66vhKRSSf8sqgNU1J3WsNLNiKfDx4zucnx72rr7Jot1YgDf98yklhQVi8ABevX2DDx8+4H//w+9x/3CHX337DczbGAdGRT8dZpLkDdg2xzzNYx+ycUra8/z904F+MeSOcHSRch6+PAZo3ElUJWca9zVvWNuG0grKVMg3GHlZTYROY/TBCyQjLrWtOubDTKVX5ZooA5HK6KCsnQq6nXyZc4FbG86tmi8gZQBG1dtUCmplYQo1edAFjmRU40UXZQZvVXkn4sc53Ux351oiO6NBEoJmKtq6Rue5SF0SZ4PUhz5UJ/ydqQPeGs7bgm4c1ySNHeYpY6MbGhsfl79LzgzPi/tHPUuZJ6ZGe0KZZ5yOFzhME0FtdxQQMehNydyZmTDFJzR0IrudDW4ycfG84+npEZYym6qXY2pgEFs3IdEUdhhSZ6ZOsKQsvEuc9x4bbUO3pObQZP+gc7U1oBMJmgvjEVptWKuPIneTMIEHBxFsT+J5dYf1hPk0Y1s3GlE+nxUT8Ldfv+iCJBjW1uOid6Qu59LODpbdhUbxYIUIXexJowAHO04PdQmisy+E7oyHbsqSmQ3kJIiqfSAr3hrcmJhoybAJsYnCIYqdQd/UXLt7KBNY2fvYCABkfOQOeZ+wY5xKHtJhFhzAWiuLmy7irZCcJmMhcksSLbTdkcQXWdcVqQPJMrJRVtzBRdziBjcbc9yedEDEl2F8ZnFBNiV6MqVYHaee60CSZHZW+55KCeyZHeOf+Y4WpDEK8GGs1V0IWPdRNOgtgbPpJh+0QD14MdRG9U7KNEuaZh5eEzgbdpSB8KRkhL8zwGohaXzCn+cArq+vcXd7h/cf3uOLTz/HZNN4F5GREtVQyCuj2Mo61E2FqGMPOAukDBY20awt6SfBdTHlCSZkxsUbWpYVd0936Knj+uqGBaf8BWhFYsipUMUkA6dWK5NHb29xeTrgn//pH1GycU2BRZLeiopU/rzeKWctZood73h4eMTT85nICQynq4udCC0SXxStJQGn0xWuLy7x7scf8e79j5jnAy4uLgnBe8fz0xOAjpubm4F3QgV8hgllcniWTAVE3kYhCq6P5kGQwSh6HOTARFp0ThlTKuwQFVDWOnB1eYXtsOHj3QP6H/+EV1cXOF1egJdkHoUzwwRJNPX24nIzkVU9w9IEGHkLGc6LrdEcke+TMmJNa8b+yeK5cVTXEGPcMnF0FNyy83nB+bxhmjMJsU6lXyAu5lR0tA5Y2kdjtVWsbUNtVPV4nLUDSdN+TwZvOzmb3hMJ505itiWavsP5GUeRoOfPQsLFr0w6fyUxNdFGPQ0k+qWtegQxtvaywWTBlUsZBWKIO6zzjDcYpkl2CtbRGrkVGRxnpJwwHQ/oZ1C9hEwutbvOqUB3MeTQJRd+Pmdj2LcGy9PwH1k1RmZjV7Etnem8MQbzCORzeCqgvQGjH2B1RzL1nEzresQGeORaJd0Z41aTEsmjJwSAgZSN+masSzZwXUU8kJgpNgl1yiZpN5spi+LUHbUHCRtIhWfzZAVozLZZXnhl/Y9ev+iCxLTZLbo2YBAkOb+EupKo42MIQzInGfLguo9KX7PGMhXyXTXjnEqgJJQh9s5DBpJtuYdtPUmvDR3ou5Mr8IKkN5opXUKCZfcFwoXWhO26Ll6P0VRi/DMQBzqLnd66DqmdswEAMT+ylMafj//NMaPm/LYfGqEG6r67VoZ0EPBRmIQsNA6YqMy7xmToXbwYf0G01dN214UW0s+g3kXkPDTb1XuCFEri9sitm50sCuPGiwLMwE2Rc4bnzMO166ZXkWluuLy6wlfzhNuP73F7ewe5G6Ckwudkefd3KWWgWzHTj5mug6jKmzdv8P7dO3z/3V/x2aef4eLichCCQ0npWj9EqhMsMfV3GOhZSMBfBNopSC7WTUoZRcGS+sI4nts2WMp4/eZTEt06w8Lunx8wTxMmjchiPUZhFA677o6np0ecDhP+H/+3/ysuJGtOUUjqsq1VYV8ibMecu/WK7//6A3766R1q63j99i0vgpKQekFtG6DLZBxgKsRMF9L1zQ3WZcXyfMb7H3/AdDxgnmd4XXFzc6UCsg3b9SI3V4eLtBsSee2zRGlkF4zvel4Irx0XttdJcg8zsuoN6IGgSLXhhp4Srq6v0HvD+9uPuKoNx+MRF8cLAU5JZN4kMvaG4CsB9D6prRIibxVrqzhMBceU1RHrc+WMum3oZkLdM63bjW7GyYBcDpgmGiyyCZJZnEjytW5AcuSJHIVIgG4t/IQcFxcXWJcFy7KgO/kCcDZV0UTFxd77Pr5JKpBbo2lZ8LNad6zbhrlMsFRQso2zBIECgyNjxlOI/xFbUxcki039Qw9yPP9nb5JHW4YpgMbie3X+967GhsWAzsvMLp4mYfL8AFEdVH5nh8MReT7g9vYWcAZ9okURrXOzq7k1YOtd9uyBfHac1wUnO3KPWoYpw6Y2jkBabzRimyeUPKFZQ902eKMXE3SO0rBsH0MKpBJ6Syt5NP13oaqwhNbW0SSGUAPmg+hLBXvD8G7SPTNNEW8BVOPnZvFRdKayAHVn8+r6nRaKLHB8b+A9dcgZ1Rq2GFH/jdcvuiDp6uIjERTghRSvyKhBjA/AjsIKc2g2xCLrACIUiR1GKkUkwxjtZBgUpd4tzP9ULHAp9hiv2H6hQl9MogGKNlmWyAxACqUDC6mcxeGAqTngBshmcJlfRZc0Oi7woORlzM0dh3WKEsEMaPInsQ7kAkvMqnEn1Nt7H66q7i5irSNkwF2wHjMKMDqmscDNkKxwzFX2OaRL9dSd4U3J47shFDy6JV0azFvhIZacwVf88VnoVHTpQRoMBGqXKKcE8mjUCrBb4b8NiWjXnPhiKri6vMSnnzzjr3/9K9bzio1tK3IqGtlwwwExEtDaEiQaqZs5JXzx+ed49/0P+PGHH/Dtt7+iaZmJ9xI+I72z6NG6DX+ZeO4AYM33AshMnRK5MDkXGMQBcnpKhJ9Okp+EJUcGUbTaFHLYOw7ztH93Hrwlolq1NvTu+PbXv8bV1Q1c0u/oonpXRhJ4QXdnXsayLHh8fMRP737CD9+/w1RmXFxeEcVJCXQxzqitwL3iZ9k1erLedv+FwzyhwHAG8HRe0FvF9fWVVGcaQerr7TUOABrm5cymgnwawL0BYPcKdZrQM3VlHgWHC+jobUMvHMlutep7zQOJSFHQW4KlCXd3d3i4v8NXn39BoiFCxcPuuYgUDyMvBO7DWyU8fObJsG5nKvh0GRczoGhc2lzwuxKIc8ZUJkwKU2ydl1NyBSFqrffG4rFMhSiQCe4HR8t9qyil4nRxMRw7CUE2jjp78HEqWnf6wpih6Hw0GLARPZsVLNi0l7fWkZVDZMmQOlHcOMOSMVSvOtGBOFNyKeSR9DZ8Z3g+xAW6oxQ8Q7mmYjm1Ru+bZBoDt0paaXBdnJyQ5g7fVLRkSWfdMaeOq6tLPD8/Y135/ZfCYjAUlcklTW59FIJ0tZWUvwPbdkZKR+RsaC1QfBluCuDbNrrR5okjlL5u5IK5Rnzi1TVvEl90ZKi5TGzqmnh1wQMM2wrXGssGmvxVXlq1VbjOrZIziwhxG4m4i3S7VYyspJATK5i19aZYEjZGPs4v2mYk7QG4YyqUvv89r190QULugTrxwDiMcy9DQEhcwAF9EioFYMAMHqi1Nc47hR5Y5uEfnS+9GCpDUDyuJQyGtMknITwXXOFFuYQXxw6XkX8QPBUhOPwXo4CJaOxs6kDV9SVA/IG9++udnUzONDEjuSmSKhMMxEqD+AcwndZMo4r2ggSsV5xnkWYc0Gq4C7Ax4OyxbrSgdpG7XhZY0YGlzCc2fley8e/4u4GYLsGSHHRZmXOKpkJCRU5rVc9E5mgdoxgZh5ZlOczyh3d1RU3wIj+u0B/5uxxPF/jNP/wnvH//Hrd3d5KCL3Bn0GK2rA4oCl0Wg1MpKC75ud7rZ59/jh++/wF/+tMf8fmXX6HMM2fIA+HY0bNeG2fdbGk0blMeuMeCC3QL49m5Nyor+k7uSzn/LHE5yfWxZB6g27ryd5fCtakI+2Ikw318+oBf/eobfPXNN9iqlB8pCrAOT47cY0yW8PBwjw8fPuDjxw8oU8FyPiNnw6vX1zidLvfsDx1sTM49oHflJElVxvVRBwGxORNlS7nA5c3lKG5HjoiRKxGoWazfkAh3RLH8YlGroCDc3dA0R7dkaB5UdBNvJzYtVTxb3VRE6DvrRDlIDuQZ8uO773Hzinydw3RgUeIiYFof6jWOErgfSzK4vDbWZaWKSUWUR9Ek4m9tbaCNbJmDS6FizIyKB0toa8yoHdu6DmVgcG56J9JolvC8bMgTjRWtN3LCwl1WTUivHMMVXZBBQA9jrd6akB0+x1DKFGCMYtmEsABkp88iMCPtrrRxwEYzFogmWbQstC14Fj4aDkpbA0XUWtCFGJUrx+ugcZ5leALWSgSRRUbDdGCQ6rKsOMwHxm1sG5IrINJDP8T/78YRF59ZJ3E8k4/X2oZtszGmTMVgPcOjeajMj5qczuFlKgjVZQbHYW6Ongy9GRFTbhU6e4/CkKqX2okaMUcIVEo1B1KXS7lG1+6wJJpBZHipGW/bOkbtZT7oudFCvjWOj1jIp7GeeU777jDrHV7buPMA20n8f+P1iy5ISJACHCRgZlNWQykkN2njt84oasoD+wh6i0VqXQdDd8AblQGdpjZu/OfeFN7mQTADOz+NITi+yPCU4a4KUt0FSSxxbEAkPXEgQi0zSEsD7iG6kYKIpZlsMQRBDD344l321Xwu7voJ3Qf/IEhR3MMcEXUlz5JSIUMiVeFMUvEXh5hcZGN/Q/yJlEG/fVpBl0Bz+m6I1vXG0uB2JEHp/F8OfgdZB7NB549TIeEmiNYN6KbLiH8vpyxkSgZBHsFQkVFBhIdIwg67QrBx16jBFI/eYbi6ucGrN2/gThLk4/0jxbL5VQAATZxJREFUnp8ecDgccTicyFRPQMrkX6RwyTSux94b3DLefvYJbm9v8f1Pf8Wb129xeXGFcM/sUh3wy2njmXoC57X6eZHKmlQEcl5bh2wZtkukezdwxMRAuBSqJeczGMZe3rFudXQ7GYDXjg8/vsf19TX+0z/+gw64ziLM+J5M3JsyTVhrw+/+/Y/40x//iGVd8Mknr3EQEjQfymgWzBxVUffxPl3FTNhbQ2s1UlUT8Wl6iiCKBn4OjhqkTNE/C+8bbund7yZFgqo7vKrA05+MVkPsEyGOptEVL7CuPWFkX7PTbuwMHY6n52fcXF/jeDyi1Q3Ldsbjwz2uLi/xtG6w5jhOM7NWPEZabYy9ZiF11Td4NzRrygchebNFsGYSzil5c85RGDvWuim4TH8WNgzvYtTSvAOVI4LYlyzeffDrtq1LqsxGxKsp7wp8ZpIpk9M0Vi4LyGSoKVFCbInJ2DqzAt2ITKqmEEzT2If+RDwFsrEwMcMw30KccPGenYq5Ma+FI7khZSLcyL6fj0KzmsjcbFK5lki2zYB19E7kdusduTdcpAOfjSWUMqM1DC8TRTLzrVn8rjZQidY7umdMWcRS8Y9cB3M2I/ev7gIC745lbcinC1jJVCt2R9LnGJe+J3reqEhkUjfVU0nvJ+cEz4a6bboLOgaf9EUTiL6LEEJlSudYMganAtTsLPQsYSoJvbPpa20vrJFAe43mO+LrWUigGnsX/eDveP2iC5KSCxIyGfisCGAwBhUlZkM0d6BWmDk6R8Lspr1jWxcaRJm8SYwH0rpsAAyn45EdVweluQjpHQ/OnIBUijaZyEPJ4B6QIjsR6Hdqb9P8SodoEjKyIxTS68dmNhJWU45Km9yCXhvcKgAWIuSNROeUEHNTWip3GVz10Z0DqvOjC9fBDuwGN/GKPJaUNGeH4Hr5aHQQraKhmjr5VMiJkDurQWOhpnRTszFuGIZWeu2KAABOI6g4FN07FTDZdoWEM7isReYJdtIrwOddCscKDiAYwsGZSbkIteHlXHIa38enn36Ot28d79+9ww/f/YinpycanB2OmtbsiJepuyOpNgFpIofi3U/4+OEdTvOMMh8FYfNZQQVii8JLxV8J35Dh8tt3NA0YRONVJmXH05UmWTwESilAUfR6a/Bkw0cF4Gz6vCyMHMgFH95/wFoX/Jdf/xcWggDnwimL31JJQG60B//w8RY//PgjThcXmA8HBux9OON0POB4eRQiIwkq2sgUQUpjJEH1QyYxs7P7dY0NXQojM/vZqJDzMoeD5HGOBDE4OeQhSHnxoltukLzZwzV458N0EYtdRV+CD5dc+oKwCG4J8F6RrGFrlIx/+PAer65v0FvDuiy4mE84Py344bvv8ObVW6zPC46XJ8yHWSPQjkFlQnT6kmS6gi49UKB9P+Rkw5MkSO0cA3EMVYqycByodcO6crwQI1hGY3CsU5Jh29iJJzeeoa1j2xgot20Vj5XeTLHXeSb44JTADWhsdDhCNPS+YNlW3MwHEqGHQ6z2JDSK1lnJ7fMC9ZN1Qko28qj4pfK75NmK0bSQ3Os70X/0SyqC1LSYJaJZ44z18VxTFkIFRzXHUisenp8xyZCyd0MYjXmVcm7KgIJU3TsNC13k9xeeJlpV6DVGHwASoyJSMlRnoeS9wROfdzK6G8MdORt8rWjuGqmD54qQvJwTlVki4xYJK3IqsKkgIArySPh/dasYTErX6CwbAwl9QyqTimGqERtY8IYJYNdnaOsq/iGAxLW0LiuO85FovLy3wjrx5dn1P3r9oguSLtluUkdj3tHaCo599UBbJwnBDK3vF23OGS0XSqTE3i4lY9sWVswqFGIuV0rBsE6WDMwBdTMYiIU3qKOhW+Dz+RmGhMvTBQ/AZCICvlCeyDo+Mj3CICy9lOpKpZMLu19KuBJg6hgy9q5OJFci/SLNgryDkWUiUlvKWR4KLEqiWHFvo4NKpbzINHDUbUWvVQ6Vjq6ZfUJGj+8Co4EhzCqQ0wGlW7IoEP0JtW/yAAmonehF7zKvkk8BMmATkzl7SSTZVpHl4vDTYWAa2QEyhBNkH6RhF3ICPS/AdPgLVWoVljNKNnz19be4un6Fu4+3eLi/x/PjA+o2oWRmigxWu76nNuDjhDdv3+Ljhw/481//jNev3uL1q9fykbEx9mEQV7jUCrPmHaCLMkaSpq6HxdhyPqN3x1wOyBNTrWGxlljcphKqDI7z3Pf3WVvD490jzBL+63/9rzgeDkSQGmfWyEV+EIbegNYTPnz4iPfvP+Dq+gbndUEuGbMCHY/zTHt8S0AilyXlLMK58jaKjUAx951jMAp4qFhEELB3lRelwpK/ty5OgiIVVEg35zFoLw5Btz4gZNcaizXJgMkYx2r96xA1z0SpEkc3uRgsF2RkuF/i8f4e9/d3eP/uHZ4eHvHw6Sfcn1uFdcP3332Hz7/6Al9++SVOFycRQXl2VI1VO7IuoARPhN1bDXRqV68kowQTrasZMKRpEpKVME0zi4AaKEjXucCzsldecofDjJToRsxGtqP1ir421BqoU9eRxk44pczYiM53n5JzHIidw3VxPOJ2ucXy+IiL0wXmQrJ2pMa6SMEcmRHpK1MesmoXitY81oMQr0wxQPDF2NBpb6gEaU6rAq59SqvDsZsIdx/cnhjrpSS0AuRF9caL+NmrSiehUtZgScVH7+iNxmVmNCebsg2PKJJL+VlgCVlj5nVZeebqXO6da8uMaKu3jvX8jJwK5vmgMQwwi1fXaifJlJcBkR3gZ+GFRYiYt4aUJ/VdXXcfC7M0T0JwuQ/WmATo/vCB5AHTPIvg7VifN7hOoRgTndeFTVTnnbj1DVtrOEwzBnEeGMYLf8/rF12QzEVR0bFRpPVfa0WSwVFov01OktBmT4kPt7mPTmBbNv53oXkdDT3OwmT7fNJ4kfJScER6JPMVAHSRNR24Ol6wSrTw5lASsVAAoiZRsWJs/lyKXBY1K43vUx34GuOHeG8O+kHwv+hHmngv/PlF8deBX6Y4CCzUNEYoz2OclDDNs2zZdbkbxgGdU5ICA0COrAe+Tc65M4C+XziCe9Hp6Boz46jjgytiKSRyDrM2Lk8WZOwCqmadxUCZZ6ap0e5qGGm5PKB640GWsRuwxW92FWa7gVu8I+HZlmAl482bN7i5vkZdN7Te8fT0hO+//x6Pt0/kDRzJqo9ursdTSwWv334CwPHxw3ucDgdcXl6jOV0YA+VJ4LPxWKuV72V89TEbt+gk6RoLSAGSHEBDr20UvSUXPov4YtSRenfMGuGk1nGcZ1zfvAIJpxoR5YJUxCWC4fbuHn/57gfcPzxg2yo8OY6nEz7/7DOOdaS2gBk/V21oYi/ladJ4SM/cXYqOiq6LF+DYT39gjDt5gDcewKaOL9Zx38cIse54kewy246uopM/ethYeyhn9krFUqAT4mw5+3oEJ8tE9CwJVzcTyjRheT7jk08+xc3NK8xzwVY31HXF2ja8/fQt3r59PbrZPlBc8jQSOOvfItzKhcaO7xoiWHU1I8xhMZl0baF62zhKqwps42inaG1xXN1N5HQ3TBpxdFn+xx6N+InY/0QmiXWZxto7h6nyT7qkqCnj6nSBtlW0ttHivDmeHh5R64bTxUnoZEOMf2K/TqXsa1N8F6KrgJvLbIs+LXEBD0zV2TjR+SCKUJ31HSpW0s/2t7vDdYb1lGC98u9qrLa1UA3Gb1HeTQcTzNM0wj+TSRAgRcrWOrx05tkEr2Yg5El7kYjGsMsHydmtL7Sdn44Ie3fyAld66YhGwP6qj8aS42YRn5Ppn3P00+wlfygJRBelQSO8ZMA8key+1Q3eO5blTPn7PMNTxrbRzfwoh+25TGhw8XD43lqn4VxOu3mnCdX8e16/6IIkpyIfhzT8IOJik6SeX4DLWt1MmRB1ZES8HA903yHiMdNGkDH1A0FToXGoxYXnABAps4A3JSlqseDFpTzev5nm+tAmM6SJHgQMwOo4b4vMakRUdY2WQtKWA5oToap3MrQ14suCJQ3ArIAociZCQpYQplOeqDqweG7GzjoZi63xO01MeAvXRcGi6rhMf8jAEVaMZ6JQSHnSOIcXo+tZclEbPBu5I4lprJNm0ib9PAQ1Ol52LfRzaYO8ByqPxEVgouWki+vFeCiY5TTm4GxW3XIyk8SHyE4kRM/HI3JJ+Prbr/Htr7/BH//jL/jLX/6K5+dH2p+b0exKGz7kuZ9+/gWAn/DdDz/gq68mlFJQmwouyBSpJEH2lEMnENpuWp/xIiStpNiuy9vDz4B/jnb3NPviOCmNQsYhmSAM5fIE9I4P7z7g5voSl5cnMPMkaS1m/PW7H/Cv/+2/43A84rPPPhUhDri+uUYuBff3DyqMGVDmkkdum9xanZ1oTjQWRGIn55AKy3xHBbWe4S7TXn5WomtCMlxrCuEj4sNllvEB2q4Qr0ILjGs+pI9RxACW8yD6tW2FSUocY9Ax+unkWM2Z6qvT5aUSdoG2Mll7Oh6AXnF5OOLN6zeY5okjL+9wdZfmPrggBP6I3FGA5MM3h3kgpvPJkeSxEa7JXehZ947ndeHopXfGLdgupweC98BGzEpC7iySskXHb9hcDq/TDO+Gra4vPHxUiJhGi24w0JAuI2D9iQ1HFFjIuL29g7cNh5xRpoISfK4euKI4dS8/p9BZc8qk+XWSLMpGho0bCe4qNF5wxgA2bnPO2CBXUy4OEqpBhJT1QNcFnceZtG4rm0xzfjeJPLYolAa11fgMAIaWdjXH6ERbOKrckW7vVU2nvG98D0mNO2ZZFhbwGrt460hloiu5qVGwpBwxYHfGzogQwrBLICq57Q0eChUwTgVZzgk5UYzRasNUmF/TINVjb6h1QTkwZ8uk0hmjZSGhLYQUQsxa55rMZiiJ04W/5/WLLkjYTmVdIqEyeMmPwIDOePG6Lmgyw0MVA+hihAPWYa75q9MYB7ARUpWzAbajAZyVCcx6wWJ3C5IoBgHR1GnDgGmaNXft7EhjM9aGdVlxPp8JPasbyC8q3JwzJvEw9owamaG5I4HVa9alYS+g7igKHFLotKrrVge0Dsl4td6HAVpOCaVkHI9H2iUrrCnJIvm8LHh+fJKqQtCS87mclye483OnNAFg15OkaOo6ZJPT1K51J0ycQvK3X7JQCUpOGT1rLXVAJlEuOD5pQwZkmBDoQrgXdo2PMmqlpXsUOEF6Rpr0/YhcmDPmacZhnnA8nHB1eYPj4QLf/uob/PjDj/jpp/f4+PEjEz0vLpTrsLHbKQWffvE5fvjuO/zHH3+Py8srfPbZ54RnnflELWDpiCKIObjejvp1EqVFkLUCwBzn5ydk8WUMEJE7LvbwjQnO0q7ECcLz+9uPuP34E7768gu8ffMaORW8f/8R796/x1/+8le8ef0KX33zLcpUsG4V3UPd5Li5foPWKrZtQ1eeDmTZb+A6b1pzTmiCo5xQzYhcO8wBQwIOjEObBPXwZngRP2CmTCV2eoT7dXH4/uwCCCGglgeXwVuH5QLLnJGnPA1/lVTksquR38haqhrpJI5KtlaR5hnFG9q24uJ0xOvXrzFP87hAS4zkGp1YLRBB7T3XecLNGeyPaA72yxpmA+k0F/zeDeflzDFKjPrQkQWpA46cp6HumC5OSBcTal0Rl3ggIr0Rlj8cRAgV2usA3DKyBzHZR3NkaUdV8jyjrRvWtSGljqvrK3hvaOIiZZO6qsvcDVGkUsmWVay2zuLWCtdKmbISgfn3enOYFaGK5MBYAqa072/LhedTdRLiVbgTIVFuElxohO9rwju68sVqb8iJCCrRCsBqhXWa2c1pJjkYHdYarJDs3h0aI9pY92FPYMYE5ZQyubJm2NrGCqxV1GXBnBJSB2rj4g3HbEudBUcyeKb4IfZZ6w5rQCpE4VICSp8RuWOOTec/U5nREyBzTI7jWWpN0zx4Su5Gs8xJhP0eAy02RjknWJNLujtEEoPDsDqLvlL+J5D9doRqoqnDFPfAXbbhDpjDCg851CooM9FoyR2tkQ8yTbz84I4tsXM1ozpmWTfxKdKwJo/xAlljVPHEyCANKIzwp/fGDZXSyFIJ3gpljB3Vd++QHgF4QlQsChBEToypm8Rw7Mugnj8lIKcZF8cTSi5YtzP16yMoMMY6LngWvHA1cok5rntCzgZLhOI7WJBkHaqtbyg5Zsh8FiUnHC9OLHRqxZQoQ9zqimSF8+0e0epJKh9dtC9QKu8VKVNOO4yRjC6iPIRUPhnddEsx1LYhF0OqASkL8taoTTcBHI66iZypjbNtJH3G8+Fz5+8omkvvl3xGyTOSkbjaN0dGwbEc8e23v8Lnn3+J3/37v+On73/Aw8cPKKWgzDPKNBOuTwlvP/sMlhJ+/P4HXF5e4nhxzbFe2wvGKEbs5XeG6BIh9QBn1uGRUSIobOyPHf4uVug+61L32K5oQvzOnNCa4a8//ojH5yecjhf4/R/+gK1uuLi4wNXNNbZ1GURalX/0k8hpHOZmmblAXKmYyoQOWpDH2HPgVDlzvq/vyJTF4TkND6CoKNpWxzrjvuFerP4Cioes9w1CTzBg8SCEImIRQOSvixBunUgauVvaFyIqDqTBMcZFsVf2Ct5xPB7Qp4TX19e4OJy4z6U2MIXnRe4IhLYgv+A+aM7Hgr+PBickzMGTMu2hKBaC0waho+575pA5kJzEWAPzR87PZ7x58xqP2dRwOIBJxbzDxe+Y5xlP57Ok+3xVd0QbhiiYPZRLQl9VDHfvmOaC7hlpCt5SRfauomRHc1p3KHiMwj0YbGKQZrxSWAJo1PDyTCNPpsMmx2GmHf+2UUk1TabLlfsoqSmxXFg8AzBPaNbp0wQbwZ3k300cmYjPZE6O4OpAkcMz0TfdB+IFwTASiqli6Wit0uFU311zYXhpR+NbXbE+swiJtdAa92mrTUaVHVakyuKDAFTYprgcjMXAtrKR8fCn8eDT8E4hSqMiyTJSLpimjNw7HWsVmJmEotPugYTVGMvQq4WS4z4AEb7f1v8nQEgCOqS5i8PCzVKQZxC/XDPGXJRS6I5tXWCa/QEQJBdELiClAjgNaRh0JI23DgSSLnc4tAkpce/c+CYOSieU1ho152tdB2TH9wf9bxs5KRGul2Ai0e+QaxyMXVwUyOa3CPkxkbZaZeLrui1CjVw8FxZTKebGZuhe0bsNuWQcsl1jopDt9rphBTt+ByW+0zwLMpXyp1U6QsZObI7iLKhQlB2iWm6oS4K/os2RDHI+ZKdWkjrs3ARJYlwMcUw6aJk8PFvshVIoUJbW0BsdEVsjAmMwtI2XQimE4TN0wFg4OZKYlcUcN2fs9qQZPZEcku/yMeMf/+E/4bNPPsUf/+MP+OmnH3F/+x6pzLh+/QbHixOmUvDJJ2/Qa8V33/0Vn34GXF5fafQQM2VekEhJBaLGLi7CXmsae9kY03AEIFmiimuL70lEs1rrcOmMgpigxF4QrLXi+3fv0dbv0d1xdXWNZAnbsmFbNo4JzdD08GMMlDJJl5RACpFIrnEMC/4WwJk5CwYobbcT5k1Ch1z24x28bDflmJSkNc7dxbl2mugKCiIshl1ajPHZIGTIuMGd/JRkHNc0SR9NB3UWcdIQhXAb8/esnCMSUrmfzk9P8N7w9s1rHI/XmAs74alM7JRVjAbnBcCY3wdaycvEGD6ZDOjBiEhwk6us0ViwQzL3gSjtaiR+H0ISM+f6fWtED6YZ3Vcs24an5ydx66qaDkYJcCTL5zwfZjwtZ6EEQnz5G8fZGmhbcMLM4wwRGTZlJCeCFeoXntsFMJrW8VIjZ8KSlIS90RMKe8MyvscUBxX20ZURKeidPEEYVSWQgWCWurKK25RyjFLChiChWEbdnMGQcc4kw1QmeOvYouj2LLKp49k3KVCc8njYUO1xI4gbk8BRTm9Y6sJRnwo6tQ/y5eHotTvgviLngixEnY1UIoLmgLtclFNYLaghs0i5NqmZAq0hqtmCK6hGomnsbXpG3ugt5cDgn7TapCDcuShNDraGriIQWJaqsdh4gGPc/7dev+iCJKcw1GFFSx6JyIx970QmByDXThoRKS9BvAuCJ23fLHIr7KCyIKe8y5icUFcTIa3ZXvlFcQTvwyvChWoAPKBL5iKNnJKU9ojmMh14ADbBqN7YMSXTTJUwXJ6UItpp40tahGuBEEWABZdGAXFGoijZTxEYyFEV5500YrIsiNrJaam9ISlEr20VbdvgATnmhL5srLrVtcQM1cywNnUeJiKpJMI5xWlCK+PW1e2nGCvxAqqt4en5GYc86TAk38KECIwxju8SQwsmv6r5kcehDpnjD0O28KYJ6BkwKVF8mmHuOB5PyDmQBT6nXDKmknB5eUIpCcvKy3eaJuRsWLcV82HG2/ktTqcZ//Ivv8Xtx/f4t9/9Hh9v3+P+LuPq8gqn4xHXN9foBny4+4DpSBQl5OF9qySjvXCY5LPcoVJVKnh8eMDhMONwOmm8lBFKA64jjfRe/AwXsdClJ4jwq5zZFfs0oc0Ny7Ji7R2HmGdrIYeyLWzxLTUUKbPcHHlKGoWJ1mpEZWIEBxXGOXEeTwm2i0geKjQiC3Xr2FpFKbNi5TtVEfp7yThKNZAzxVA4jjLiYjB13K4OldNMQxj59QaNEBzedJmAz3JrTSZ7XWGJyl0xFom9NaznM7744jN8+dWX2FYqKiCuTi47YbqpGt9aY06IUrlhVAS6Gaw6ZdvqeMNIMIVEuu0jFIvnr+I8zAyLIgKShzNpY6GdgTJl1A5svYo7k8YFlYWUNgtUiKZd5/MZJP6QeBxKtJ1ozbXVGgMkt42qsQncryxK6uBBZSNyE0qiulXkWaqixvcbxMtxvoUCSuiWSTllJkCrJNg0KYuHFvs8azdUr5g0donLm81EIeFYWV8pJxQ/wCyjbvVn6yzPGlV2FQD6Pqsv6NYVFZDRaoX1hFblvZOYcG4acwOGunYs2zKMDC2JnBzydncU8XaWbQVawzxNRCIAdJj8RYR86Swz8Rhrr/AOTFORFTwNPw3RVDeOro3y46jGkxFxRQpjMzbiORVa2yMcwPngN0iErIZiKhPmOcO7acrAu/lFPfk/fP2iC5LWKrzm0WVAyASAQbgcTyJgvbarOqp3SkYhUytt3jh0AyYl544HRxDI+Dt4ucWL2QwYhWFU9elFDgkhGIwFRI+QgraBs2wLAhAXTYxujO5VrDTPNmZ+gA5d350gx0GuTti6AV6xbrQKzoM4SKY8hCi4YaA70KWWlenD2Ssve17sNnyBVB3xd+m9x+akQc9+6FoiNFtSGv5FSSqZCIXjZ474+E69fuH3nFwkz4DhQYlaEDlLjDeSo/YuGFiHZmjd9B13zWVzTi+cUuWDAODidCGlQsO2rKhtRc4J08SC7Lw8o/WO4yVtt+HAMR/gPnNkJZXUm7ev8ennX+D7H37Ef/zpT3h+esb7D4/oMBxOR0yHA959fI/Li0tcXFxSEp1NBxov6V2mitH1xjjieXnG+fyEKwdOpxNsikvChhKqy/UxxkF9JKcCm0yUgnhMlJCHPef2FWtbkVNGzjNHcir+KGNlhxewbFj0NzRYoRtwr3VcyrFrWq8kkKrIpIkf02lLSthqw7I8ozkwzzMMVKOQqMzPUSYal3kgekLOghSurc6uFSJCgoVzho81UQzoWWOGTlIgPDhZNE7ksRB8C/7ZupL8+O03X+Hzzz4jh2ea0bNGtwofLJmmZARtXCqIwkIEEFrju6oPLDbIh9mzSoggcO+l6NZhw6G1G+Xa27YSTdI1TsMsNTkZGm+biMtloCTLtrIL1tQKZpjniVwOM8mf+65SC6TSdCFaQi7k+mzrAusT0VEIARZ64XAVhlQbdccYmeWSYG0PyEwuXtgYXflQ5/C8N2TLY8TtTjl77aE0U/ZRbYN7BY1WiLjuyrDW2FRanpCR0EXK3mpFPh6AzMI1Pi/NMzNJs+aYMkfsvXd04wjEEidRlNAaugGe+Rla7eiFvBkTYowQFBg5dhmUSNfN9/MRAl80DTDNhco08frpvDtchVagT2nwZFgwEe0WYu8NSY2bCXFL4tk4KpIxq2oQvBs5SkxldizbxnFoTsCUMeXEO1rN7d/z+kUXJLVuqMN3gV4b0QEHfOvq2MKVdGv7jo9uJQ7urpl8FCKAI2LJeSGr2oWkna0HLoPhhwKHN37hL6FfXv8d0Gy3A0BXAJcqY3apktfpnzkcvXbkRDdBV0dGyJ2fKWtOzOq7j4Nfu25fuOFrkoPsKoY1H9YgypqlHcJWF0nXSqBtXa6pQG/BGJc23TDImLlkeOrjd0eKJBxCjlwcIBZMKSXC9eZjROExesBu6taBwTkga/znLxJWXxAlRZods3iwcveo2nVodxVBkRZ8mI/ykuF8naZqDfPMBN9QEVxeXGGaZjy1J3Q4Sp50IU6YxN2Zp4KOhM+Q8NkXX2A5L/jTn/6If/vd73F/d4fDxQXmMuHh/h69dbx6/UqoCEmANgo6EV7ZMsLhyCXh5tUNHm7v8PR4D/SG19evEaOKjvDMEUFU62ZrK2jmpO5dh/26buQ9gMVGzpTrtk6pNgtYhjKagx4RMSZse+R9FMwvVR60spfCxQxImaMEp1yzti5lWkaV8VivHcfjQaMGw9Y0cgJlhaNTRyABuiQLBhFcHUYsEI5cuo/3FbwE5pNop+p3NNRA3QcRtqOjb0Smeq/4za9/jbevX/PHdxb9TRde3xzrwqA5gKMQNI5HkWJE6lIisAmJUemkhspfFNXwQMc4IuyN5wSa1GlSprRWAe8oZab9vyLlWcfviFWZDuhb54gDHLflJK5UIjo4lQP86Hh+fkY4rkbxHkgkyxeOES+OJ3zy6jXu7+/w+PiM3jeOEFp8F/G5TcZmJgUixzQdOzkygc0YnYpdCGDIw3Wm8L8KreMotiCaPZ6P20YH3kDPtRvQVOCWMqGZY6sV3XZVYKJBlJpSfrcJFDmEfX0PFLw1ODLyxGu19s7GQm6tRFEL5iNt4h8fHuW26rJsYHHUnHh/H3tdqCY6mocMmCilgfy/QBQH38zIUTH9+TxlQOougD4yNJSL4qJhXRfYNMlHiOus9Xh/VN156ypkY4/HmIgIlum+mUSPyFbYRKf/40n9f/76RRckACHP0MfDxR/RNRUJnQCEHkSYVXhg7AdWS5zFJTMm9QpCHkY6Hg6cPuazhoScVAAlMf1bIwk1iRUHFQQc/PLi04VZm/IFRCLiIqhkg+c9OXOUWO6CbLsOx66OwLRRCZXxPVJtUYzIApM+qZkv00GHCjiLTYy6r95RLNQLVNcA3IiWKOvtPUYCXS63xtM/HLcDbenGA6/MWNcNW+9iMTqSuk/+L/4e0xgoIGoSgjHg6G3beAEVyXDjYIZIqPruTCGIo4gy8U9a48xWsr2Ud1VDcAIigdY7UYN7fyB5tFU0bzhME8xokd2b4XA4oteO5/o8ZIxbr+Kh8Duby4xsCZcXV8gp4/3tR3Q43n76KU6nC/zlL3/B9z/+AKCguePjsuHq8hqpiOOTgxynq9KEDvHxorvjcJwxTW+wnhc83N8idfI+AKPpEvjdDFfc3gF1lDlljspaSNlVqFnk4pBjAAt/BgbwlVJQyjy8EcjFSGio4xeax0hFniw6DE37sjeqWLgvXT+T+2BbVuamzDMdmXUwJ+caU9W6IwRaJwjioIUf4kuY34dcdS/sNK6Jgh3KR4LL+dpVeHHsYImE7duPH1C3Fb/+9bd4dXXNg9noh5JzERm8672ReA+TV0SmAqxJRmojMI/P0TfmLtFpOTYgYOAhHy6yPZARFQm0ByD/LU26ZNqGw+GgcY/iCEDRyWQTDnlGnve93nolKrk15OIk3nrDPM9MAxbS623DPM9suCzQY77Vviy4fPMKJV0hOfC8rIjGafgd8WRhESbAor1Yg9HFBUk5/sZeYO6v8IMK4v8+lmUBsm3baDgwfo5QMzlJe6c81TLGfjfxlbqSwnfbAxV+ultylZJrq0REfJeqV+2XlDg6KRoRljKhH48kiPfOLwSUf3cTut6lptHYKtAhBNBr4Niza1Stc5CoUJi1sQDrzYU0CZVOCShJBFQWN4fDgeeW7jzAd5QxGaxzP8W9BMso84R1WceoqW0NpSR69YBFppX0M2Ly/+j1iy5IUg4OCefhgA6ZpNGL5uLBMSGTu42LLCRcuQhKbBXVgVQSpommL/z2eUyF4CMO624sgErmNrAEeOIjpcJB452NdvRba4SityaDr4SkWTE3Df09ciJ86YDSNg3J8+g2U+KXnaeJBUlI0TQSgYqz3itWi2hwEpm21tDPy7DvBqDRDy+9EpeyLi4u8YKUqZ4wITgmohaTfwl/c+03GtPlBOsZrW4KDKPkWggrUk44KHeoCb1ikBsP2VYb7u7v0bcGoI1RS/iwIDMROL6PIA22pO8MkhL3NrwsMgJ5wch1AVwqlSRrfkllRbrsThh0snmQawEAmTHtQWrtvQ/PjWnKaMYuo/eOis6EYQPcG7zzO7m8usRv//M/49NPP8W7dz/h490d3n+8w5/++Ae8ffsJ3rx+pYKzKTfHRWZ0WCqIzBJAlxDI9fHesdUNWV05s5O61Ft4MZsX6bN1tLWi5Ak5gn31PC0loGWZiwHTcUISv2drlZ4SXQMRExdTxb8qD5glJHV0YYseoyFLZXA3khJ3w/Qq5TJkq33l6C8u/ForWu1DQUeqlaFJZeTxnesmM9vDwIDgQIhs6CKVGuf7prMCAetrnXWnw/C6rDidZnzzT/+Am+sbGJIKHR/PNtkE9I3QOsksksb6UF1AHioGjkuDx+P63bTlCqmo6a1EmCKLnXAytpQY8NiJOJnR9bW547yclUnCDpyptBmpd3ijF8XpdMLz8zM5VxtzuLa+X0zoDGhcex/EV6hAIrLqLNaSwxNJoVXoQzITSTIjCLChyRmeT2Z6Tvq+gv9kjtqwh7Ppe43vLXg1vXc0c0w5D5uC6OCbHFLD1G2cEEJRAw1wqRRbI5qXs4+4hd47Fvl+QIgykhx+VdgiZdTu6Ctl3aVMNN7soQqqRINKjq1BondnMZ8gVMeFHkVhk4gwZ30GjFUKFb/cAzwXNO55gfaPeJNxVrx8Fq7iWd9BzmP9pZyBjc/CW2NjkOJcc6GGBYdDwbZtWJeV3K3Os1T0ep5Rf5/I5pddkDjIk/BekVPCxcUFcs5Y1hXndVPMs4+Lh4otbuyAYHlZJyC7sioc80y1BbzDcibjGgbzOqDo2DI81JIuGoeF+zdU4LSGdl7xxz/+GbcPz3j79hU++/QzJKNtcU5Uh6TMeOjI5EjJGFtufVzELIwMBo5oXEhYsoQui+bhsKgOEiDSQ3IrF/xSlx1q1WGbJT3sltTM9bHRONLJggT7UHD4IB/y83aPvxP29RnlNOPglBFOJeMwT4TldZgFYbRuFZuzUOuVyaaBZHUnXGg57fkzFsVDsMWz/r2PjdcFxycY6qqH5QrxAlRMlv3i0SaGlE4+OuPwgSAXoMhErfXKjreT9NgblQjZwFwR2OhmWme43dX1Dfyy4/n+CQ6OQdbTCcevv8bXX3+J777/Dr/79//An37/EdN/+i1evXnFw6mL82EJ6GkgYjApK5yGc0VGeSyRNU5EolSw0rgoZSFN6rS96cBMHSXPXCc6uAcaA4xI93IoyMrCeXpacHm6YJJpToO31ZxjjwR/0eUR1G0C7HPi+GzrNNSL77yUgrZsKJkFe1KHmKY0JPU5Ee2LnBJAUnh1fnHJdAsULZG7ZQaEXDfWjdCSnx3iKY31byDsvq0rNgMuLy7wxduvcZyPSEhEscbFhJ0ErfGpG7CtG4mmGseO0UXf0S9TtT7kmDpluFexh7SpOInRzsimShkpq7CpRGSCL1Sdvj+e9u/JCtBRebGBPJmWxC1oFeYTUnaUiU3fNE9SFQmZDWTDO6bEPJvSuUd6c7StD04EnPskjAhbC0+oXW1k0FjcjGev1kyrIpJmmnMhaf+OvR4FTTQaEwmY4t1YdngPxRV0GXPPxyi3e4cLsUo5wSsL+GmekQCsvWNrfRScAPYGR5wadJ21cGx1RVWzMpUJy3rGEmq4iyOmw4wJDW4JtS8DATEH0POL90fUJKsC65GbJqmuk80LKwXWA9FoFF3Y7k5bonAJxWTn/gtbg6T7I9R2QEJ3WVRIGdR6k+oUgHHEvq2rvgP+Wf//tfftMXZV1f+f/Tjn3DsznZk+aKcVWioPEXkEqdSKxj9oRCS+YgwhmOAjGrBESIgRNYr/aElMTNSYGjWCicZGjSAqDwmPKgaK1FYomFKk2n75UgqUdp73nrP3Xr8/1tr73uHd5GuH4bc/pgHnHqbn7LvP2mt91lqf5blhBCo6wEhFza8F89ohAcApkgCUZYWB1gCgZQhV6AKItR0AlEIc7gRhCwCIf8JpFCM53ViwFfUGFHGtR1DyZSlIESnnFn0jDImKszhEUKzxCN6h2zR47tDzqJ3HQlqAVrtkQwadIjkowBY6jTPncWA8ZI0jRp8o5v6ojaTILOk7KJXuEUJfehGniQckF7ry8/MsH5WmFsfUESiKfCPlEpWkYjhA4BQJs0CAJ2Z4oOXZhRrXnqMWBY3GBTjfBfnABiPEnvWofEjp3oPQ6yTFxFH5syyYllVacusxiuSRNJAH5EOFmP0AiBkLoVFjpb13LNZkJW0Qh+IZK22oCDCWr+eaHo5klNHwjlA7z7nYIAZJS42AZr2awlrYooB3Dk3NY841se5JWRQifBeLSfkgXn38KoyOjGDf3n2YmjgEYzQGBxdw22fgrjDTl4YE+L8PEhX2BMPY8MZuJOccfBNQVWVqL4/0dyAStk2n/QsEkFep0LkseuqaXJSoELzG1OQ0hgeGIGeIGFad3gduv+fDmtN7vXcFSsE7Sk5S3a3x3MHn+L6dx4LBQRyzcBHKkvVVvOiOiAIGoshUIOpR47aQNIIwdk7eeSOt4CrS1pK+8hCtCQ4slDBxGlzEbeU7fP7559HMdLBk8SIsX7o0iVkR+mpVYnrQsZJlaWUEhCi5anGmyYvjE/e8ONDsp1ASkYopnTTzSpOwYnwYOBl5kSDRPEnaAFBolQWqwTYmJyf50JHCeRWHYQKStlNo6xYQgI7v8vBA7wHvAF1KOhNotSrUdS3yCuJw+8CCadaiKBQKbdC4wAoVSurJhG2FFAQHqNRiCsXdfP2ibyransCzcwx0KiaNn4lfBoiOB/kAeKAqSoRaJiMXBYwJqBtmaZldEZYhOp7oY7OJf6+XtQpNzU6xlto3uU6nrj/OxrXaPH+m0+nIHvA8q0fxvJtSxZSXR7fTxeBAG5UdxFRnBihJHCKpXxQnOrJ6YgGhRRfJeyeOHno2n4I4arFwnBLLHYMP1tfh59IEGOLUMqd/CKR0EuOMYw201iisgg6WhdsQRT7Z4SYp5id5d+KAVRKW1CiwiGBS7n1lzG+HRCJRajyca9DpdKBsARd4pyZDAOmXNwpKGTZnGoD0xQfiCbKmT/yHD0lJJRiLorBMuYlHToF4kbWJTif/TGbocHCqobVFURJOOvlktFptruCWNkQiaSePxhqRjhOfwDdQ4lmG4BOLwXRfr0aFKA4Y9GzgxBgDhKb2PedBWiC1QYoMuHPC9Gh66dNPXnBUqZR7DuCNHHxIxjt4z8YxRnbydytHgOqiK5Qt4svlXa+VUcV6EBWDRkRpZm2UaKaIUI8tUZSFCBx5KTgDKPAkWTZYHEVbbWCs5K1DQGj1WhWNMUnu24owl3NNMtDk+3PQAVVRikFgA8BRghQsCz3qG8c5aM1tuiQOKxE7Nc5z7YHv1qg7nUSPNk0t1K2WfWGw9JhjYI3Bf/bsxeT4IQAKRdVC1WoxfSy/l6RbQUk7rSIVSXBhlqIYktDdGqkYLYAjV+edsDeWayTEWJNj9qcoeEgXiIe6ucaJmFjAwWeew+joME8/FceH5aZJDiIeR+6ahg2upIG4A04lFqGUQ7vdbqEoLZqmRlFYtIoKLVsCkraAAzqu5n1riuj9oLAGjpgS50Fs4GhV6q8IzBpYccRgDShEcbUeAwTV0xiJLFtdB3RmOtAEvGlsGRaNjqIw3FWhDU9DDohdWkCrspiYnJCx8xplUcBax0XrRNCcyxUnxKRnMIbfKYiTqiPTKI59amNWBlYRSNig/jHzlF4gJEdJQWHBggUYHBjA4cPj8HWQQmmum2O1T0JhLMqSGZyuq5PWCIiFBG3Rc74qW6BpGkQOh1PfCgj83hVF2ZvRFFM2UAg+pm7Z5gTplOGWYKCRzhANQmGi/o44DtYg1ofE/a2lWzEGjgSg2+3AO49Wq5UGZ3brWpxpaeuTujBr+ByIYyyg+P0JwkQTkGprCi5IQkBA7ZilgLEANGzFNRIc3LV4300R6sYnrRhbWmaxvYMLDlNTU1iyaDG0NqhqcQBdwwPrpLuS16l3RBuxLUo5KMc2zxidHDhWxxb7G5kgq+IiytnBwRWTJXxORJE5bY2k9lmcMjQNyLBOkNIE12V15rKs2O6QRyF7mKTQmJeJ67LkphK7/Fowrx2SGI3BsEE6PDUl3hnT14SQ+s2Z1i9Ejx9SaW3SghGUVDdL90efcS1tyTMNYptjbFNTrEMRAlKuVCFGhVJsp/hgHBwqkmfJX56ouUIl+i3IXJOi5ELGOKNBASgLm9RUhTFMNF+vpSqKXaGXQtI9JijOkNAxilUaHg3SdGOvmV1FTB2x4xWLo6JcsZNuCiVV9Qgk0Q7X7sThdfGQYsNC4jBJDYNWok3CkaCCSoqNSmmuFdAakMFQ3AvPnT3M0EgaRQFEUvgp3x+TR6FXBU+BB8lJAR4RoSpbKIqSC7AU0J2ZRmemI9GfljZDg4FWhaosuIBPs3GDiq2LQm5aCwIfOI1nVULWmOAC3LKsAAB1PS7CYdzeGFUfy7KEtTKUrWkAbzDYHsCqlcfhySf345mn/geqaOG4Vat4rk/cz0pkpyNtTwokejrcwcEHpTUW2nLdhZOppJAMAwW5T0ktsHMuTlVTs+R8zS19zvnUPjg+fhijCxdgyeKF/PemqFG6PkKMQNl5UELzxwLwlGqT/HcIDQwRqsLKwExe3673KDSnM53zqbsHEOE0CtJpEZhNDDx8LlLPvFfEThABQcm8JiWX9Rfb8QHF4+YD4AkTBw8ByuPkt5yAgXZLomxJPQgjAeIUIzOQGkpbBAjDoCCCVGJXfKxMk/vQBiFQ0iVKLA3A/1RIYn4QJ8RqjeBqFugTphRk2IkgqdWRtpCm22BmqoPBgUEYaHh4dvi9Q92V9J1R8NqhNdBGWbXQHqgxNT0NkKQGdexyAxzxZGGuefHCOnFQFJ1NiC0MdZcdc7EfjeODtoR0Bka2g7idNUhemsAFwiTPTwCzDdomNjLOf9GKmTMnHX+kCB3XhUPA8OAw1wMqC9IVj7WgPhl4ImaKKbLS8kIr0RVSOp0Pqf7JE5QHHHkAJgWGURvJWA0rgUYjrGWsLyoKC9EsYFavaVCUBWzBQdNUp4OOq5m109xcEZyMMFAKPp0GKqVPFff88lkgWlUkWlPcksuMICBCnlrODM3PwjWY/KbwfBxOnVnTAjTrUyloGAMURUAjgzsB8OgTiENHfZpg6Uzle/fBCQHw6pjXDgkFSgVcAOc+G+JoL/SJ6ISamY3CsoQ25NDiqIjbu2opvETMS8Y8vAfqUMOlIWGBI3GNRM+yumIhnQSQg1yltj6krhLZ7YiD6noHM7MYzKhETZAoPc+HOKudpumMOsr49ow7ERdKhcBFkB6xwE1ElV6wfhxYRO+Z4MlBk1iAED8L3LIrLcuKlKRvwO2PbGZh5bmitDUF6RKQgrDY5hmL84yJwmwiTieFj/HGYsQal4znLEhhY1TmTQwRpbRKTLf5vqjHiqKqAv+9cZZEdNwb56CVRVFUCA7w5FHYEu12G0MjC9iY1g2C5N4dBaYoLTuTGgFkZUJxihtjbI7UDstKj47zvlIDEZ8nrlPjua5koD2A0dEReAo4eOh5WKvR6UyhKEYQRL8hPh8ghbics+H9CRmtrrUYRUjLeiz2ZTlorQxKWyAQoVM3TMtbrpOZnDiM8fFxdKem0am7UNpgcMEQWq0WFo6MYmBgAIhtiJHdi9F+iFLrwv7F+5X3Nr6Duq9QmGQWBh9yJjEYUarci7OkwEP2gg9pT8f6EZ530yTF1biJlOkdcOjbW6lNEsIyeO6ggA+YOHQYwXdxwolvxuDgADsHIaBuHArD9RSGRH9FXpvGN1xQr1VKJ5MUBHMnUnSWIFF9SM9ii0LsUo/J01IwSwCUdMvZgmvfgg+wWnGBswhyQQKC1DVFClOTMwiBu11miZ95J3aMrzcdLUX1XAQfAh9YSmyTUkoUp9npJgUR21JwCKDGsageSLRv+I93Xp6Hiycb3yB2CBA45aulgy5OD0/KrxQ7kXjPctGngbElYp1rFIcDCB7ssEx3Z/g9arVQFSWq0qLpGsx0G06lJ3Psk+21EvgQcdGwKS3gRE1XGE+uTZH0vNQo1g2ntKvSwBpmSqpWiW7jUMeJ157ZRq0MYCGKyD41JsAorivpVmg8z30yWqVGihgIA7Fmrl87iZ2OALbV1vJsIOcc4HWvxs8HIMSuRP7uuC6J//vGx8JXPk+5R1wjeA2lAgpbQmkP57g9GpoVhZW1wnZ5qetSkhoTRkupxPS/Gua1Q6JIwRBrJnAunqNEQFqZSKGpWdmw0AZGWyQLRj0DitBXoAkeKBXbDLk3PoiDICPDFUdaII56mOb2ye8I8kUo4iKtAKRIEGJwo9PBlLMM/9PxDROmRl5Go7XMTwEIDlwmIO1xNNv15FbkeEgrUOiLvKTKXxHTazwEj3jYlVLgIolYM8GPCBWLEaUvP87dCFFSXjabitLzhMi1RnXbOOvEaCMdNz2bDNKwhU1dSVr1zgzvXe9gQ+9Ru8GlGhiAO5OsjoxKZMQlV5o0XVg7IkjRnasbOCk05OrxAu12yd0sIaBVtVGVFR9wYlDZCdCwsPA89UqKhaPzBcQNposiFWAG+Q6ikY1Fcc4L1a3YoTDawmvHfrE1MEWFlauOh9IW/9rzHzz1v/8LjAGtgSHZJNHhZZ0QSB1RfzojDhDkBWTnRSnAiuPb8xKA6elpFKVFq9VC4zwOPneIpy5TQLdbo2pVaLrTWDA0gKoqIE2skveWNQfv9wDxlSg6HhIgSEdY/Gv5fq2wPkAcn86aICw/zUJlMs5cxWhWnk9o+CB6MrZvLkztGjHqCqSDvDJcIKzl3eylSkkOGIAc4LpdeF9j9fErMLpwCIE8onaFthbaspMex1PE/cEFjmx7PIkIVpCOChm0pkilegUWQeztcS8MgI6dcdHGGJXqGKLehIrFj3EfJLso0gSKj3znAyYmJlNqDkrJARKARuqslEK304Wx7GwwG9vTz+D0tzgaAIwt2H7E75+AummYJa05zeEaj7qp5XsG2wPLzo/onyYGhiigKio47cVBcz1HVYKJWHAavyulDNtNCCMo37s2Spobumi6M1i8cCEG2oMIg21Md2bQOJGNV+gVOGuAhP1T0jWnAkFZDQTuzoydJST/U5DUo+IiVqUsWlUbADsMRVHABXaSCMwe8PgJtgudpgtoQqtqRS4PxhYorGcmx2hhhZklVJrk+4yqriK6pnq2gMS4esjzmNTrwo8rOivamF4mgGlS3ocx/SUq2zp9v8xIWa3giNukY3eUVhIYK4iyNweePCZEAsd4nr4K5rVDwv3VcTEZRnLgcGyIyXum5qVDQ8cNQcQLKgvWKipR/2NKklslZU5OX+TOPfGyIRVQqiK9kPyC9Z22ig2uIs7/kRQKFbqnTghIPYrqzSGIv99KBxDTm0zztqsWF70phU635kmyYGn5GGkEpeEDtxij0L37l8+VAXQA5zR1YOMcAKuK5D3DkKxDFLLi2hcED9JWGCWkIlEtxl2BI2BtTWJlYtsfiCvGG+kKMUaDNM/XAZCcQKU4EnFBFB2pry8fMdLttVmS404rFAWgLUeYpJNDF4f4hcARWwOHoihQli0oxfLyKqhUTBjZFhccQNwiZ2xv7pE2zChERKPMBjugqioUIhTXNA20E9YmytiLUfOe0zzcbSodQd6grmtMjE/AKE4zLV68BJ3ODHY/thtPP7UPYytWcT2JDAYjSVvEThEttQNRhTSyIkYrjoaJUu0OFOfJtWEGrtvp4tn6ILrTM6BAGBhsQylgaHgBjDVotUoMLRiO2wmInVDJy4jfYY+94uieeimOwCq6UV0UEkVxCyezKkppZqzEqEUvJgh1poyBgYZRQdgAaV8UJohpbK4TsUWviF0pTmVw0V6k/VXSjZiYHEd3egZLFo1ixfHHYWR4iA0qscMHsLJpnFgd7z/NpZHnNIZTqV7YwcjignrpNRUPA3nj67pO98OZGPHOWf+dU7FKQRlhhErVp1jK+6dXa4Jkg2KApZVGobl1UwUFHxoEF1gjCczykgooygrKGExPzbBjQzIbBmAnQPZ5vL3Uyh0c6k6Dpk+gsj8tl94YYVpiSo9roPi9r6oKTdPAQUPrgMbVCM6hgUJRFACMMLu+z7lXsr+ikyG2y3DH3tT0NFrtNsqyQFkWaEIHgZhlZMKKW/ZDKFAUNqWDAgVYWJiyBNUNiBo+F7yCNlFEEtJpxR1hSoQEFXiKeKk1miYAmqB9kJZfApFH3Tg4V3O6ToqzlTjwwXPKuShLsf2BlU9DgKp5OKiPkgaenb0oyui8R1TKImG0eJaPYkaTSOoCpUA81pilIEEIRIJMuWbmBfKOVgWgiVVmQQDFzsvUfuwlvaiEcZc08WvAvHZIjLAHXg5Dkg0SvIMiBwoeVitUIn/OniC3dbraszaCUEzacP6T5Ywl8pBRy1xhztfFFI01/QZXeuvFIBErEAFQiHIMfYEoGu9SKoWIX4j4siqj+l9dgBRcw8I62hoosojMs1I8apu7iiRSJIKKtdaB6eCYHlHiGUctkzgsjgKvDUEGzmklTIUSoxMj/dD392poXYhB4YiQf1cAhEqMHf9JmZYAkkFbMc3UK2wlRHl+DpzY8BHYOVR9GgLsGPZoWgWJgp1HMEp0GfilbpoeTU/yshtbwpYtFFIwOTM1DYDgTGy3lOFaxvA18pJzLtXAFoQmcGsksyeExgWWrQfrkyil0KoqNK6Dru/ANw2mp6d5homxoskSmFUhdt6qquDDkthATkyOo6oqKKWwfPkKKKUxfvgQfNPBDDkMDo2IQ85RIS+3uLN9NR0MHqfeY5tksqikeYzRmBk/hGeffx5asZDb2NgYAML45DisMRhaMIzCsOJmFO5jUUKf0qe9fSupz3QPlATGYjdFNI6RReMVAcgTvAp9DqIURRIbu9SiLrVXNh1w3IKqhAkxon4aBzjqvnvRpk85lLgo2bsGM9OTWLJwIRYvWgitNGa6DcrA9sGTMB3ChCZDjl63hveemTdjxNHhdz8FQJH9UNKiGQ+I0Jt4bAotf4fsaxGhimlZEiE1EEXSCyQtxjAqjVKI7E8IHi4A1pbM5kEGGhLraMSBlzyPJDDjKIq53nsuVoysr+IErg8BTZB6jOhUin1TqX4tRtf8HUO6vuK7b6QolPdgtBFBGFdeX83RHNfZeECrGJQgqazykDr5LgIf9mx3uCOvWzd49plnuJbLe5SWf7/RGso13FkSD1IoKKtSIFo3Dc/jUUoYGQIpqQNSYuWCl+wGCYuiEKkxowAYzUFXkGGSCoCiNMJgpjsDELe9c9cYp8eD92i0Q2ktWiUHOYEIVQl0ZrrMANVd3uvCpgDSAWlZtj5qQIUmQJUFp3BlOKpmvpw3MwJiY4HSPP4AIDSoOXCSdnwFHrWhqxJNp4uo6RUF2GJ9oJKNycXa/ZT4K2NeOiTRqDbOoyp5YzR1IxoCfDi7ukbjPGxh0UHU5O87yYWZUNGYuMhLcDTCn4s8uVLQynExGTErU9cy9p160sGxViLKUmvZiFFRDxItxAgI4JeOEnXLRagKUVmPo4IYIFprEafQxr5urSGjoIP8fgMlEQrA80QaOTQBJNnsaOwBcKGfeLEEpM9qF0ezUlr3mM+WUwQhDRyNLATkMAJHgVoD6HIfPdhJqEMjnjcrFhpreoej5DCjxkCsC5nlVEiknA46rRCMODihTlOPnRQlx++eiJ/bGoI1FTrUgQoBU5MTaOpa5mhYlv1WCqawySEJIaAwJYzlF7Ihzx0nUtQbnJNiOf4ujSiMNo2DDw1ch1kPH1jbwFojUS/B6hbKloG3FlqxHPpM02B6app1FSyLoFVVifbAICampjH+/EGMT05hoD2AorQSucXWcO5YiJogUdhJy3Tr4LmiHuB96esatVI4/PzzCHUXymjMTDlMtktMT02DlMKiRW1OITgPH9igkVbCHHnZs/EQjNuBv0tCL4rmFlDZm+JEKKgUlfIe4VZCZ3t1TyEEnj0VuIg4kAeC584GyBRrx8PbTNRAkPQHy71LQS4FkBF591hMHQJmJibh6hojI8MYGR1Bt2k4Su0aNJWTfaxjpki+X93nlCAFLK6uUYs77rzj6FlYXCIWGCuMRtM4aVmumU3x7PDPUEAte9gqm5wfL2mtWtVprZTiQy1ObY11Bqk2QJw4EMHoDg8/K0qoQKg9C/txQMKuvTEG3W7DzKJzaByPLrCllfBCwbkadVMnZhPgLhQu5g88ldY5SWeJvZLgy/tYhMx/n5Vi8agjZEV2faauk80MvkHSZ4oMmMzUUkqJejO7RLFzhG0dOzJNU2M6zvVSCjCc/kNZAK7m6b/eo/H8uxttUYhmjIJCIymoQEHWOKS0IPsZXK/WNCULiFnLqRHvUXdZfoLHLgDBF9CGO/U4mOGDu2m4AQNKGh9kXbvGolWUQNUCVbF8QOZTOULddVKIruBcITWEvO9jmqmRItRG1LqjAB+nyoSR01yTFJlErZkdCyI6F+v0uBtPin01uC5O0nj9+xDgFCWXDQTU3Trt/1eCole74nWIJ554AieccMJc30ZGRkZGRkbGa8S+fftw7LHHvuzn85IhWbRoEQBg7969GBkZmeO7mR8YHx/Hcccdh3379mF4eHiub2deIK/ZkSOv2ZEjr9mRI6/ZkWMu14yIMDExgRUrVrzidfPSIYn52pGRkbwZjxDDw8N5zY4Qec2OHHnNjhx5zY4cec2OHHO1Zq+FPHiNciUZGRkZGRkZGf89ZIckIyMjIyMjY84xLx2Sqqpw7bXXoqqqub6VeYO8ZkeOvGZHjrxmR468ZkeOvGZHjvmwZvOyyyYjIyMjIyPjjYV5yZBkZGRkZGRkvLGQHZKMjIyMjIyMOUd2SDIyMjIyMjLmHNkhycjIyMjIyJhzzEuH5Ac/+AGOP/54tFotrF27Fg888MBc39Kc4c9//jM++MEPYsWKFVBK4aabbpr1ORHh61//OpYvX452u43169dj9+7ds645ePAgLrnkEgwPD2N0dBSf+cxnMDk5eRSf4uhh48aNeMc73oEFCxZg6dKl+MhHPoJdu3bNuqbT6WDDhg1YvHgxhoaG8LGPfQxPP/30rGv27t2LCy+8EAMDA1i6dCm++MUvwjl3NB/lqGHTpk0444wzkqDSunXrcOutt6bP83q9Oq677joopXDVVVeln+V1m41vfOMbad5M/HPKKaekz/N6vTSefPJJfOITn8DixYvRbrdx+umn48EHH0yfz6szgOYZNm/eTGVZ0k9/+lN65JFH6LOf/SyNjo7S008/Pde3Nie45ZZb6Ktf/Sr99re/JQB04403zvr8uuuuo5GREbrpppvoH//4B33oQx+i1atX08zMTLrm/e9/P5155pl0//3301/+8hc68cQT6eKLLz7KT3J0cP7559P1119PO3fupB07dtAHPvABWrlyJU1OTqZrLrvsMjruuOPozjvvpAcffJDe+c530rve9a70uXOOTjvtNFq/fj1t376dbrnlFlqyZAl9+ctfnotH+q/j5ptvpj/+8Y/02GOP0a5du+grX/kKFUVBO3fuJKK8Xq+GBx54gI4//ng644wz6Morr0w/z+s2G9deey297W1vo6eeeir9eeaZZ9Lneb1ejIMHD9KqVavok5/8JG3dupWeeOIJuv322+nxxx9P18ynM2DeOSTnnHMObdiwIf1/7z2tWLGCNm7cOId39frACx2SEAKNjY3Rt7/97fSzQ4cOUVVV9Mtf/pKIiB599FECQH/729/SNbfeeisppejJJ588avc+Vzhw4AABoC1bthARr09RFPTrX/86XfPPf/6TANB9991HROwEaq1p//796ZpNmzbR8PAwdbvdo/sAc4SFCxfST37yk7xer4KJiQk66aST6I477qD3vve9ySHJ6/ZiXHvttXTmmWe+5Gd5vV4aX/rSl+jd7373y34+386AeZWyqesa27Ztw/r169PPtNZYv3497rvvvjm8s9cn9uzZg/37989ar5GREaxduzat13333YfR0VGsWbMmXbN+/XporbF169ajfs9HG4cPHwbQG9i4bds2NE0za81OOeUUrFy5ctaanX766Vi2bFm65vzzz8f4+DgeeeSRo3j3Rx/ee2zevBlTU1NYt25dXq9XwYYNG3DhhRfOWh8g77OXw+7du7FixQq8+c1vxiWXXIK9e/cCyOv1crj55puxZs0afPzjH8fSpUtx1lln4cc//nH6fL6dAfPKIXn22WfhvZ+14QBg2bJl2L9//xzd1esXcU1eab3279+PpUuXzvrcWotFixa94dc0hICrrroK5557Lk477TQAvB5lWWJ0dHTWtS9cs5da0/jZGxEPP/wwhoaGUFUVLrvsMtx444049dRT83q9AjZv3oy///3v2Lhx44s+y+v2YqxduxY33HADbrvtNmzatAl79uzBe97zHkxMTOT1ehk88cQT2LRpE0466STcfvvtuPzyy/GFL3wBP/vZzwDMvzNgXk77zcj4v8CGDRuwc+dO3HvvvXN9K697vOUtb8GOHTtw+PBh/OY3v8Gll16KLVu2zPVtvW6xb98+XHnllbjjjjvQarXm+nbmBS644IL072eccQbWrl2LVatW4Ve/+hXa7fYc3tnrFyEErFmzBt/61rcAAGeddRZ27tyJH/7wh7j00kvn+O6OHPOKIVmyZAmMMS+qrH766acxNjY2R3f1+kVck1dar7GxMRw4cGDW5845HDx48A29pldccQX+8Ic/4O6778axxx6bfj42Noa6rnHo0KFZ179wzV5qTeNnb0SUZYkTTzwRZ599NjZu3IgzzzwT3/3ud/N6vQy2bduGAwcO4O1vfzustbDWYsuWLfje974Hay2WLVuW1+1VMDo6ipNPPhmPP/543mcvg+XLl+PUU0+d9bO3vvWtKdU1386AeeWQlGWJs88+G3feeWf6WQgBd955J9atWzeHd/b6xOrVqzE2NjZrvcbHx7F169a0XuvWrcOhQ4ewbdu2dM1dd92FEALWrl171O/5vw0iwhVXXIEbb7wRd911F1avXj3r87PPPhtFUcxas127dmHv3r2z1uzhhx+e9RLfcccdGB4efpFxeKMihIBut5vX62Vw3nnn4eGHH8aOHTvSnzVr1uCSSy5J/57X7ZUxOTmJf/3rX1i+fHneZy+Dc88990WyBY899hhWrVoFYB6eAUe1hPb/AJs3b6aqquiGG26gRx99lD73uc/R6OjorMrq/58wMTFB27dvp+3btxMA+s53vkPbt2+n//znP0TELV+jo6P0u9/9jh566CH68Ic//JItX2eddRZt3bqV7r33XjrppJPesG2/l19+OY2MjNA999wzq71weno6XXPZZZfRypUr6a677qIHH3yQ1q1bR+vWrUufx/bC973vfbRjxw667bbb6JhjjnnDthdec801tGXLFtqzZw899NBDdM0115BSiv70pz8RUV6v14r+LhuivG4vxNVXX0333HMP7dmzh/7617/S+vXracmSJXTgwAEiyuv1UnjggQfIWkvf/OY3affu3fSLX/yCBgYG6Oc//3m6Zj6dAfPOISEi+v73v08rV66ksizpnHPOofvvv3+ub2nOcPfddxOAF/259NJLiYjbvr72ta/RsmXLqKoqOu+882jXrl2zfsdzzz1HF198MQ0NDdHw8DB96lOfoomJiTl4mv8+XmqtAND111+frpmZmaHPf/7ztHDhQhoYGKCPfvSj9NRTT836Pf/+97/pggsuoHa7TUuWLKGrr76amqY5yk9zdPDpT3+aVq1aRWVZ0jHHHEPnnXdeckaI8nq9VrzQIcnrNhsXXXQRLV++nMqypDe96U100UUXzdLTyOv10vj9739Pp512GlVVRaeccgr96Ec/mvX5fDoDFBHR0eVkMjIyMjIyMjJmY17VkGRkZGRkZGS8MZEdkoyMjIyMjIw5R3ZIMjIyMjIyMuYc2SHJyMjIyMjImHNkhyQjIyMjIyNjzpEdkoyMjIyMjIw5R3ZIMjIyMjIyMuYc2SHJyMjIyMjImHNkhyQjIyMjIyNjzpEdkoyMjIyMjIw5R3ZIMjIyMjIyMuYc2SHJyMjIyMjImHP8P58ugBtOvfXuAAAAAElFTkSuQmCC", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "plt.imshow(rgb_camera_bridge.get_image())" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "import socket\n", + "import struct\n", + "import numpy as np\n", + "import time\n", + "import threading\n", + "from cyclonedds.domain import DomainParticipant\n", + "from cyclonedds.topic import Topic\n", + "from cyclonedds.sub import DataReader\n", + "from cyclonedds.pub import Publisher, DataWriter\n", + "from dataclasses import dataclass\n", + "from Go2DDSMsgs import PointCloud, RGBImage, DepthImage, Pose, HighCommand\n", + "from scipy.spatial.transform import Rotation as R\n", + "\n", + "\n", + "def get_last_msg(reader, topic_type):\n", + " \"\"\" \"\"\"\n", + " last_msg = reader.take()\n", + "\n", + " if last_msg:\n", + " while True:\n", + " a = reader.take()\n", + " if not a:\n", + " break\n", + " else:\n", + " last_msg = a\n", + " if last_msg:\n", + " msg = last_msg[0]\n", + " if type(msg) == topic_type:\n", + " return msg\n", + " else:\n", + " return None\n", + "\n", + " else:\n", + " return None\n", + " \n", + "class Go2DDSServer:\n", + " def __init__(self, robot_name):\n", + " self.robot_name = robot_name\n", + " self.domain = DomainParticipant()\n", + " self.rgb_topic = Topic(self.domain, f'{self.robot_name}_rgb', RGBImage)\n", + " self.depth_topic = Topic(self.domain, f'{self.robot_name}_depth', DepthImage) \n", + " self.map_topic = Topic(self.domain, f'{self.robot_name}_lio_map', PointCloud)\n", + " self.lidar_odom_topic = Topic(self.domain, f'{self.robot_name}_lio_odom', Pose)\n", + " self.high_cmd_topic = Topic(self.domain, f'{self.robot_name}_high_cmd', HighCommand)\n", + " self.rgb_publisher = Publisher(self.domain)\n", + " self.depth_publisher = Publisher(self.domain)\n", + " self.map_publisher = Publisher(self.domain)\n", + " self.lidar_odom_publisher = Publisher(self.domain)\n", + " self.high_cmd_reader = DataReader(self.domain, self.high_cmd_topic)\n", + " self.rgb_writer = DataWriter(self.rgb_publisher, self.rgb_topic)\n", + " self.depth_writer = DataWriter(self.depth_publisher, self.depth_topic)\n", + " self.map_writer = DataWriter(self.map_publisher, self.map_topic)\n", + " self.lidar_odom_writer = DataWriter(self.lidar_odom_publisher, self.lidar_odom_topic)\n", + " \n", + " \n", + " \n", + "\n", + " def sendRGB(self, rgb):\n", + " self.rgb_writer.write(RGBImage(data=rgb.reshape(-1).tolist(), width=rgb.shape[1], height=rgb.shape[0], timestamp=''))\n", + " \n", + " def sendDepth(self, depth):\n", + " self.depth_writer.write(DepthImage(data=depth.reshape(-1).tolist(), width=depth.shape[1], height=depth.shape[0], timestamp=''))\n", + "\n", + " def sendMap(self, pcd):\n", + " map_pcd_mgs = PointCloud(x = pcd[:,0].tolist(), \n", + " y = pcd[:,1].tolist(), \n", + " z = pcd[:,2].tolist(), \n", + " timestamp=''\n", + " )\n", + " self.map_writer.write(map_pcd_mgs)\n", + " \n", + " def sendLidarOdom(self, lio_T_body):\n", + " q = R.from_matrix(lio_T_body[:3,:3]).as_quat()\n", + " t = lio_T_body[:3,3]\n", + " pose_msg = Pose(quat=q.tolist(), trans=t.tolist(), timestamp='')\n", + " self.lidar_odom_writer.write(pose_msg)\n", + "\n", + " def getHighCmd(self):\n", + " return get_last_msg(self.high_cmd_reader, HighCommand) \n", + " \n", + "\n", + "# class Go2DDSClient:\n", + "# def __init__(self, robot_name):\n", + "# self.robot_name = robot_name\n", + "# self.domain = DomainParticipant()\n", + "# self.rgb_topic = Topic(self.domain, f'{self.robot_name}_rgb', RGBImage)\n", + "# self.depth_topic = Topic(self.domain, f'{self.robot_name}_depth', DepthImage) \n", + "# self.map_topic = Topic(self.domain, f'{self.robot_name}_lio_map', PointCloud)\n", + "# self.lidar_odom_topic = Topic(self.domain, f'{self.robot_name}_lio_odom', Pose)\n", + "# self.high_cmd_topic = Topic(self.domain, f'{self.robot_name}_high_cmd', HighCommand)\n", + "# self.rgb_reader = DataReader(self.domain, self.rgb_topic)\n", + "# self.depth_reader = DataReader(self.domain, self.depth_topic)\n", + "# self.map_reader = DataReader(self.domain, self.map_topic)\n", + "# self.lidar_odom_reader = DataReader(self.domain, self.lidar_odom_topic)\n", + "# self.high_cmd_writer = DataWriter(self.domain, self.high_cmd_topic)\n", + "\n", + "# def getRGB(self):\n", + "# return get_last_msg(self.rgb_reader, RGBImage)\n", + " \n", + "# def getDepth(self):\n", + "# return get_last_msg(self.depth_reader, DepthImage)\n", + " \n", + "# def getMap(self):\n", + "# return get_last_msg(self.map_reader, PointCloud)\n", + " \n", + "# def getLidarOdom(self):\n", + "# return get_last_msg(self.lidar_odom_reader, Pose)\n", + " \n", + "# def sendHighCmd(self, vx, vy, omega):\n", + "# self.high_cmd_writer.write(HighCommand(vx=vx, vy=vy, omega=omega, timestamp=''))\n", + " " + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": {}, + "outputs": [], + "source": [ + "from dds_telemetry import Go2DDSServer, Go2DDSClient" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "server = Go2DDSServer(robot_name='go2')" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "client = Go2DDSClient(robot_name='go2')" + ] + }, + { + "cell_type": "code", + "execution_count": 6, + "metadata": {}, + "outputs": [], + "source": [ + "img = client.getRGB()" + ] + }, + { + "cell_type": "code", + "execution_count": 19, + "metadata": {}, + "outputs": [], + "source": [ + "client.sendHighCmd(0,0,0)" + ] + }, + { + "cell_type": "code", + "execution_count": 23, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "HighCommand(vx=0.0, vy=0.0, omega=0.0, timestamp='')" + ] + }, + "execution_count": 23, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "server.getHighCmd()" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "rgb = np.random.randint(0, 255, (10, 10, 3)).astype(np.uint8)\n", + "server.sendRGB(rgb)\n" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "usr", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.8.10" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/dds_bridge/DDSMsgs.idl b/dds_bridge/DDSMsgs.idl new file mode 100644 index 0000000..69a13b9 --- /dev/null +++ b/dds_bridge/DDSMsgs.idl @@ -0,0 +1,43 @@ +module Go2DDSMsgs { + struct PointCloud { + sequence x; + sequence y; + sequence z; + string timestamp; + }; + + struct DepthImage { + uint16 width; + uint16 height; + sequence data; + string timestamp; + }; + + struct RGBImage { + uint16 width; + uint16 height; + sequence data; + string timestamp; + }; + + struct Pose { + double quat[4]; + double trans[3]; + string timestamp; + }; + + struct HighCommand { + double vx; + double vy; + double omega; + string timestamp; + }; + + struct Imu { + double accel[3]; + double gyro[3]; + double quat[4]; + string timestamp; + }; + +}; \ No newline at end of file diff --git a/dds_bridge/Go2DDSMsgs/.idlpy_manifest b/dds_bridge/Go2DDSMsgs/.idlpy_manifest new file mode 100644 index 0000000..64128af --- /dev/null +++ b/dds_bridge/Go2DDSMsgs/.idlpy_manifest @@ -0,0 +1,8 @@ +DDSMsgs + +DepthImage +HighCommand +Imu +PointCloud +Pose +RGBImage diff --git a/dds_bridge/Go2DDSMsgs/_DDSMsgs.py b/dds_bridge/Go2DDSMsgs/_DDSMsgs.py new file mode 100644 index 0000000..5922568 --- /dev/null +++ b/dds_bridge/Go2DDSMsgs/_DDSMsgs.py @@ -0,0 +1,79 @@ +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.5 + Module: Go2DDSMsgs + IDL file: DDSMsgs.idl + +""" + +from enum import auto +from typing import TYPE_CHECKING, Optional +from dataclasses import dataclass + +import cyclonedds.idl as idl +import cyclonedds.idl.annotations as annotate +import cyclonedds.idl.types as types + +# root module import for resolving types +import Go2DDSMsgs + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class PointCloud(idl.IdlStruct, typename="Go2DDSMsgs.PointCloud"): + x: types.sequence[types.float32] + y: types.sequence[types.float32] + z: types.sequence[types.float32] + timestamp: str + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class DepthImage(idl.IdlStruct, typename="Go2DDSMsgs.DepthImage"): + width: types.uint16 + height: types.uint16 + data: types.sequence[types.uint16] + timestamp: str + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class RGBImage(idl.IdlStruct, typename="Go2DDSMsgs.RGBImage"): + width: types.uint16 + height: types.uint16 + data: types.sequence[types.uint8] + timestamp: str + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Pose(idl.IdlStruct, typename="Go2DDSMsgs.Pose"): + quat: types.array[types.float64, 4] + trans: types.array[types.float64, 3] + timestamp: str + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class HighCommand(idl.IdlStruct, typename="Go2DDSMsgs.HighCommand"): + vx: types.float64 + vy: types.float64 + omega: types.float64 + timestamp: str + + +@dataclass +@annotate.final +@annotate.autoid("sequential") +class Imu(idl.IdlStruct, typename="Go2DDSMsgs.Imu"): + accel: types.array[types.float64, 3] + gyro: types.array[types.float64, 3] + quat: types.array[types.float64, 4] + timestamp: str + + diff --git a/dds_bridge/Go2DDSMsgs/__init__.py b/dds_bridge/Go2DDSMsgs/__init__.py new file mode 100644 index 0000000..df3657b --- /dev/null +++ b/dds_bridge/Go2DDSMsgs/__init__.py @@ -0,0 +1,9 @@ +""" + Generated by Eclipse Cyclone DDS idlc Python Backend + Cyclone DDS IDL version: v0.10.5 + Module: Go2DDSMsgs + +""" + +from ._DDSMsgs import DepthImage, HighCommand, Imu, PointCloud, Pose, RGBImage +__all__ = ["DepthImage", "HighCommand", "Imu", "PointCloud", "Pose", "RGBImage", ] diff --git a/dds_bridge/dds_bridge.py b/dds_bridge/dds_bridge.py new file mode 100644 index 0000000..9e77b73 --- /dev/null +++ b/dds_bridge/dds_bridge.py @@ -0,0 +1,116 @@ +import sys +sys.path.append('..') + +from Go2Py.utils.ros2 import PoindCloud2Bridge, ros2_init, ros2_close, ROS2ExecutorManager, ROS2CameraReader +from Go2Py.utils.ros2 import ROS2OdometryReader +from Go2Py.robot.interface import GO2Real +from dds_telemetry import Go2DDSServer +import time +import numpy as np +import time +import cv2 + +import pickle +RECORD_DATASET = False +DATASET_LENGTH = 120 +ros2_init() +map_bridge = PoindCloud2Bridge('/Laser_map') +fast_lio_odom = ROS2OdometryReader('/Odometry', 'odometry_subscriber') +rgb_camera_bridge = ROS2CameraReader('/camera/color/image_raw', 'rgb_reader') +depth_camera_bridge = ROS2CameraReader('/camera/depth/image_rect_raw', 'depth_reader') + +ros2_exec_manager = ROS2ExecutorManager() +ros2_exec_manager.add_node(map_bridge) +ros2_exec_manager.add_node(fast_lio_odom) +ros2_exec_manager.add_node(rgb_camera_bridge) +ros2_exec_manager.add_node(depth_camera_bridge) +ros2_exec_manager.start() + +# The extrinsics of the MID360 LiDAR with respect to the robot body +body_T_lidar = np.array([ + [ 0.9743701, 0.0, 0.2249511, 0.1870 ], + [ 0.0, 1.0, 0.0, 0.0 ], + [-0.2249511, 0.0, 0.9743701, 0.0803 ], + [ 0.0, 0.0, 0.0, 1.0 ] +]) + +robot = GO2Real(mode='highlevel') +dds_server = Go2DDSServer(robot_name='go2') + +def GetLidarPose(): + lio_T_lidar = fast_lio_odom.get_pose() + if lio_T_lidar is not None: + lio_T_body = lio_T_lidar @ np.linalg.inv(body_T_lidar) + return lio_T_body + else: + return None + +def GetLidarMap(): + pcd = map_bridge._points + if pcd is not None: + return pcd + else: + return None + +print('Waitng for the ROS2 bridges to start up ...') +time.sleep(5) +print('Running the bridge loop') +lio_pcd = None +map_update_counter = 0 + +rgb_imgs = [] +depth_imgs = [] +lio_Ts_robot = [] +pcd_maps = [] + + + +start_time = time.time() + +while True: + tic = time.time() + lio_T_robot = GetLidarPose() + if lio_T_robot is not None: + dds_server.sendLidarOdom(lio_T_robot) + if RECORD_DATASET: + lio_Ts_robot.append(lio_T_robot) + + + if map_update_counter%10==0: + lio_pcd = GetLidarMap() + if lio_pcd is not None: + dds_server.sendMap(lio_pcd) + if RECORD_DATASET: + pcd_maps.append(lio_pcd.copy()) + + map_update_counter += 1 + + depth = depth_camera_bridge.get_image() + rgb = rgb_camera_bridge.get_image() + if depth is not None and rgb is not None: + depth = cv2.resize(depth, (320, 240)) + rgb = cv2.resize(rgb, (320, 240)) + # print('sending image') + dds_server.sendDepth(depth) + dds_server.sendRGB(rgb) + + if RECORD_DATASET: + rgb_imgs.append(rgb.copy()) + depth_imgs.append(depth.copy()) + + + if time.time()-start_time >= DATASET_LENGTH: + break + + # Forward the rgb, depth, lio, lio_T_lidar to the computer through DDS + toc = time.time() + command = dds_server.getHighCmd() + if command is not None: + print('Recievied a command from the client. Forwarding to the robot...') + robot.setCommandsHigh(command.vx, command.vy, command.omega) + + print(f'{(toc-tic):0.3f}') + while(time.time()-tic) < 0.1: + time.sleep(0.001) + + diff --git a/dds_bridge/dds_telemetry.py b/dds_bridge/dds_telemetry.py new file mode 100644 index 0000000..d31959a --- /dev/null +++ b/dds_bridge/dds_telemetry.py @@ -0,0 +1,111 @@ +import socket +import struct +import numpy as np +import time +import threading +from cyclonedds.domain import DomainParticipant +from cyclonedds.topic import Topic +from cyclonedds.sub import DataReader +from cyclonedds.pub import Publisher, DataWriter +from dataclasses import dataclass +from Go2DDSMsgs import PointCloud, RGBImage, DepthImage, Pose, HighCommand +from scipy.spatial.transform import Rotation as R + + +def get_last_msg(reader, topic_type): + """ """ + last_msg = reader.take() + + if last_msg: + while True: + a = reader.take() + if not a: + break + else: + last_msg = a + if last_msg: + msg = last_msg[0] + if type(msg) == topic_type: + return msg + else: + return None + + else: + return None + +class Go2DDSServer: + def __init__(self, robot_name): + self.robot_name = robot_name + self.domain = DomainParticipant() + self.rgb_topic = Topic(self.domain, f'{self.robot_name}_rgb', RGBImage) + self.depth_topic = Topic(self.domain, f'{self.robot_name}_depth', DepthImage) + self.map_topic = Topic(self.domain, f'{self.robot_name}_lio_map', PointCloud) + self.lidar_odom_topic = Topic(self.domain, f'{self.robot_name}_lio_odom', Pose) + self.high_cmd_topic = Topic(self.domain, f'{self.robot_name}_high_cmd', HighCommand) + self.rgb_publisher = Publisher(self.domain) + self.depth_publisher = Publisher(self.domain) + self.map_publisher = Publisher(self.domain) + self.lidar_odom_publisher = Publisher(self.domain) + self.high_cmd_reader = DataReader(self.domain, self.high_cmd_topic) + self.rgb_writer = DataWriter(self.rgb_publisher, self.rgb_topic) + self.depth_writer = DataWriter(self.depth_publisher, self.depth_topic) + self.map_writer = DataWriter(self.map_publisher, self.map_topic) + self.lidar_odom_writer = DataWriter(self.lidar_odom_publisher, self.lidar_odom_topic) + + + + + def sendRGB(self, rgb): + self.rgb_writer.write(RGBImage(data=rgb.reshape(-1).tolist(), width=rgb.shape[1], height=rgb.shape[0], timestamp='')) + + def sendDepth(self, depth): + self.depth_writer.write(DepthImage(data=depth.reshape(-1).tolist(), width=depth.shape[1], height=depth.shape[0], timestamp='')) + + def sendMap(self, pcd): + map_pcd_mgs = PointCloud(x = pcd[:,0].tolist(), + y = pcd[:,1].tolist(), + z = pcd[:,2].tolist(), + timestamp='' + ) + self.map_writer.write(map_pcd_mgs) + + def sendLidarOdom(self, lio_T_body): + q = R.from_matrix(lio_T_body[:3,:3]).as_quat() + t = lio_T_body[:3,3] + pose_msg = Pose(quat=q.tolist(), trans=t.tolist(), timestamp='') + self.lidar_odom_writer.write(pose_msg) + + def getHighCmd(self): + return get_last_msg(self.high_cmd_reader, HighCommand) + + +class Go2DDSClient: + def __init__(self, robot_name): + self.robot_name = robot_name + self.domain = DomainParticipant() + self.rgb_topic = Topic(self.domain, f'{self.robot_name}_rgb', RGBImage) + self.depth_topic = Topic(self.domain, f'{self.robot_name}_depth', DepthImage) + self.map_topic = Topic(self.domain, f'{self.robot_name}_lio_map', PointCloud) + self.lidar_odom_topic = Topic(self.domain, f'{self.robot_name}_lio_odom', Pose) + self.high_cmd_topic = Topic(self.domain, f'{self.robot_name}_high_cmd', HighCommand) + self.rgb_reader = DataReader(self.domain, self.rgb_topic) + self.depth_reader = DataReader(self.domain, self.depth_topic) + self.map_reader = DataReader(self.domain, self.map_topic) + self.lidar_odom_reader = DataReader(self.domain, self.lidar_odom_topic) + self.high_cmd_writer = DataWriter(self.domain, self.high_cmd_topic) + + def getRGB(self): + return get_last_msg(self.rgb_reader, RGBImage) + + def getDepth(self): + return get_last_msg(self.depth_reader, DepthImage) + + def getMap(self): + return get_last_msg(self.map_reader, PointCloud) + + def getLidarOdom(self): + return get_last_msg(self.lidar_odom_reader, Pose) + + def sendHighCmd(self, vx, vy, omega): + self.high_cmd_writer.write(HighCommand(vx=vx, vy=vy, omega=omega, timestamp='')) + \ No newline at end of file diff --git a/dds_bridge/neurodiff-controller.py b/dds_bridge/neurodiff-controller.py new file mode 100644 index 0000000..c37fc27 --- /dev/null +++ b/dds_bridge/neurodiff-controller.py @@ -0,0 +1,53 @@ +from Go2Py.robot.fsm import FSM +from Go2Py.robot.safety import SafetyHypervisor +from Go2Py.robot.interface import GO2Real +from Go2Py.control.neuro_diff import NeuroDiffAgent + +import torch +import numpy as np +import time + + +class NeuroDiffController: + def __init__(self, robot, remote, checkpoint): + self.remote = remote + self.robot = robot + self.policy = Policy(checkpoint) + self.command_profile = CommandInterface() + self.agent = NeuroDiffSimAgent(self.command_profile, self.robot) + self.hist_data = {} + + def init(self): + self.obs = self.agent.reset() + self.policy_info = {} + self.command_profile.yaw_vel_cmd = 0.0 + self.command_profile.x_vel_cmd = 0.0 + self.command_profile.y_vel_cmd = 0.0 + + def update(self, robot, remote): + if not hasattr(self, "obs"): + self.init() + commands = getRemote(remote) + self.command_profile.yaw_vel_cmd = 0.0 + self.command_profile.x_vel_cmd = 0.0 + self.command_profile.y_vel_cmd = 0.0 + + self.obs = self.agent.get_obs() + action = self.policy(self.obs, self.policy_info) + _, self.ret, self.done, self.info = self.agent.step(action) + for key, value in self.info.items(): + if key in self.hist_data: + self.hist_data[key].append(value) + else: + self.hist_data[key] = [value] + + + +robot = GO2Real(mode='lowlevel') +safety_hypervisor = SafetyHypervisor(robot) + +time.sleep(3) + +print(robot.getJointStates()) + +robot.close() \ No newline at end of file diff --git a/dds_bridge/test.py b/dds_bridge/test.py new file mode 100644 index 0000000..6a88389 --- /dev/null +++ b/dds_bridge/test.py @@ -0,0 +1,26 @@ +from cyclonedds.topic import Topic +from cyclonedds.pub import DataWriter + +from cyclonedds.domain import DomainParticipant +from cyclonedds.topic import Topic +from cyclonedds.sub import DataReader +from cyclonedds.util import duration +import numpy as np + +from Go2DDSMsgs import PointCloud, RGBImage, DepthImage, Pose, HighCommand +# from scipy.spatial.transform import Rotation as R + +participant = DomainParticipant() +topic = Topic(participant, 'test_topic', RGBImage) +writer = DataWriter(participant, topic) + +# domain = DomainParticipant() +# rgb_topic = Topic(domain, 'go2_rgb', RGBImage) +# rgb_publisher = Publisher(domain) +# rgb_writer = DataWriter(rgb_publisher, rgb_topic) + + +rgb = np.random.randint(0, 255, (10, 10, 3)).astype(np.uint8) + +rgb_msg = RGBImage(data=[0, 1, 2], timestamp='') +writer.write(rgb_msg) \ No newline at end of file diff --git a/dds_bridge/test2.py b/dds_bridge/test2.py new file mode 100644 index 0000000..e69de29