From 35bccd27546718c685b04d83f9840415b1b2ff15 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Thu, 6 Mar 2025 01:33:35 -0800 Subject: [PATCH 01/12] adds pose2d command, reset event and observation function for the task --- source/isaaclab/config/extension.toml | 2 +- source/isaaclab/docs/CHANGELOG.rst | 11 ++++ .../isaaclab/envs/mdp/commands/__init__.py | 3 +- .../envs/mdp/commands/commands_cfg.py | 25 +++++++- .../envs/mdp/commands/pose_2d_command.py | 64 ++++++++++++++++++- source/isaaclab/isaaclab/envs/mdp/events.py | 39 +++++++++++ .../isaaclab/envs/mdp/observations.py | 16 +++++ 7 files changed, 155 insertions(+), 5 deletions(-) diff --git a/source/isaaclab/config/extension.toml b/source/isaaclab/config/extension.toml index 56419d47a599..8558ac94f192 100644 --- a/source/isaaclab/config/extension.toml +++ b/source/isaaclab/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.34.9" +version = "0.34.10" # Description title = "Isaac Lab framework for Robot Learning" diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index d20a641a72ab..d874f7aa41ae 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -1,6 +1,17 @@ Changelog --------- +0.34.10 (2025-03-06) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added the pose2d command that generates the target position based on the position of the obstacle object. +* Added the reset event that samples a position in a sector of a ring area defined by the radius and angle ranges. +* Added the observation function for getting flattned normalized rgb data. + + 0.34.9 (2025-03-04) ~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab/isaaclab/envs/mdp/commands/__init__.py b/source/isaaclab/isaaclab/envs/mdp/commands/__init__.py index 28846fed0921..5bc9af02a849 100644 --- a/source/isaaclab/isaaclab/envs/mdp/commands/__init__.py +++ b/source/isaaclab/isaaclab/envs/mdp/commands/__init__.py @@ -8,12 +8,13 @@ from .commands_cfg import ( NormalVelocityCommandCfg, NullCommandCfg, + ObstaclePose2dCommandCfg, TerrainBasedPose2dCommandCfg, UniformPose2dCommandCfg, UniformPoseCommandCfg, UniformVelocityCommandCfg, ) from .null_command import NullCommand -from .pose_2d_command import TerrainBasedPose2dCommand, UniformPose2dCommand +from .pose_2d_command import ObstaclePose2dCommand, TerrainBasedPose2dCommand, UniformPose2dCommand from .pose_command import UniformPoseCommand from .velocity_command import NormalVelocityCommand, UniformVelocityCommand diff --git a/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py b/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py index a2af9bbb0fab..077f9491da4e 100644 --- a/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py +++ b/source/isaaclab/isaaclab/envs/mdp/commands/commands_cfg.py @@ -12,7 +12,7 @@ from isaaclab.utils import configclass from .null_command import NullCommand -from .pose_2d_command import TerrainBasedPose2dCommand, UniformPose2dCommand +from .pose_2d_command import ObstaclePose2dCommand, TerrainBasedPose2dCommand, UniformPose2dCommand from .pose_command import UniformPoseCommand from .velocity_command import NormalVelocityCommand, UniformVelocityCommand @@ -228,6 +228,29 @@ class Ranges: goal_pose_visualizer_cfg.markers["arrow"].scale = (0.2, 0.2, 0.8) +@configclass +class ObstaclePose2dCommandCfg(UniformPose2dCommandCfg): + """Configuration for the obstacle-based 2D-pose command generator.""" + + class_type: type = ObstaclePose2dCommand + + object_name: str = MISSING + """Name of the obstacle object in the environment.""" + + @configclass + class Ranges: + """Uniform distribution ranges for the position commands.""" + + heading: tuple[float, float] = MISSING + """Heading range for the position commands (in rad). + + Used only if :attr:`simple_heading` is False. + """ + + ranges: Ranges = MISSING + """Distribution ranges for the sampled commands.""" + + @configclass class TerrainBasedPose2dCommandCfg(UniformPose2dCommandCfg): """Configuration for the terrain-based position command generator.""" diff --git a/source/isaaclab/isaaclab/envs/mdp/commands/pose_2d_command.py b/source/isaaclab/isaaclab/envs/mdp/commands/pose_2d_command.py index 6c37a1146490..6e5000f02000 100644 --- a/source/isaaclab/isaaclab/envs/mdp/commands/pose_2d_command.py +++ b/source/isaaclab/isaaclab/envs/mdp/commands/pose_2d_command.py @@ -11,7 +11,7 @@ from collections.abc import Sequence from typing import TYPE_CHECKING -from isaaclab.assets import Articulation +from isaaclab.assets import Articulation, RigidObject from isaaclab.managers import CommandTerm from isaaclab.markers import VisualizationMarkers from isaaclab.terrains import TerrainImporter @@ -20,7 +20,7 @@ if TYPE_CHECKING: from isaaclab.envs import ManagerBasedEnv - from .commands_cfg import TerrainBasedPose2dCommandCfg, UniformPose2dCommandCfg + from .commands_cfg import ObstaclePose2dCommandCfg, TerrainBasedPose2dCommandCfg, UniformPose2dCommandCfg class UniformPose2dCommand(CommandTerm): @@ -143,6 +143,66 @@ def _debug_vis_callback(self, event): ) +class ObstaclePose2dCommand(UniformPose2dCommand): + """Command generator that generates pose commands based on the obstacle. + + This command generator determines the command position based on the position of the obstacle. + The heading commands are either set to point towards the target or are sampled uniformly. + This can be configured through the :attr:`Pose2dCommandCfg.simple_heading` parameter in + the configuration. + """ + + cfg: ObstaclePose2dCommandCfg + """Configuration for the command generator.""" + + def __init__(self, cfg: ObstaclePose2dCommandCfg, env: ManagerBasedEnv): + """Initialize the command generator class. + + Args: + cfg: The configuration parameters for the command generator. + env: The environment object. + """ + # initialize the base class + super().__init__(cfg, env) + + # obtain the obstacle object + self.object: RigidObject = env.scene[cfg.object_name] + + def _resample_command(self, env_ids: Sequence[int]): + # obtain env origins for the environments + self.pos_command_w[env_ids] = self._env.scene.env_origins[env_ids] + r = torch.empty(len(env_ids), device=self.device) + # offset the position command by the current root position + self.pos_command_w[env_ids, 0] = ( + 2 * self.object.data.root_pos_w[env_ids, 0] - self.robot.data.root_pos_w[env_ids, 0] + ) + self.pos_command_w[env_ids, 1] = ( + 2 * self.object.data.root_pos_w[env_ids, 1] - self.robot.data.root_pos_w[env_ids, 1] + ) + self.pos_command_w[env_ids, 2] = self.robot.data.default_root_state[env_ids, 2] + + if self.cfg.simple_heading: + # set heading command to point towards target + target_vec = self.pos_command_w[env_ids] - self.robot.data.root_pos_w[env_ids] + target_direction = torch.atan2(target_vec[:, 1], target_vec[:, 0]) + flipped_target_direction = wrap_to_pi(target_direction + torch.pi) + + # compute errors to find the closest direction to the current heading + # this is done to avoid the discontinuity at the -pi/pi boundary + curr_to_target = wrap_to_pi(target_direction - self.robot.data.heading_w[env_ids]).abs() + curr_to_flipped_target = wrap_to_pi(flipped_target_direction - self.robot.data.heading_w[env_ids]).abs() + + # set the heading command to the closest direction + self.heading_command_w[env_ids] = torch.where( + curr_to_target < curr_to_flipped_target, + target_direction, + flipped_target_direction, + ) + else: + # random heading command + self.heading_command_w[env_ids] = r.uniform_(*self.cfg.ranges.heading) + + class TerrainBasedPose2dCommand(UniformPose2dCommand): """Command generator that generates pose commands based on the terrain. diff --git a/source/isaaclab/isaaclab/envs/mdp/events.py b/source/isaaclab/isaaclab/envs/mdp/events.py index 82db1515c52a..bbf6930a6675 100644 --- a/source/isaaclab/isaaclab/envs/mdp/events.py +++ b/source/isaaclab/isaaclab/envs/mdp/events.py @@ -737,6 +737,45 @@ def reset_root_state_uniform( asset.write_root_velocity_to_sim(velocities, env_ids=env_ids) +def reset_root_state_uniform_angular( + env: ManagerBasedEnv, + env_ids: torch.Tensor, + radius_range: tuple[float, float], + angle_range: tuple[float, float], + asset_cfg: SceneEntityCfg = SceneEntityCfg("object"), +): + """Reset the asset root state to a random position within a sector of a ring area defined by the radius and angle ranges. + + This function randomizes the root position of the asset. + + * It samples the root position from the given angular ranges and adds them to the default root position, before setting + them into the physics simulation. + * It keeps the root orientation unchanged. + * It keeps the root velocity unchanged. + + The function takes tuples of the form ``(min, max)`` for the radius and angle ranges. + """ + # extract the used quantities (to enable type-hinting) + asset: RigidObject | Articulation = env.scene[asset_cfg.name] + # get default root state + root_states = asset.data.default_root_state[env_ids].clone() + + # poses + range_list = [radius_range, angle_range] + ranges = torch.tensor(range_list, device=asset.device) + rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 2), device=asset.device) + + rand_x = rand_samples[:, 0:1] * torch.cos(rand_samples[:, 1:2]) + rand_y = rand_samples[:, 0:1] * torch.sin(rand_samples[:, 1:2]) + rand_pos = torch.cat([rand_x, rand_y], dim=-1) + + positions = root_states[:, 0:2] + env.scene.env_origins[env_ids, 0:2] + rand_pos + orientations = root_states[:, 2:7] + + # set into the physics simulation + asset.write_root_pose_to_sim(torch.cat([positions, orientations], dim=-1), env_ids=env_ids) + + def reset_root_state_with_random_orientation( env: ManagerBasedEnv, env_ids: torch.Tensor, diff --git a/source/isaaclab/isaaclab/envs/mdp/observations.py b/source/isaaclab/isaaclab/envs/mdp/observations.py index 12e93b69d287..686ccdb3e48e 100644 --- a/source/isaaclab/isaaclab/envs/mdp/observations.py +++ b/source/isaaclab/isaaclab/envs/mdp/observations.py @@ -231,6 +231,22 @@ def imu_lin_acc(env: ManagerBasedEnv, asset_cfg: SceneEntityCfg = SceneEntityCfg return asset.data.lin_acc_b +def image_flatten(env: ManagerBasedEnv, sensor_cfg: SceneEntityCfg) -> torch.Tensor: + """RGB-D data from the given sensor w.r.t. the sensor's frame.""" + # extract the used quantities (to enable type-hinting) + sensor: TiledCamera = env.scene.sensors[sensor_cfg.name] + # tiled camera data already normalized + rgb_image = sensor.data.output["rgb"][..., 0:3] + rgb_image = rgb_image.permute(0, 3, 1, 2) + rgb_image = rgb_image.float() + rgb_image /= 255.0 + + mean_tensor = torch.mean(rgb_image, dim=(2, 3), keepdim=True) + rgb_image -= mean_tensor + rgb_image = rgb_image.contiguous().view(rgb_image.size(0), -1) + return rgb_image + + def image( env: ManagerBasedEnv, sensor_cfg: SceneEntityCfg = SceneEntityCfg("tiled_camera"), From 428831f814b63295369edfcbbc0a468e7de2d56c Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Thu, 6 Mar 2025 01:34:34 -0800 Subject: [PATCH 02/12] adds anymcal-c navigation env with obstacle and camera --- source/isaaclab_tasks/config/extension.toml | 2 +- source/isaaclab_tasks/docs/CHANGELOG.rst | 10 + .../navigation/config/anymal_c/__init__.py | 20 ++ .../config/anymal_c/agents/rsl_rl_ppo_cfg.py | 43 +++- .../anymal_c/navigation_obstacle_env_cfg.py | 234 ++++++++++++++++++ 5 files changed, 307 insertions(+), 2 deletions(-) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index f3001ef174ad..86d9d5572854 100644 --- a/source/isaaclab_tasks/config/extension.toml +++ b/source/isaaclab_tasks/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.10.24" +version = "0.10.25" # Description title = "Isaac Lab Environments" diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 1cb88d71a56a..1c3c3b43c40b 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,16 @@ Changelog --------- +0.10.25 (2025-03-06) +~~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added ``Isaac-Navigation-Flat-Anymal-C-Conv2d-v0`` environment as a manager-based RL env that implements the Anymal-C navigation task + with obstacle and camera sensor in the scene. + + 0.10.24 (2025-02-13) ~~~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py index c03491851dd2..572d659ba6f2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py @@ -32,3 +32,23 @@ "skrl_cfg_entry_point": f"{agents.__name__}:skrl_flat_ppo_cfg.yaml", }, ) + +gym.register( + id="Isaac-Navigation-Flat-Anymal-C-Conv2d-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.navigation_obstacle_env_cfg:NavigationObstacleEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:NavigationEnvPPOConv2dRunnerCfg", + }, +) + +gym.register( + id="Isaac-Navigation-Flat-Anymal-C-Conv2d-Play-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.navigation_obstacle_env_cfg:NavigationObstacleEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:NavigationEnvPPOConv2dRunnerCfg", + }, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py index 043e187af985..942b4ee15d85 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py @@ -5,7 +5,12 @@ from isaaclab.utils import configclass -from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg +from isaaclab_rl.rsl_rl import ( + RslRlOnPolicyRunnerCfg, + RslRlPpoActorCriticCfg, + RslRlPpoActorCriticConv2dCfg, + RslRlPpoAlgorithmCfg, +) @configclass @@ -35,3 +40,39 @@ class NavigationEnvPPORunnerCfg(RslRlOnPolicyRunnerCfg): desired_kl=0.01, max_grad_norm=1.0, ) + + +@configclass +class NavigationEnvPPOConv2dRunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 8 + max_iterations = 1500 + save_interval = 50 + experiment_name = "anymal_c_navigation" + empirical_normalization = False + policy = RslRlPpoActorCriticConv2dCfg( + init_noise_std=0.5, + actor_hidden_dims=[128, 128], + critic_hidden_dims=[128, 128], + activation="elu", + conv_layers_params=[ + {"out_channels": 4, "kernel_size": 3, "stride": 2}, + {"out_channels": 8, "kernel_size": 3, "stride": 2}, + {"out_channels": 16, "kernel_size": 3, "stride": 2}, + ], + conv_linear_output_size=16, + image_input_shape=(3, 64, 64), + ) + algorithm = RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.005, + num_learning_epochs=5, + num_mini_batches=4, + learning_rate=1.0e-3, + schedule="adaptive", + gamma=0.99, + lam=0.95, + desired_kl=0.01, + max_grad_norm=1.0, + ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py new file mode 100644 index 000000000000..6dc77c07d771 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py @@ -0,0 +1,234 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import math + +import isaaclab.sim as sim_utils +from isaaclab.assets import RigidObjectCfg +from isaaclab.envs import ManagerBasedRLEnvCfg +from isaaclab.managers import EventTermCfg as EventTerm +from isaaclab.managers import ObservationGroupCfg as ObsGroup +from isaaclab.managers import ObservationTermCfg as ObsTerm +from isaaclab.managers import RewardTermCfg as RewTerm +from isaaclab.managers import SceneEntityCfg +from isaaclab.managers import TerminationTermCfg as DoneTerm +from isaaclab.sensors import CameraCfg, TiledCameraCfg +from isaaclab.utils import configclass +from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR + +import isaaclab_tasks.manager_based.navigation.mdp as mdp +from isaaclab_tasks.manager_based.locomotion.velocity.config.anymal_c.flat_env_cfg import AnymalCFlatEnvCfg + +LOW_LEVEL_ENV_CFG = AnymalCFlatEnvCfg() + + +@configclass +class EventCfg: + """Configuration for events.""" + + reset_base = EventTerm( + func=mdp.reset_root_state_uniform, + mode="reset", + params={ + "pose_range": {"x": (-0.5, 0.5), "y": (-0.5, 0.5), "yaw": (-3.14, 3.14)}, + "velocity_range": { + "x": (-0.0, 0.0), + "y": (-0.0, 0.0), + "z": (-0.0, 0.0), + "roll": (-0.0, 0.0), + "pitch": (-0.0, 0.0), + "yaw": (-0.0, 0.0), + }, + }, + ) + + reset_object = EventTerm( + func=mdp.reset_root_state_uniform_angular, + mode="reset", + params={ + "radius_range": (1.5, 2.5), + "angle_range": (-3.14, 3.14), + }, + ) + + +@configclass +class ActionsCfg: + """Action terms for the MDP.""" + + pre_trained_policy_action: mdp.PreTrainedPolicyActionCfg = mdp.PreTrainedPolicyActionCfg( + asset_name="robot", + policy_path=f"{ISAACLAB_NUCLEUS_DIR}/Policies/ANYmal-C/Blind/policy.pt", + low_level_decimation=4, + low_level_actions=LOW_LEVEL_ENV_CFG.actions.joint_pos, + low_level_observations=LOW_LEVEL_ENV_CFG.observations.policy, + ) + + +@configclass +class ObservationsCfg: + """Observation specifications for the MDP.""" + + @configclass + class PolicyCfg(ObsGroup): + """Observations for policy group.""" + + # observation terms (order preserved) + base_lin_vel = ObsTerm(func=mdp.base_lin_vel) + projected_gravity = ObsTerm(func=mdp.projected_gravity) + pose_command = ObsTerm(func=mdp.generated_commands, params={"command_name": "pose_command"}) + camera_data = ObsTerm(func=mdp.image_flatten, params={"sensor_cfg": SceneEntityCfg("tiled_camera")}) + + # observation groups + policy: PolicyCfg = PolicyCfg() + + +@configclass +class RewardsCfg: + """Reward terms for the MDP.""" + + termination_penalty = RewTerm(func=mdp.is_terminated, weight=-400.0) + position_tracking = RewTerm( + func=mdp.position_command_error_tanh, + weight=10, + params={"std": 2.0, "command_name": "pose_command"}, + ) + position_tracking_fine_grained = RewTerm( + func=mdp.position_command_error_tanh, + weight=10, + params={"std": 0.2, "command_name": "pose_command"}, + ) + orientation_tracking = RewTerm( + func=mdp.heading_command_error_abs, + weight=-4.0, + params={"command_name": "pose_command"}, + ) + + +@configclass +class CommandsCfg: + """Command terms for the MDP.""" + + pose_command = mdp.ObstaclePose2dCommandCfg( + asset_name="robot", + object_name="object", + simple_heading=False, + resampling_time_range=(12.0, 12.0), + debug_vis=True, + ranges=mdp.ObstaclePose2dCommandCfg.Ranges(heading=(-math.pi, math.pi)), + ) + + +@configclass +class TerminationsCfg: + """Termination terms for the MDP.""" + + time_out = DoneTerm(func=mdp.time_out, time_out=True) + base_contact = DoneTerm( + func=mdp.illegal_contact, + params={ + "sensor_cfg": SceneEntityCfg("contact_forces", body_names="base"), + "threshold": 1.0, + }, + ) + + +@configclass +class NavigationObstacleEnvCfg(ManagerBasedRLEnvCfg): + """Configuration for the navigation environment.""" + + # environment settings + scene: SceneEntityCfg = LOW_LEVEL_ENV_CFG.scene + actions: ActionsCfg = ActionsCfg() + observations: ObservationsCfg = ObservationsCfg() + events: EventCfg = EventCfg() + # mdp settings + commands: CommandsCfg = CommandsCfg() + rewards: RewardsCfg = RewardsCfg() + terminations: TerminationsCfg = TerminationsCfg() + + def __post_init__(self): + """Post initialization.""" + + self.sim.dt = LOW_LEVEL_ENV_CFG.sim.dt + self.sim.render_interval = LOW_LEVEL_ENV_CFG.decimation + self.decimation = LOW_LEVEL_ENV_CFG.decimation * 10 + self.episode_length_s = self.commands.pose_command.resampling_time_range[1] + + if self.scene.height_scanner is not None: + self.scene.height_scanner.update_period = ( + self.actions.pre_trained_policy_action.low_level_decimation * self.sim.dt + ) + if self.scene.contact_forces is not None: + self.scene.contact_forces.update_period = self.sim.dt + + self.scene.env_spacing = 20 + self.scene.tiled_camera = TiledCameraCfg( + prim_path="{ENV_REGEX_NS}/Robot/base/front_cam", + update_period=0.1, + height=64, + width=64, + data_types=["rgb", "distance_to_image_plane"], + spawn=sim_utils.PinholeCameraCfg( + focal_length=24.0, + focus_distance=400.0, + horizontal_aperture=20.955, + clipping_range=(0.1, 1.0e5), + ), + offset=CameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"), + ) + + self.scene.object = RigidObjectCfg( + prim_path="{ENV_REGEX_NS}/object", + spawn=sim_utils.CylinderCfg( + radius=0.2, + height=0.6, + rigid_props=sim_utils.RigidBodyPropertiesCfg(), + mass_props=sim_utils.MassPropertiesCfg(mass=200.0), + collision_props=sim_utils.CollisionPropertiesCfg(), + visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2), + ), + init_state=RigidObjectCfg.InitialStateCfg(pos=(0, 0, 0)), + ) + + +class NavigationObstacleEnvCfg_PLAY(NavigationObstacleEnvCfg): + def __post_init__(self) -> None: + # post init of parent + super().__post_init__() + + # make a smaller scene for play + self.scene.num_envs = 50 + self.scene.env_spacing = 20 + # disable randomization for play + self.observations.policy.enable_corruption = False + + self.scene.tiled_camera = TiledCameraCfg( + prim_path="{ENV_REGEX_NS}/Robot/base/front_cam", + update_period=0.1, + height=64, + width=64, + data_types=["rgb", "distance_to_image_plane"], + spawn=sim_utils.PinholeCameraCfg( + focal_length=24.0, + focus_distance=400.0, + horizontal_aperture=20.955, + clipping_range=(0.1, 1.0e5), + ), + offset=CameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"), + ) + + self.scene.object = RigidObjectCfg( + prim_path="{ENV_REGEX_NS}/object", + spawn=sim_utils.CylinderCfg( + radius=0.2, + height=0.6, + rigid_props=sim_utils.RigidBodyPropertiesCfg(), + mass_props=sim_utils.MassPropertiesCfg(mass=200.0), + collision_props=sim_utils.CollisionPropertiesCfg(), + visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2), + ), + init_state=RigidObjectCfg.InitialStateCfg(pos=(0, 0, 0)), + ) From 2c970f060d9053fb535b8e1f53ce9be0f69a83b7 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Thu, 6 Mar 2025 01:35:42 -0800 Subject: [PATCH 03/12] extends rsl_rl ppo configuration to support convolutional newtorks --- source/isaaclab_rl/config/extension.toml | 2 +- source/isaaclab_rl/docs/CHANGELOG.rst | 9 ++++++++ .../isaaclab_rl/rsl_rl/__init__.py | 2 +- .../isaaclab_rl/rsl_rl/exporter.py | 5 ++++- .../isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py | 21 +++++++++++++++++++ 5 files changed, 36 insertions(+), 3 deletions(-) diff --git a/source/isaaclab_rl/config/extension.toml b/source/isaaclab_rl/config/extension.toml index a631aebc0905..ebc77a2310b3 100644 --- a/source/isaaclab_rl/config/extension.toml +++ b/source/isaaclab_rl/config/extension.toml @@ -1,7 +1,7 @@ [package] # Note: Semantic Versioning is used: https://semver.org/ -version = "0.1.0" +version = "0.1.1" # Description title = "Isaac Lab RL" diff --git a/source/isaaclab_rl/docs/CHANGELOG.rst b/source/isaaclab_rl/docs/CHANGELOG.rst index 2f8d5d040b91..903cb6f72676 100644 --- a/source/isaaclab_rl/docs/CHANGELOG.rst +++ b/source/isaaclab_rl/docs/CHANGELOG.rst @@ -1,6 +1,15 @@ Changelog --------- +0.1.1 (2025-03-06) +~~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added configuration for RSL RL actor-critic networks with convolutional layers. + + 0.1.0 (2024-12-27) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_rl/isaaclab_rl/rsl_rl/__init__.py b/source/isaaclab_rl/isaaclab_rl/rsl_rl/__init__.py index 19314893a62c..e1ea9e94f660 100644 --- a/source/isaaclab_rl/isaaclab_rl/rsl_rl/__init__.py +++ b/source/isaaclab_rl/isaaclab_rl/rsl_rl/__init__.py @@ -16,5 +16,5 @@ """ from .exporter import export_policy_as_jit, export_policy_as_onnx -from .rl_cfg import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg +from .rl_cfg import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoActorCriticConv2dCfg, RslRlPpoAlgorithmCfg from .vecenv_wrapper import RslRlVecEnvWrapper diff --git a/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py b/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py index 94144888719a..458f2dff8ef2 100644 --- a/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py +++ b/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py @@ -137,7 +137,10 @@ def export(self, path, filename): dynamic_axes={}, ) else: - obs = torch.zeros(1, self.actor[0].in_features) + input_size = getattr(self.actor, "input_dim", None) + if input_size is None: + input_size = self.actor[0].in_features + obs = torch.zeros(1, input_size) torch.onnx.export( self, obs, diff --git a/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py b/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py index 697e018b2222..384d77ae20ff 100644 --- a/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py +++ b/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py @@ -29,6 +29,27 @@ class RslRlPpoActorCriticCfg: """The activation function for the actor and critic networks.""" +@configclass +class RslRlPpoActorCriticConv2dCfg(RslRlPpoActorCriticCfg): + """Configuration for the PPO actor-critic networks with convolutional layers.""" + + class_name: str = "ActorCriticConv2d" + """The policy class name. Default is ActorCriticConv2d.""" + + conv_layers_params: list[dict] = [ + {"out_channels": 4, "kernel_size": 3, "stride": 2}, + {"out_channels": 8, "kernel_size": 3, "stride": 2}, + {"out_channels": 16, "kernel_size": 3, "stride": 2}, + ] + """List of convolutional layer parameters for the convolutional network.""" + + conv_linear_output_size: int = 16 + """Output size of the linear layer after the convolutional features are flattened.""" + + image_input_shape: tuple[int, int, int] = (3, 64, 64) + """Shape of the image input in (channels, height, width).""" + + @configclass class RslRlPpoAlgorithmCfg: """Configuration for the PPO algorithm.""" From 6f7857962e27fe38d8f1efb5d71b888a940df7f5 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Thu, 6 Mar 2025 01:36:48 -0800 Subject: [PATCH 04/12] adds convolutional networks and ppo runner to rsl_rl libraries --- .../rsl_rl/actor_critic_conv2d.py | 229 ++++++++++++++++++ .../rsl_rl/on_policy_runner_conv2d.py | 67 +++++ scripts/reinforcement_learning/rsl_rl/play.py | 15 +- .../reinforcement_learning/rsl_rl/train.py | 15 +- 4 files changed, 324 insertions(+), 2 deletions(-) create mode 100644 scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py create mode 100644 scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py diff --git a/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py b/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py new file mode 100644 index 000000000000..f1ef5f831d56 --- /dev/null +++ b/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py @@ -0,0 +1,229 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import torch +import torch.nn as nn +from torch.distributions import Normal + +from rsl_rl.modules.actor_critic import get_activation + + +class ResidualBlock(nn.Module): + def __init__(self, channels): + super().__init__() + self.conv1 = nn.Conv2d(channels, channels, kernel_size=3, padding=1) + self.bn1 = nn.BatchNorm2d(channels) + self.relu = nn.ReLU(inplace=True) + self.conv2 = nn.Conv2d(channels, channels, kernel_size=3, padding=1) + self.bn2 = nn.BatchNorm2d(channels) + + def forward(self, x): + residual = x + out = self.conv1(x) + out = self.bn1(out) + out = self.relu(out) + out = self.conv2(out) + out = self.bn2(out) + out += residual + out = self.relu(out) + return out + + +class ConvolutionalNetwork(nn.Module): + def __init__( + self, + input_dim, + output_dim, + image_input_shape, + conv_layers_params, + hidden_dims, + activation_fn, + conv_linear_output_size, + ): + super().__init__() + + self.input_dim = input_dim + self.image_input_shape = image_input_shape # (C, H, W) + self.image_obs_size = torch.prod(torch.tensor(self.image_input_shape)).item() + self.proprio_obs_size = input_dim - self.image_obs_size + self.activation_fn = activation_fn + + # Build conv network and get its output size + self.conv_net = self.build_conv_net(conv_layers_params) + with torch.no_grad(): + dummy_image = torch.zeros(1, *self.image_input_shape) + conv_output = self.conv_net(dummy_image) + self.image_feature_size = conv_output.view(1, -1).shape[1] + + # Build the connection layers between conv net and mlp + self.conv_linear = nn.Linear(self.image_feature_size, conv_linear_output_size) + self.layernorm = nn.LayerNorm(conv_linear_output_size) + + # Build the mlp + self.mlp = nn.Sequential( + nn.Linear(self.proprio_obs_size + conv_linear_output_size, hidden_dims[0]), + self.activation_fn, + *[ + layer + for dim in zip(hidden_dims[:-1], hidden_dims[1:]) + for layer in (nn.Linear(dim[0], dim[1]), self.activation_fn) + ], + nn.Linear(hidden_dims[-1], output_dim), + ) + + # Initialize the weights + self._initialize_weights() + + def build_conv_net(self, conv_layers_params): + layers = [] + in_channels = self.image_input_shape[0] + for idx, params in enumerate(conv_layers_params[:-1]): + layers.extend([ + nn.Conv2d( + in_channels, + params["out_channels"], + kernel_size=params.get("kernel_size", 3), + stride=params.get("stride", 1), + padding=params.get("padding", 0), + ), + nn.BatchNorm2d(params["out_channels"]), + nn.ReLU(inplace=True), + ResidualBlock(params["out_channels"]) if idx > 0 else nn.Identity(), + ]) + in_channels = params["out_channels"] + last_params = conv_layers_params[-1] + layers.append( + nn.Conv2d( + in_channels, + last_params["out_channels"], + kernel_size=last_params.get("kernel_size", 3), + stride=last_params.get("stride", 1), + padding=last_params.get("padding", 0), + ) + ) + layers.append(nn.BatchNorm2d(last_params["out_channels"])) + return nn.Sequential(*layers) + + def _initialize_weights(self): + for m in self.conv_net.modules(): + if isinstance(m, nn.Conv2d): + nn.init.kaiming_normal_(m.weight, mode="fan_out", nonlinearity="relu") + elif isinstance(m, nn.BatchNorm2d): + nn.init.constant_(m.weight, 1) + nn.init.constant_(m.bias, 0) + + nn.init.kaiming_normal_(self.conv_linear.weight, mode="fan_out", nonlinearity="tanh") + nn.init.constant_(self.conv_linear.bias, 0) + nn.init.constant_(self.layernorm.weight, 1.0) + nn.init.constant_(self.layernorm.bias, 0.0) + + for layer in self.mlp: + if isinstance(layer, nn.Linear): + nn.init.orthogonal_(layer.weight, gain=0.01) + nn.init.zeros_(layer.bias) if layer.bias is not None else None + + def forward(self, observations): + proprio_obs = observations[:, : -self.image_obs_size] + image_obs = observations[:, -self.image_obs_size :] + + batch_size = image_obs.size(0) + image = image_obs.view(batch_size, *self.image_input_shape) + + conv_features = self.conv_net(image) + flattened_conv_features = conv_features.view(batch_size, -1) + normalized_conv_output = self.layernorm(self.conv_linear(flattened_conv_features)) + combined_input = torch.cat([proprio_obs, normalized_conv_output], dim=1) + output = self.mlp(combined_input) + return output + + +class ActorCriticConv2d(nn.Module): + is_recurrent = False + + def __init__( + self, + num_actor_obs, + num_critic_obs, + num_actions, + image_input_shape, + conv_layers_params, + conv_linear_output_size, + actor_hidden_dims, + critic_hidden_dims, + activation="elu", + init_noise_std=1.0, + **kwargs, + ): + super().__init__() + + self.image_input_shape = image_input_shape # (C, H, W) + self.activation_fn = get_activation(activation) + + self.actor = ConvolutionalNetwork( + input_dim=num_actor_obs, + output_dim=num_actions, + image_input_shape=image_input_shape, + conv_layers_params=conv_layers_params, + hidden_dims=actor_hidden_dims, + activation_fn=self.activation_fn, + conv_linear_output_size=conv_linear_output_size, + ) + + self.critic = ConvolutionalNetwork( + input_dim=num_critic_obs, + output_dim=1, + image_input_shape=image_input_shape, + conv_layers_params=conv_layers_params, + hidden_dims=critic_hidden_dims, + activation_fn=self.activation_fn, + conv_linear_output_size=conv_linear_output_size, + ) + + print(f"Modified Actor Network: {self.actor}") + print(f"Modified Critic Network: {self.critic}") + + # Action noise + self.std = nn.Parameter(init_noise_std * torch.ones(num_actions)) + # Action distribution (populated in update_distribution) + self.distribution = None + # disable args validation for speedup + Normal.set_default_validate_args(False) + + def reset(self, dones=None): + pass + + def forward(self): + raise NotImplementedError + + @property + def action_mean(self): + return self.distribution.mean + + @property + def action_std(self): + return self.distribution.stddev + + @property + def entropy(self): + return self.distribution.entropy().sum(dim=-1) + + def update_distribution(self, observations): + mean = self.actor(observations) + self.distribution = Normal(mean, self.std) + + def act(self, observations, **kwargs): + self.update_distribution(observations) + return self.distribution.sample() + + def get_actions_log_prob(self, actions): + return self.distribution.log_prob(actions).sum(dim=-1) + + def act_inference(self, observations): + actions_mean = self.actor(observations) + return actions_mean + + def evaluate(self, critic_observations, **kwargs): + value = self.critic(critic_observations) + return value diff --git a/scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py b/scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py new file mode 100644 index 000000000000..9f11a8d38936 --- /dev/null +++ b/scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py @@ -0,0 +1,67 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers. +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from __future__ import annotations + +import torch + +import rsl_rl +from actor_critic_conv2d import ActorCriticConv2d +from rsl_rl.algorithms import PPO +from rsl_rl.env import VecEnv +from rsl_rl.modules import EmpiricalNormalization +from rsl_rl.runners import OnPolicyRunner + + +class OnPolicyRunnerConv2d(OnPolicyRunner): + """Custom on-policy runner for training and evaluation with convolutional actor-critic.""" + + def __init__(self, env: VecEnv, train_cfg, log_dir=None, device="cpu"): + self.cfg = train_cfg + self.alg_cfg = train_cfg["algorithm"] + self.policy_cfg = train_cfg["policy"] + self.device = device + self.env = env + obs, extras = self.env.get_observations() + num_obs = obs.shape[1] + if "critic" in extras["observations"]: + num_critic_obs = extras["observations"]["critic"].shape[1] + else: + num_critic_obs = num_obs + + # init the actor-critic networks + actor_critic: ActorCriticConv2d = ActorCriticConv2d( + num_obs, num_critic_obs, self.env.num_actions, **self.policy_cfg + ).to(self.device) + + # init the ppo algorithm + alg_class = eval(self.alg_cfg.pop("class_name")) # PPO + self.alg: PPO = alg_class(actor_critic, device=self.device, **self.alg_cfg) + self.num_steps_per_env = self.cfg["num_steps_per_env"] + self.save_interval = self.cfg["save_interval"] + self.empirical_normalization = self.cfg["empirical_normalization"] + if self.empirical_normalization: + self.obs_normalizer = EmpiricalNormalization(shape=[num_obs], until=1.0e8).to(self.device) + self.critic_obs_normalizer = EmpiricalNormalization(shape=[num_critic_obs], until=1.0e8).to(self.device) + else: + self.obs_normalizer = torch.nn.Identity().to(self.device) # no normalization + self.critic_obs_normalizer = torch.nn.Identity().to(self.device) # no normalization + + # init storage and model + self.alg.init_storage( + self.env.num_envs, + self.num_steps_per_env, + [num_obs], + [num_critic_obs], + [self.env.num_actions], + ) + + # Log + self.log_dir = log_dir + self.writer = None + self.tot_timesteps = 0 + self.tot_time = 0 + self.current_learning_iteration = 0 + self.git_status_repos = [rsl_rl.__file__] diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index f53f3b6e17e0..0da6231290c9 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -49,6 +49,7 @@ import time import torch +from on_policy_runner_conv2d import OnPolicyRunnerConv2d from rsl_rl.runners import OnPolicyRunner from isaaclab.envs import DirectMARLEnv, multi_agent_to_single_agent @@ -110,7 +111,19 @@ def main(): print(f"[INFO]: Loading model checkpoint from: {resume_path}") # load previously trained model - ppo_runner = OnPolicyRunner(env, agent_cfg.to_dict(), log_dir=None, device=agent_cfg.device) + if agent_cfg.policy.class_name == "ActorCriticConv2d": + if ( + env_cfg.scene.tiled_camera.height != agent_cfg.policy.image_input_shape[1] + or env_cfg.scene.tiled_camera.width != agent_cfg.policy.image_input_shape[2] + ): + raise ValueError( + f"Mismatch in camera dimensions: tiled_camera.height={env_cfg.scene.tiled_camera.height}," + f" tiled_camera.width={env_cfg.scene.tiled_camera.width} must match" + f" image_input_shape={agent_cfg.policy.image_input_shape[1]}x{agent_cfg.policy.image_input_shape[2]}" + ) + ppo_runner = OnPolicyRunnerConv2d(env, agent_cfg.to_dict(), log_dir=None, device=agent_cfg.device) + else: + ppo_runner = OnPolicyRunner(env, agent_cfg.to_dict(), log_dir=None, device=agent_cfg.device) ppo_runner.load(resume_path) # obtain the trained policy for inference diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 95ca95f47fa3..664071b08a6d 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -49,6 +49,7 @@ import torch from datetime import datetime +from on_policy_runner_conv2d import OnPolicyRunnerConv2d from rsl_rl.runners import OnPolicyRunner from isaaclab.envs import ( @@ -127,7 +128,19 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen env = RslRlVecEnvWrapper(env) # create runner from rsl-rl - runner = OnPolicyRunner(env, agent_cfg.to_dict(), log_dir=log_dir, device=agent_cfg.device) + if agent_cfg.policy.class_name == "ActorCriticConv2d": + if ( + env_cfg.scene.tiled_camera.height != agent_cfg.policy.image_input_shape[1] + or env_cfg.scene.tiled_camera.width != agent_cfg.policy.image_input_shape[2] + ): + raise ValueError( + f"Mismatch in camera dimensions: tiled_camera.height={env_cfg.scene.tiled_camera.height}," + f" tiled_camera.width={env_cfg.scene.tiled_camera.width} must match" + f" image_input_shape={agent_cfg.policy.image_input_shape[1]}x{agent_cfg.policy.image_input_shape[2]}" + ) + runner = OnPolicyRunnerConv2d(env, agent_cfg.to_dict(), log_dir=log_dir, device=agent_cfg.device) + else: + runner = OnPolicyRunner(env, agent_cfg.to_dict(), log_dir=log_dir, device=agent_cfg.device) # write git state to logs runner.add_git_repo_to_log(__file__) # load the checkpoint From fcbdcf812c291b98468044fa8849d2cb15adc36a Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Fri, 7 Mar 2025 02:31:23 -0800 Subject: [PATCH 05/12] change to resolve_nn_activation to adapt to latest rsl rl --- scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py b/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py index f1ef5f831d56..49ef69efe038 100644 --- a/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py +++ b/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py @@ -7,7 +7,7 @@ import torch.nn as nn from torch.distributions import Normal -from rsl_rl.modules.actor_critic import get_activation +from rsl_rl.utils import resolve_nn_activation class ResidualBlock(nn.Module): @@ -159,7 +159,7 @@ def __init__( super().__init__() self.image_input_shape = image_input_shape # (C, H, W) - self.activation_fn = get_activation(activation) + self.activation_fn = resolve_nn_activation(activation) self.actor = ConvolutionalNetwork( input_dim=num_actor_obs, From a88553cc04d4f4be6f89a8466f6a383b333b5208 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Fri, 7 Mar 2025 02:32:25 -0800 Subject: [PATCH 06/12] rename the env as Isaac-Navigation-Flat-Obstacle-Anymal-C-v0 --- source/isaaclab_tasks/docs/CHANGELOG.rst | 2 +- .../manager_based/navigation/config/anymal_c/__init__.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 1c3c3b43c40b..172833e8f5df 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -7,7 +7,7 @@ Changelog Added ^^^^^ -* Added ``Isaac-Navigation-Flat-Anymal-C-Conv2d-v0`` environment as a manager-based RL env that implements the Anymal-C navigation task +* Added ``Isaac-Navigation-Flat-Obstacle-Anymal-C-v0`` environment as a manager-based RL env that implements the Anymal-C navigation task with obstacle and camera sensor in the scene. diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py index 572d659ba6f2..eb671975942c 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/__init__.py @@ -34,7 +34,7 @@ ) gym.register( - id="Isaac-Navigation-Flat-Anymal-C-Conv2d-v0", + id="Isaac-Navigation-Flat-Obstacle-Anymal-C-v0", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ @@ -44,7 +44,7 @@ ) gym.register( - id="Isaac-Navigation-Flat-Anymal-C-Conv2d-Play-v0", + id="Isaac-Navigation-Flat-Obstacle-Anymal-C-Play-v0", entry_point="isaaclab.envs:ManagerBasedRLEnv", disable_env_checker=True, kwargs={ From 4ffe9d261f8a50b14ccbf47ddfc449de8dcb6cf9 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Fri, 7 Mar 2025 02:33:12 -0800 Subject: [PATCH 07/12] update contributors and environments doc --- CONTRIBUTORS.md | 2 ++ .../navigation/anymal_c_nav_obstacle.jpg | Bin 0 -> 125205 bytes docs/source/overview/environments.rst | 18 +++++++++++++----- 3 files changed, 15 insertions(+), 5 deletions(-) create mode 100644 docs/source/_static/tasks/navigation/anymal_c_nav_obstacle.jpg diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index deca7c88f9b9..eb5ecf470c1c 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -56,6 +56,7 @@ Guidelines for modifications: * HoJin Jeon * Hongwei Xiong * Hongyu Li +* Hui Kang * Iretiayo Akinola * Jack Zeng * Jan Kerner @@ -65,6 +66,7 @@ Guidelines for modifications: * Jingzhou Liu * Johnson Sun * Kaixi Bao +* Kingsley Liu * Kourosh Darvish * Lionel Gulich * Louis Le Lay diff --git a/docs/source/_static/tasks/navigation/anymal_c_nav_obstacle.jpg b/docs/source/_static/tasks/navigation/anymal_c_nav_obstacle.jpg new file mode 100644 index 0000000000000000000000000000000000000000..6d25b9770b833018a51a4d78ae95cc85ceda5d8a GIT binary patch literal 125205 zcmbTdbx>Ph7%h4rSdmg(ODHad;#Ra2cS&#!uEnibTPVf75Zv8eik0FNPjQMn6nD7! z-FxTWnfKRw?_@HQnVdPZ*PQ+By}q^9ewuyy3%pR2RgeWxP*4C<*Gc z#lgbG$im9<-$PI^F)^{Ru!*p-iC8E}DOvtMUr${C0T$>BdNv4!4nQS90TG})^#Wi3 zKtV^2_P+uD?+XPLgd8s>)-!Az!UqV8^hJ6cbJXLs-9^z8iN^6L8L_CH)G0O)_g z`aj72AGipRxKPp1Kxml%;X*<6LViI6Xy~uFF$kqJFwIE9X$Ol~{d_8dOtUx3G`b=wD+<6D>ld*BYJ0A6a0jbrp^o%-twx_e@N@u^n?v83%JFf{BZaf51nsfSi4vF7!UlN~j zWE*0A6WZ51|4aTaJF6#_ZnNP&xfZi&$n@m15w-ZM&zezY(|M2&LP;)JeJ!tuGQ;g; z8sl0|WP<)6+}p~`w%;%Nw`^Ld&V>E$z2L7ZGBLD`e7@;DcoUnx0c}tAg*KfnDAKly z!I*(@OmLQ_&AxtXNX#ttFBc+IAxuQ^vrqU*m<=F0?EY+tBw;hRd#3z5!@Q85X%+T5 z%P1};C8&gV$n8`Qf19&{%TW=DcD(PI%JCRq&<+RxTRpPjX&51=_?3%l$CTqT_^s;0 z+7sZ_TC(da~ZyRt#Kwsh_y6jNCX5kG7r@v&j%sUnE?|QFUx_{CAi%-Bs zDY$_xuQ z1;?g*U`Q*(2+{2gW&XoYp2B*g?MDf~w^du4Hdh@p(kMub%&m6ylZ{`sH5f%SOcf%C z6&NeC7lKb2#o8!=+(rjEPISJWh@U?cJYX)*Hk?f$8xYELVEE2TeUnQsf73@pF&L`aNI%)5G>A z?g8&J`X_*?Or@}Jg;zO_lW0nU>z<{V`UyyQMS(SYtF_*cbjw<%wPf_pQ$Cb;M~6hE z(2JQVh@&uF_v2~qiSmn|6b~EiF-KRWmf!YND8$cE>g-FT?F7D@$>o&bU4(SMt++3| z(C_Ah75M^-9$8lVI#3gtzX-$AvG$vg&wf+pyssA1zOL%5wfkTU7fY9{i{YX2dez*G zs{Ho1_qMrg(l}~t(GENk23?dA*&aKsbYjw!4czaLgp0Ah?r$3tW@-Bz6+LU0#JGV`A6P5$7Dh)i zh7=yV|015dEhib448`NuWaC_U_Wk*0>LH#F(GXt_lb~#|FE@NIFxY7G1T!$vF+>$R6G7A$V z9$VX9e&*TCm$`*YIb$~+Gg14h(~(zNhTX>#T+bx6M{7ldea_NAq|@|pxt8}Ma>;DI zUb%3-wNU5jzx?P$y}-*V(eo2EFG0Rddc>NhxllasEiNb~yYN@BVgHqdgtX*01J&7< zcnDhHbK8iQrLH5ox7t|_q3e(0c|QYvybB*fg>?j`*uh6l7{TFA9FPyOXM1+szB)&A z;h*e%%!J(Omvgs*IF$T&{~4SXe0tmh-L<6qS(UNX?BK7e>gF>af%}5^h_uh}Z!MI# zF2n*w0^?vFBbq*V4+siyhNhCBlisHX73TQj6~52WYeCFeO3g7TT}l4x8xSU0=}=Aa zJdzxH-{d0hI?^(Qit?z(?@sY=DuuIgEu+R@H`?DE={*5IM0>pcvJ2XZwHRvkZ@Z|z zEHALs7XBrc#85<7RK+{o_Rs$ci<`6tnaWzLg-pBdBDDfd3TWT>SHJ%`hz46OuWWd= zX0z_xQ_E@tl2!QI@-g0=c?uq_B)CuX4YOvege_SJNH{N95BHE@tG;KUpz7QGS%%+} zY9O$-Ipwe*5Lj<}>{vv@@E!I9)Vi{O2qUcv?cMce8T|5MhXR^QH4VuXo;hIV(2k?O z{{-Ejhy5Y3Tb|$jpmB+>X&Y~+ReLx9nuS;;%kK4#WBg6*m2C6gyggIXtJlLner4gb z;eKD1!I0(40t%3)U25&l^EjaT3~{ph5oDHULDN&)O}jzaf>Gc`hH~{LCmVZAG`io7 z>)v%)>sanlMa;dqlE<+KG+`1B433iI-g2xp5gZ{)qnNS&)WBi1 zejMG>)A&nxbyIwBLx|69)+E5ED8WN6png77;=Y%#XOm=*-u{UQgn9^%o&#l1H@)Po%KI8$&4LRlt z20IQn)r(Ni@aAXmupTRNxQ1l0=-jJ8sye{;USjR_7n=V22sP0<{sWdsg9oU!d8kH!4*} zyg8rM=`h5+<)ZXcI=$yk{v&Z$Ey6i#soLxiGA~SY%sMt%7`klboJevDZx-y$8%>fw z-mx7=Nmyxd^pC3#u*0w(QS5>pvvV(5xdNVb0bON1fYHneEJ9e9Bo9JJWmudPIF63hB?y9{EtdJbU@0@Eba769)CROLsRuERD<+orRe%2pvVz?ot zZ)(++nZX+2X$LY|?(uAQRzcLY`U+R;EdDZd^D^vfta6REFjALoA8VmQWrJ?;ZSl0< zI9j}|jv~*CxY=Mu_d!_9#|_zz3*4qFLJwC=Q`RS7UaJ<}6F09W8%@eC>WuK5DqmJy z+0<7nd2MOzc=a9{x7HBX>GjH_0+3@o7@HZm)e@h0b2aM!6<1nAl_g?ll>^FQJ}Rm4EtgE-c5={i)Bj2X5;;jz>2gt+%v{2J zl8sZHPf*RInt@eWr2OaLh$G-<>6^Fk}o!{n9p)6N)1rX1Z+d)rEaw7Qb@X(3vCyu#;2bEJDe++ zzQuRW$IrWxqfAk_n8O>Ucenh#3%1QLvDC9$jgqQa4XgQ5{ z$1Ir^V&!r!ivJvR`wa3IU{rH*JdPE=NfE&mgO;uAs!*Hzd7iy;R-HzX8;uIs2+Uwx zO1dk}`&TT$br8sgtSy=sQ!jQoEnw+usaq|N^icX5xKui9U)7#4Yo7to#38{UdII(f z!sVhq)05E0${0lBSUN8c;ZJ70s)O8sh$M9!#~bq z{pKAgH*=$Wm<|4ARC9v9lu+`m88cRmIMkZIzKjW>Nwr+gl*Z2K#d2?-Lx#{_H~))c zAL)Oxh~O+MT$&Si9VOUV|G~wUrY+kWAFQTbtJa~{kt7u(-l?w$w4N=LJS_Uqoaf#- z-!@MNkjPY0mF?K}Sy&fBAj#E-k^0nov=Ez0qd?Xo9pnDhtJ} zxK%FxA{;lrAV!Ba{RmV}lT?+UnHeQ=&b?2-kFb-5VuEi|`-;Su7_ADlQ_i)BNcw;_ zp{?3V(S6xhYdAYDl0#DDPr$PhO@!<@abI&>v>fJq%6|+RP(>_=--XNQ65o$z6+nOc z!ZjqxG*=xL#ab+BZxO$m!jc_iiY4QVRIWF4_~FKGT@Ne-(~G+&%d!?zj8Nk?s^Ut| zHQ~RGwPmdNjkc@)WmZB0;#48aOL17UJ&x|q6RiMPR$hE-Y8nhT36AS((A z{F;)+1(uDCDbd+Kxfbde86D+JM(~i<5sA)70_1`WTUd^|Bm!0z0~!)8M>tV~HT-iW z7m~s=dnr*jhb!o|79THMAn)acJS*5GUKsYG8U{Ry!tAFD_?Dy@$rpzFXcFx(>>^Ct zH{da&G7@waeluyKbZbjq!CNv9o8_liq8sWwV+&w%0Oh<`-x~IZxa+z1C`;7XzpSAk zvXKt~C*UZ(&+2fAj)gxHEye5gsbfRUx6@-q?XaszbTU*ej)JjeY2vTVyUO2{KeVly z(cMwX|82y)ir<)yaKo$n3?h^($z9`}XV&`kMYEhU@C#y5f5T$U&%#W>bz=D=qG~g9 zSf*<4^a;Pi|4X6*yWS3Q8 z^KQx7$d6v0qq>U!Bvy?2^@na#OLIsaQPY%g8R4Kc#lyVw?Ics)CVo64YV5Frw-aDc zW*IOC!aOgF$TcwRZ>0*RdICK5u?+@a*2Rh^5hN{?W&I8kU>u)+uJ`%P9aEXYr7q^8 zqyz3`9HQ<~E@tNyuY zmHINT)0B18vFW%uAFac(d}W^q=34FRc{r#@~rKY&yn{kL!hTOIcVE9#|HKaB{VjP}!C$Bu$7GiNh3%h|jvS|9E z27C(Qo2R1q!!2(v9;KmBs7&T=Y2+WJ6OFJH-=l1MnKZ%%9+?%dN6BJP{ko;enlz!m zB1MSazQA&@OhiBz)jIuE_qS84Ug9%@uYMl@yBdur~A%h^~! z3KNA6{U7AdnMt7bKHB#yg6oiO`a(OKBZinfZ~^eXD>{1;GU2v$!XSAUJgOJo#~yNn zpBy-!jSDxtI@X`GDUWCym8JQVV`KVF^9>FB1{s;lI*j}FOqonR%a#A$ zw$^CiLENMOunj#+q)JHul~8MSj23j>H@b_5)`<3tlJc!o0M05!?`w{l=rk@$)kIHF z(WC;gbK^zM&Ba5@e-J=RA?z>rN z`XYieZYO8v_~v?!G=2omkpT7S={|36)Y0tei)4jwXF}RPnsu2Sv1w0k&9w{_Ulsjy zw8`4v8k-EF)ua7*{H|y|pVZj)VQ>tQ#c&y$wfL)Tae}Feo>n(WYgdv`E@!FvE)T44 zzdP)-vde>Vz*e<@WXAQMPxv|=y`BJl!3P`Eg~lvmn0Z~(582k7ur=~ne{ITdl=I5R zMuiCnJBMNU<57y=Yk|vK z1$TA|kF6x)>)|b{Iq{FYw()q3}tYn31o0Y=l^Q5+bHHgXM-wSC?_; zs5yGMv03~ES-wR|lBDe^CPxZmIfa9E`vcuz{VG*LuAROhyhxFXS0ql)m_^ZE;}@5W z?;dhvXzTV@&~kT*7}CtNw+3WTXZ>iwoQ2)nf)6GH9ASFm^<9JEZ$s&aaV02c>g(IJ z&t8tdxq}#Qt2e_Mw1)ey?8Ox}KOTGDs{l@NOqoFs)tF9Mj9`b!i9i>W#kbXC7nOd( zxv^B9I;6KV)s1aEhA5|<6>hg7UoKq}lgOXtUNMhD zlqc2EKaH2%Xjfkq;UuZGekvX3y~uvH*^+sr{LII6uLB6u~3!7Va<*-Wo6u+O8 zedz$&Y|mggaCS7^xn1B6zx>py*^n)zd{CnkeLjztzUzciHQstU938$N7&Cy;+1QT@PH&NE1K6cwJO zVc_W%yVAd5QmFf{7FGb5r*25}+6h=W<-_NvKZ<$Tb=Xy2xiI2s!cd4WMvh6J_ z1b>fxV9j5slHri)Dv7+EN+Lhkx`8CMzF(y?=}Wm%^#wYmWV#$a45@0HhA&L_@2?KiBEjF+>X^LE`Rs@gDf5( zI`(RvZ;GC#Fqo=IhF?V2kn8sdzNQUorQ34kgWahv_{R3N{WbjiL1SE{MS9J-J}?Hg z6xNFAt3UJ*usE&M8jo+p*V z;w%jFnsI$vPR|?jGep)-CPLmk;LnFz4U3X!c~z#F6x>P#Q#L5=hyqj)LYrb+nJby z-6SbjvXf%?CF~xllRCSwKkSk}@}WoBQ$a;3qAvR>z3kiY0MZ zl`51z=a>Fz#e}P2!l8&+6{RPq7s%?rq97~1{Z$g{`w6K(58I7V-n3@xcr5v-s1CvWCf-o7lpohj$BasBm{ zyRa;~itbX!UILV^x;fyTsUKX@s1acanG@2}8V^sbO!He@Xt^(qpM^bGgmuR7(@R+s zZjZk9FGg|V^9$?S;pXvVal3_JgvvPZIpOCRLX$emE@d%rPxke#d#e{Khuc`v8aLJP zcO}VR%#OZUG7JzZO2d%8>(|iV!s6`PXYXW!lkZEq6J(5<=(9>~V*ceW~3 zj*s_8m)lzCTWO2&d}Gqf?RYUB5$SSQ@| zs-xwunBAn~=ajiDR~G*AIP%K3XgE@}?l|Kqu?ukTy8RYF8Jm zDEyKIBj$jo<<_mK zkLOVuPQpktNRacu@le+M;R&E#E91=Dh-6?B&n@nEd2PMv29?=sM)ih#tz@B~ZaR~n zTZ+7OFV?rEI_Bng9%x8ah#CS*Pv*w=cu)XB$XXsp*JssJOy{DV1k|J?pX*rOmCG1@ z*2?5u{hC99=9wVRLk3#THxMhjs%49@1L`i@3__m(`LDJ|(4=z5B8i>4vspp?%6&)h zyRr9P_GGv9pnutz!v)4NPr&O4{7awW(Jw>1EG%NzB|18-vNsG4zS_s-X(7+NC|mDv zDS_hHF8pJL`w~j|7mtT-7iEqZ86sA!G|cBtGSW;5ABa9OGO1mvU5}%=nh-W?qh|9C z1V#||%gVkACY}e9tYZTSN^(2g@4C3IO0$N-fgf87Ln}XwIu)fIslWIT;`f!Z@%qm& zRT#_~DUI03zTFCcbe~*p`7crbM!NcUm9^$3~0UU&UehjC=`>+^mjJ|Vm=u8 z@($+j^sPKE%WvTR{iB>}AK_nx_a&*g_SXJ{y?`wjIukB(b<3Zemt&h0NrV9Q{-rp1 zcWVP`nryD?YP${WCz{+cF8X6s30z3nv9;PdgWpWS zG^s|dF3Cd|(v5v|NAl!-#Aaivv*(vk8?{cw_u~=rl9>XasS3b6zPhU{+~+jZVtN!{D6t;%vL66lS3u?G@>RoO_bVDSpscwMckE9*-a z$Y*OCn@2{NrX0fip8zpiNccHJ03V90XDeoGAa?1&#{JExm=hyrDD&*}ih~Y$GNT<( zaxq|hCpDGCQHylV5TJp*!! z;vcNk8KaOtVw9rrZy`OjN0>}sMLb$=2ny-jTqFs8;Wc#kVB#IH4S9QR8Ip$|A~oEg z;{2JuuEu{1rd~*izA?{T?RFa+1t87P#+8#RPKhPq(nH3Ay2m4)>&FYNJNJ#KNnRMD z$ViI96S)X+ZoaNY!lmiINqjR6OG6@Xd55jhOi zV>%=Xrs!vVX38XwHDKzdhZ&s*2RfK)Bk!w|Z?hg7*!P|xtFdBTdJo-N^XgC=y>HqH zU$%dIn#XYX)o=?x>7*~~J-V1Fl1iZDg9O1^H{;K!KZmF2x9kUB@YBt6@=T%};L!@y zo4g>2I1q_FtDp+feVF>V1M78|CjsJON7@SN2%>I5UI%WjXev1%tt7J*pIHE|TOj z@b<8)AR9 zwo!Vb=JY8XB18&ldofXYK}TZSVeEae!9Ii~x64p49D|UAgvhYX7k^hhfUlW3oB3Zp zMn^`K(R>WY;^4EtWt4RuX3z6+FY&*MrtIUHC3Wm^-?NRv4S&+weA5)OLCueA*ChF% zeHU)&F(G4Liub*|M%9-~6zcI9*68H+%KP>ca&spEOTmA%PSOVz>Q~tc}eG8 z-vwJI(fHpP6RiYBAeH?6ngnNJXj95xm(WK@msXx9Qto~sC#sIoS4OfKkr;<%Jc5Z) zJHKT`enzzmU!H20)aP%SR#(DTjvFXi@%HB=9xLcfDT)s|WepxBWsX;2-qsql=2L5w zAIfr3y3`^6jSfI_D;|=_j^)wG8;v)Mn@L!^6?UGL$$CRR#67zI^hR1t05W$#q^IEJ zNbB8%vfMD?=t1&pT-Q>f?=1pkH1rc~+F;?X54qQz6FIcqcQg1)87IMemegGRcQ1X@ z5!+}-($kdf=C#wZFmdIg8ZjHt+e3}gRWrleDV2?so{UaKgJFt_v@OG`s}RU8B8b6u z!>K$Fq!F)H@t=+pi0#|W?mz836a_>_UY2RhDsNK>Jg6x19RyY+k)32?Bfh)o%hNog zpqgE4%0+N^pr2mol4NBkB2z3I^UN!WO_K?~8&pwA^U?3B@CW`57fH<1?FR{yBsx@r z9Boo)(!?{hI{Is)$g9 ztXQ*cKl)@gq=^!~Td;iB!1qCc3e?QJuHSf7<9K@9IF$Kg2ZWl4>Zc>en4BuKV#&$y zxK26ROlUx3M(ewlLQKdCJ}Tkos{h^$+Lvlexc-`7XICi+{b(N?OL zeF7aX^HtYcF>Ch#v-nI2tlVe;ujP#XaUXXaLl2xmGKp3_!$nE&%z7lEtwTfJE@}LN zF=j@d?+8;u2AS5d4qI?Itd7nepP1_tcHN$g2+kBM*(d76E?)^TBJ(_nWT1VpEz(R3 zEW^&*l}C&2*)G=1n?BJO2wA(~EP$%+`ILWiW==R3E>_~+Qvuv7ob!IK?Bl8&Mrsop z^gAdt1v`=5&5oLCUtYO(1$tgzU7xrteOl03uN)Pt^FnM$cuwOO!E->+DtqiF%he~S(B2IkVF^UhAuENNx0Pr2X}nYrX?D;YI-%D-ALY* z;y2wnpUe~KpDw$c8%#c-XQ=X6DIgJ|%r}R5i+F!Arr*Yz@!g|*NUp$g5hq9?QE+;k zXJ21mR>DX8*i6|VLMUzHYapU7pnU?4W~)%b?Ytyg6Jtkn@l)1tGA>3m*c z7tv_1owgWllYG?YAz`gn2bR($uE(87Ufw9N*?69HKw}pfJiR6Wn=R}KSd~o9uqvU#+Yt~eYyF(@B`4yEvKT2b=m0L)aox(_W4MA#fKuz|5|I1 zV#KNIj&l5tq}*h`Xz-jECym9GkZyZ=9CX;gn)XbT&I4%-TUAOI8Z6gXYuRTRV{Yoz z+EsdgBay%^<5)a>xI(f?=Qp8wRyS{QKYD^6TPs`~or@Z2NZs~)Df{#+WQW>7&?&8S zfch)wt|y4;JEW`kg>2?uHwZ&V^9QMVbxzihN3hRDxsy#ajl>g7ws$jQbb=T8?Y^jz$w$S1iD zy!=XfuU%VXe&_+&J`|EFcJ4FcAa&X(TdKg4RJEG5TtDGIk9u|ZW?G>QUp_r^W$W4J zdB=@fY~mtG46Dt!A*iNVD==WdyqYY1VEeg`&vTe6D^`l~vi*UPr5_PQ5|S^}XW{Hi zb8m{3BlGM1B`5xXbPPvkM1#)I9%0kpvP3;te$zR^EQP6jaks+lQp6MeGN z&(FIwuiE*eQQPSt9cnVJIgSCJogZn-ZJuBHjQ{xK-MnMhT|~QYg(k&ecNwD7(byah zsW-{VNq2H7{UqE`vFF-^- zL;N&OV{dwjZP=Z~v@@4yvZ5U=gfFSQ}H zzxFcqn_r%Qd~y5_tfF`FQgalZSJ_zEna9^S)nlLpeT`2iPe6h6i!n_({tTu()>YK( zOA@_JFQfq?No8-JUv)dUARgo*zpP(Fszl_M+3;Bv%06Jug8DFJd}=6U;;>fCEqqf4 zuX}mE(Ojz!9ag-c*+X* zT`BszKZHc-Ye9nN2BDEuev_0K>zL_U4H+o3sB23tgkE50n?MayHS{xN{)-xwT zup~<}iTmBnffYVZb-&%7#=*V9^FJCSM?yk<>xNVOx!^d3s}hcjH+9W6v8cktK`L@` ztu=||#UI{IKZEf`2C-L9-78@f;Lmx;fV@!E6#M`14VQ@yf+!qkH;sJFQz&G+iican zKYCu~Jy?8sKv%bY88gzCCP`^|pl+sJQ^;}e@-U$NU@sodhk9nm6Zn`jQDgTb_|nRl7zqDm zLK07Ov)5yNDl*uOGAG_^;tPPfWw(O3zcC*Z$%$Q8cGti4cjXmGe(&bNO>^1K_YnKN94#1_s3;(*c89HiiC1A zG=8)%u+=_s8<9aBMP*5aIUmHg_5C2Gz6*0&8?Qv+9$>kJr1@(wO1<3sYMd6M@6nf7 z$C^AOV<~!Y!~)_zDufMZbxq66ULeh7J$mnj=LPZ?#3Nuu(>MBR6$;cm3jgilMR&Mu zuCvHUlXhN#p@BAdp9!?9*fWEPt2^<5uwT8U?!)+i3hv5pJKQ_0C=LFrspCG$AyyHMQ@V#XFvr?|{&;GZ`M$f#FNm8&ruGJ)EFM!zrr2aKKY{BpbY)OVv`rot@>FqKxWxRC^v-%F>A<#oxbn? zS0*v16`U$i^(S0X_fD+fbZhC0^NwBAXe6?Y^x^5qt&p=ubz|(p9EU9UYvP#1#t4g; zMIq1mDD2q1|D+=XVQQ8AF~zBK<$_gkI7O1?-4uJ@?FP1z`UOCYM9g`*Sg!akYQL!+ z7Xp3|Jx)s}ifHi$0)`9WY&@|>?(@a-vBsZN0eb}32oFZU*zuk6ebAe6ZA9zR1v2Av zMApnqSI6?e8a%;SX8W3P0wtWc|(o`ZHeFDOQucr`vU$#f-X+lftqXSMPGMM#& zr3Qp~m?QiZ&s{j&AWHloU{f?zjQf{cRunNxiHEZnm`(bPc|#Vxu#l_UF8rflg3OiS zU(ZpaI|njq!(No#W_1h`<3wn}?l9X?W1_?z!t%m*+LpSABbm-AJ`|FS%|+4ohE;j4 z?B+}H7cM?dWDhA}zW&!gIT(H7^Ia*&E+JX_ROVlw$zFzj%$ z2I@mnTPamRWn{JXs^Nsq3vU#lTVD9}SV<7K$0p1#thR`qCCPUEUAbdTn@irWN-=a@ z`n%J))<|Ka|c;S%tYOvOBIMDp3*-$n}Tg8Jtkd&>%W~=~};S4Oi zh*UkHw@D+^ufJ5~xoOuaNK&zv7>xZ|YE4*5G*5TGQ>t`i#_~P1>-}xJMiQbnuVADP12Z zo#6&|6qXJ1%&D)sS%9wf!B~^{ zp`ldvdpN8o`w}(xw8D}?jvH=oI|<`X3e3sIvS?0L>!b&l6n|qbDH3(2_*nwhcLdn# z-YhW$@Y}t7x5gcGLvuePI+3LaOc`9~udR`Y=WEsr@KX2vqFSzF9g6JVM9V4wOcIo1 zar=hWXJ-^llizgYLz)jNC%l}vV*=RjdHYdg>J=H08R;M{;oodF6&tauGLD5sMMpOk za)0i_qoLuhD)ohGfbIMsT{j-OL%gw!zt9b+3UZXWBO0D)zVv%;xE?P6jSw}Xk!+oF3sSw#FB zWpH2i?qt5ghV*GoHU>}9YA|t<)7zea+t3oTZ%*lKvfVM+*|<+Y#hXooWKDUbf;U)Y<%fq|7BumA0*48r@JU7kGy*v(ZNz+LCOBU-)41 zznad|2s@kz;KfS_tyYE4k#*)X|eW6EnFwr8F8g4rhL|Jx}z= z#w4@aQ(;6ZE$&tYq*LI(LfKfwW!!TEONv#9Oh-DkPUJZw)D$66BKVFw{tGITbHAB0 z#~3t%fpQOloyEgnL4N5cey)27EU==u(?ATg8Waz#eX zH)hWL;ch0?=H`-_DX3{oc^=Gq1~jQf9~g`Tl-G3R#{%569zuusN4^`x>Ya#!1kD(y>0q)Ij5<~cN}v;?#KoD#8*E0sp(EqCrahfYI^VpA zk1EL}<1$^3GHI7d69*Hd{P@WmUxIaz$m)Ir7cS5AMu~|j6R%LF%}f)M3dQ2)jG6dXujGqYwMgO{r8BgZWgk^ zcxl;KRA_|H`AFR)xgK6oJa@xpQ6t5G*(^-gGSp-nC{~6S?XsjWkd49L8yxfRk%UV5 z_$mdlypN|2AP;Iai``LyPN?zzB|(Xh#F}QaUh9*R z)yYk_yT11{TS2_LawJ8JQRVbk-%(=j_~KN|p1Tpr`&k816z=IjT|ppjnlDzZLa=(o z`mbrG<&Q3G|M1+V?63l-yGpLLnKhdGNQPqUBpp_+6_4gV4lJtRUnRh^`R=?s|BS|{ zi%h_(R^|l<-zFZFyW-hZY^9ZRE)4XNG3OO`NhARL8^UjCjuza5mu=x1Fec`>~n0L#$#uI=jpL4QG+)^OVs(7y; zhBPN_w(IL+`Ka>gTgp2BB@nh5W6k-xvZobfKM$$QX*a4K;8?sAV;4W_JK{}9C92$b z8)9v-RWZLuM%sVnn(^ZgGPk7u?}P6xCH@Ub)#dQpnuz9i3UlM;sZ8;Dg7X8lZ;GTP zDYUgG7gQ*I_VpwhD9UdrS<m7-4Wh%fuCyv+egS&V-vAd$>9FInnloDRLCp$o{$A$vi zJInC(dY$|Mg9XH}G#u&Fby=L6+G54jxbR+KyfI5;c*XvMJ=@x(pC|ikOZod^RBV>q zAZ(WXDSkeII;AUmrXVb*!m#^Dmt!3rO$8mtMYi?n4|YQCXwUkYNEvKKU@;^vA3%{oRw~Y@F5F`XakQR{ck{*IINRIAqBqgLo zx?4t#7~L=$QR%MHrK4NA@j2h$^AGH`I_KP<>v~_;{pm2O>4d<~$_+yClS|Uk{wE;N zN}+d#HRiE3!h-zaqU$=8Zm#HZl4;VYDLWiuCW&4dsh3OYEpDOAG+!$C8>s4-vSiUo zh(&`$5zeJXhIz@-Zu8M)avoBYri|(>%Ehl3xCdmD@v;sKyQjb83W?eCQ124{!fd&r z?iIW@@0h3B90S10Nm0$;_`P*erKYlOF1^Vh&{5-4SQFV3t9*<#K-7BrWy?QIYj?In z+1HJkkO5V3#9RY5z_N2~4Ee5Z#W0($s@k;~{q!*{M;2XR+OSh2laZd=sF(1skMh>v`Moo~PPv7YeEw_&qfn+4%+1 z+w&|Bf(ok-|ENN2b}I<7)i8KgxcYV_GHFj#`|pmsS8EbI2Jn27v>yUSffwhb)h|>V zQ?9;_1eDp%{KmzEm(x)XJek0BG?u)MJLwzhS{2vn%ZnVp4H$B!ZkuIXtlFqR6n`wK z6^97fxOOPsLP7f`S5hzVC-~0>f%`J?(n!|{hY!+QYqnJs@+NQ>AQdPwH1?D-lk`gN zn88E!^G$&k@2)C7?&XcF;fRpBd9mwfIIk4Ey;I_`!=QQq5<9;FZEQ)wEllff)!@6mRU{IKa)Fi4LypxD#^{+1?@t7;>lpXs(}CDJn0oGY+^Ik zrPVCv;N2rcVNciaV|{%MOt`q}V*Es5L;`0Nq`zY8a=mE9Fc+dIRBRY&`JUz%G{cRj z=Wp2+?46^~=T`9s;PBFz!8d%BjVfS-BHnzh81eA}at7<3!d`R}7_wY$6WLQXsp?NA zS5#@2y(`=ttlR|b>5h~1k*R2$s(7gR`Lk)POLrQP*N1Np3q8HP3jRh72YB;3QtaedmmLn*42&bZNj zo?jb&sG9D=^6XV3MuwI#wOw82ncivArj&!opfEXbn$7aO(c6&*-&VkAuxiS*raSF6 zvPAw3N)uW)POM(Cn|gB?GHNyG%3&ISiww#E=|eA3t{2I?#W9&ucRfgwMzmbx1g*Tj zyhBc~sGNNf~I0`NiFB#_?!=))8xYs9-#CbdqG z76>3{e&y07#vX{=YVZ3uAJI=!oa!85|B-sx*vgE^=4-%9jU6lzhGrZfxF0t`jaz5dB@lBpOYoZz6Z2b6LUaUmz=AXa;1$zZsy+lI=-o_ zOnyx+VTZQnY<(B~GU=Gf?JAO{uYv-t7bKFCuO z6UsnAbAi_JHI~rj2~5JFlKOV&m^mXCBxIb_Y4>mcNJGMp=|T$6Am7YVjH0I2h7;2I zUQcx6kgHC|yqU&lqmrgjX4Zw^-$=R3r;PXxVS1i|vv#XI`lvgmqH;+1M6aJZ_VXt9 zygv;4I)zj7u^j_laZc9>D!Du^9OGF|%U?Px((S1(YyeESu_^NL)XV(v!&&3?_XF!u zYg#|RV@z>iAv~gkki=E2kp8OGIMn|!L0AP+d(%@-n=^RtK(DxG&&M(fk_2*!cwfIr z;JX;?B^mc{9wUh+z;1dpIE{=PZwmJ5hNT+rxqqF&rj~kgj)haGq&zKS zXh^y}xqv(FD*X6Cs}urv4+K((ux-X-(b&b+(36pNPEwd z>^^U3)l_=0XwKVSE_J|&k22d)+=%wNjB@phb1NF51@k7vMsM8BR8a0#Zmm5_gFP(? zS1_t9AL>SGLl)iznOF7EcWIFR1bR>^S9H7IddF=22-hQgodE@H?>smRG^A#e0$;SQ zikSN;?A{JTD7|rZv5)_5FotMetEja$;XzwAp%Y}o;R4)a74O-s>Vb$`a6)MXc(JnZ z%B|oLxC@2#+*qlFJLFJ% zRo?tegn8dkm%@llYS5fc4+5lG>~N*Sd}UStNoRv%DNf+Q*?srYG4#iI zwbzlk)?Mjtmvdsk2q(yXPm;2&(fP+K`hz__c8P;DEd3u9-ZZZ}5W<{W%vX9=6f`jYOVO6F4${A$a-|_AEj@iyS}| z%a7Sxhj|65Nq!h@Ox|c}NMY(DI-mWp+t(|0Q=8Et8zsD zK;IGgeW^>zivtbJ%?9zDY&NglOC?6to>&ZqyrmYym<{H$id(m!R?2gWmi>PKAINCJ zRmqiG+}GAX$QOq1cdVv{YB7YFp`f42VgQbq?j%`I^|PqmgQGNbdCJ(tgk^z_1=|^s zJJs%GbH9V3TE+1j+?f|tTZX@yN97YuJh~V30EzWGQeV&IzD0g*~XY2SfjD`rDUr zQ7G%Heo_-w6QLE#w0>!JhhgJPt)aGe;(=klMOd_*q%%P__KVqOi*?P}XNUw+rTy+t z>Gv&oU8^!s(654;o9A-#nep-(%8X5=V9&34exRZ{v4Y3-K#nn897WKT(h zaBJT5#Ji6GH?l@22pOMJ>p50YQ|>dJ<*(_aQ2ng3A`-MI?#OPg!K#^zxlYEZrB$Ff zvd_Dl46-m6s1r3I6=!{s0{8vJwbT@dq6)_g`P^+pFptLFksD8m{OM)iG zIw)DX=M_7cAWsc@1D8S?0}XrbdKo>+$$tf=2PgUfFP%~Y-3!Tz-A+bz2gi`twUHWI%S%`EcuE>Gb@Zlh zMlW3HTh2#y{Mo+>+ZhG@aM z81@zK@*S0O_sgErkP3SepXNQS-P-iWlznG8x=Ug!D472jJxADq##{J}g`vk)_{M?TDQ1sDAy-`gP-AgcqtwD)Vm zhLNCkFvV88-Z$TR!R00y#nI!gEn1UDR{o=kvemH_1+?B5Er>hi)cRIB!rSmOXC8|v zzK9eh9JLd|O+)o^$egmQXku9~_|ltR21stuO7c_Y?yHI#c~~usRUPz`0D7|yQ*F!F zKZVRIzU3ph7f;mDr);NE1oD;5Kxz}}80%1lr41YMb3xlXX*nPsM;bAeyr$ZgeV^D2 zKvcYT6|`?X3J88v0V2?-Bj4XF!$o+ELb}(;D_1kNCFP>Uf1nDT%zh7Ov}&OBjq{9! z$vg?@T3p2QA4uS~(bK<>N=ZVTu#u$&)|{G)qI0jf&=pvIJPzcKy4A`aRxegueo z+#p%Rgg@2dY3U9OA9Kc*y-B_L`vu?f{74IwIBt&+_%QWAiH2-lbJoNA-+ovqSe9C@ z&=1Op((<|p<_+w>Rg?;@4Xy5EGeAwnBg@pwneQ`Z3&$Q0-&L{+RCLy5zCBD4?sE2UH6&Z zVACHYp{YUDhQ9pO2IqNImhlHp6EtT(H*Q&nUo!%`PE0I&-WS-^cId8>L)@)ImdEm! zO=}nGK;r&~to2nvFt=*ivVz~?EySLS$+eS#wy&Td7`^9$aZ2Mx6BSIHO#tr8tp&PR zyx)S~X}yW@JL?B zsL7O<=|OAvuN#cgaV+458Lp6B87)K57Z$Y?_GGR=?I9CoceO+s{g)uOxMf9=OW-a& zT$^opjRZ}RW7G1=?V?PwH{l|g4ax1nke3cI?2A$W4l8K--i%C?@q-Fr%=OK3`qO#k8L3AXs=JP9;(mH@td); z@iG0Z0*O$e*aNOVBEwa~hZLZD!#0HbgcIcMThOMe+wBv%Vy_ucyw+l(aF6K`Ul}XI ziY?s7g4WpR>(ale8TbXRtePd(lb)yB?x=u&u!P;GtuOEt$aN8Gh)sgZ8E zJb|s@3zLeru1{1WYu3=4QYK-xi`hC(f*f+&B0f&G(k2)z8V*xKyiL&XIx%Vhy^J%6 zX_*d}t$m!`%kpM6JilPv>ARCp@{7rgTz2jfby*Org1ehP{cExX_o3roT% zq=Znb%HB(Cq=IDI#+*6B0|lJ#+2tqd_H{NU&MU%JY<<4l-k(`ug51tG{~_uNk@b_(Bvsc#cgXM%`=HrtjiFMQu&w7wiCK{EjmA_BNtCx54BMb)BdX@XYM ztKBW;Cqbf$9iq)jR+HO?Vd4h^c)$R;%_8U$AbPrTsp`x|lgF2&Ww@(3GS3w$p&wj~ z{S@~+ibu3uWy!P%jKIa7a0lqOsQ#QltX0Ye14}rnrt2qbI6*Vb5d9Q!HcR9EKam(6wp z*N<;@)kh15n*$1;0qC4<%_blcH&(~SMQ9dzGhk(@U=|hRCba`&`wno4ZrW&d6P;J^ z>|PPmwrKm+_Ub*3MRQ+VJtc%~CE_?%uKWz?XuIVdsA4&C5+sVL2;x#Zrt7u!ZBpkR z2$#EHDsX<+CKnA5s(allERy>d2#{`|Ow0i}BJ~$dfXKn7OoErLrje z39XFr6AFKQ^CNBsm7u3)YMapJhl(P!CLq;G+XH^ke!8jo7SQ-y9VQ~=+EZQFhyo0n zvecWBz$nAbrRF<%(v;FTg-tjgUy!f6EXJG1Aw)1>tiRZ4Jo!{?5Zj9l?Y^7&vJ|zE z9I(rRVWH|`@;Oy6;*JitkaOeA_H(7jlAu8<#S?L{vH_2qnRaKLtru6rgmNO~+No$w z(6F>$sH1r-a8DsgOwmuzpa~Z_wZAR>*RyX#^zwm*LIlXDecGi8JlhBSGkrYEKX276 zI+A(!Zzk5ByQF>Gd#T%Dw1nv~QwXzR3Zh^S@WgCWy?l!+e`N}aj=LB00CBnt!5%rR z)ES7=G_vmt!AjGnwMzj9L#sKgHD!mWRmOMwv%&Ncsx2wW`SN9g!u8D&kCM!<&JEz4 z%Toc{4iO?Sn;yT|mtA|$>n;SveA55SIkGwL{vZvJ1v$Q|I{KFRs?hRST?l%Z@~k3Z zwp43M9x%cI$blnqkfniHqvx z8Ar?wMe&4E>(E;oBpNA+**2;8%ZwMisrto z8?`ao)77QjXS4u>DP)lO&R(GZ4?-`1SyqN4rsp28R%{0LUnU~l(78Ri^O3$QrODb+|~8%?rhI9kv}iS5=2MXOfvWF z+bD+}JpU5(TK~*&6vM(Uhwx5@1dW=DmDK}y0OnCm$py+YoD|!n)TpRq&LC;YlVk|p z)Yk0z?gunF%VXU-;v$iCl3yC>CXY<9WKTnmUoYM7po8nMjf#SS^NIe5p~Gv-Lj(HN zU&z4A-vjH{y7vw~_lj>ym+Wy_E`T`wc!E;vXIJCUnR0V`Ti1UeTH<5LXx2H3rB&MV z{Ji{LT^>V#sdp~AbO7ZbSj@-~A@45eD9VKL#rrep{4he47CqOQ1kbSV#AoCH_E<-2 z2YAfme?9V{3@jmCy*AJ@S)Si>m#=Gik_|oUYt8J6>k@TPV-xoB9@z1i3KkmK>;j7GqAChJ9E11BhSy;Qz;*{PNnj7(gl-(0REnHC@t=3yNW z83h^6oa-Mf`7sEnxIeAzZBEQ<3!*q^R3nYbzoS048;r%GbJGueT?@tH|Fsa(is`S8 zrKBf@*HHc_5a&!{yZw#!%ArDGyMoGl>zgl7&dUBKnlQ~cp_BhGvgAs=;Pw;17+?+x z;w)Q!)HuM@wKsk|OSwjRs$;YYtfs1~g47&6I4cVjj0!`u=Nv7|^&Btv9m_!(!aox6 zY+4|g-*-lp@%UYaumAuYtGF{?t$09>3m6;ps800Kc1$Qb&dgr=wdj70MZZ5R1+tQu zob`yA$^zxjE;s&~7$I;#0iSKhmwdzKKE}p!@igD57d`250_z*eIwI%sKqUwlftBRN z{WpvT9$cbYWz?3YBG+{g3whg~3p`36J<$RhTTuT%#vbIC`wy&>_-x!4#q!{TS!LqD z6D9x%o;EdLzV}~>_2!)YcH6P(4TG3k1AY?76fxscRkT7?DN@zjftao8`Q*H5?Cmx& z$NB+JJC^tlt6Jt(4^Lzk)cQ7?S%>VECQP zngMKPgIv1eHR_J}zUQjGXmkdvx$AT^-}T@#v$>hU~8q8t!RO=Fmua48{O&A1L@$EGlzx-aup)=6Kg< zyR)%@_?7U5Qt@&zL88&_GXIIK=cL}$^hb~Z)xy)a6x6PK zV9!#nEpBNuC%p+#c=(VzJR%{cZ~h@VPU7+bQfrhfUbsp_@VHX^mg>NA`olEZ`9 zeW5DPPUTLU@8t5G^%!hsSB3w90CGvR(8H0l!6{Qg5`jGh90JRYhkR3O>SH1DNz3;K zinr6Oc4#c{f?(n_y)sNitmJs0&1E-`v9-~Z%emoaEJ>nGV_a@hWuL+5lrx zGzCW2w&JR8bDo=Sr~XcmnC9d$2jMYF%%4XDtD(-=B&!-xenSz?MZb%c%K;$+ zX@!9W9Uv^0s*crJ+(6Hr;aMRNAZf0NfX7`4x!-68xs8)XNLdt_B?15Dm6fpGiogp3 z33>W*is^<~rZ8#csKNtUXj^(ZwBYC~x%GZC0_1V7)00c{U9N8=L7nwO6r<7DUWF7n z^1q{qp(9oXu8pE{*MC1V(o(BA_#dcnG5^X8n2&UHi5~{OJ;<8INM~2?nh4LWgvq*9 z84ds9iS=V9RZ@=1J095Hv%^qz=AaYKb>E(Jc#r(ukm42T#n37kri5jOQQvgZI8K-p zvme5d1C(AVgvUiI8=ha#y?Daz0iSqE5=ogn6z7D|Yqwe9iJK?6b zTl758W;pV!-gT{a!D{$<_+Y1Ma7*-`__7qd-jAQ z+ka8{jJYMutButHnItbmzD6DDkH9Gjihy^f#4`GZ2iHK!1PN+AukeP(%~TLF>GYRq zX#W`eZBzNqR{S4muh8b66|EjRgFr=IuxkUY!4f292}9}5^kX~6(_A3~cgesT)k%1l z<#Ll_NwW>jCHK6O$;io!u>S8F#`3&{955b*MABr3s>G{My)nkbK6O<*iG7S8 z^1y=PkFV>Ie{dL0ZBk%fKS z@v;yGYB_efIlb0kOdCGtE29laSCgJ`HFGmjm$ycU6nU!72vkKYd*MSR@5HQEZ|Ywm zYA}%$=}y^89KGMK!C`g=b{V?Zi43MX#aPB{6>nFb%>JFO3`{6 z?lzePl~PAc*I56IX2O^gu4>_k>j*mGX^X=40*rILD}$Ad8;#d-L2cO(?4%75Z^k<) zXfJFl4C8ZR$M|xW+EkWgiJNFztzCYsCz_nBdrL`0eZVZk3C!3@uY)Y%^;u^2mB^Sw z<`Wu^Jik`_^Ew`pl>-M44`;D0pQhYRAm2IGSkSoG_bTh*CFGW(N+PZY>??dhHNn?O z62VYIl6f@>;@)B*S)Td_%4I>aTyATvy%bb4X1C6Wy^eL+U8B^HaE|qoivHR zv2tbwj|dGwnby->8CP`zgnM7}wxJ4*A};REuZ+dK;r~EU&ZShDrsu_y2sZSlicP{x z9~jX4`%BCxlaB>LeTpy0P>T?5Sz}1}L(Rs5Xh$-8R{p-g^U&gafREn?7zVGc8h|Vv zw!rCQBvFBx;401BBVR!KA26JsO}Grm`7sI~z`m=3*iKcWcCs>%>X@{rc5pANKdGU| zs({MF`Gy6C!vIzIzRq*+Fy)}>+%u3&=%#JYf+76CQqle4vyHs=y}iyNFg~c}nM;xU z$t+0Zqy6T&)rsAG8*6Y8Qi~jl0`<5!MseHadEwkn|3Sv$;juPu)7`3Lb_R9Ni5maJ zRE&L?j%OEiDq>&;1vpL!beb&n7}(c!h`IOyCA%h_=AYoJ;{3KQfm-v?pz5Y1!iy9% zwIyrXlb3=yc~!s>$?n;F;ay_rMd=2T(S-!)I4Mz_3TAf9G^~I|eQVZKeM17Wh~}3C zQH$!z7C0)A9W)nua`vhHof9WoIw}K)>Baxrz0u182E;x@{x7=f$%C#hsW+T7yqq$u}+2 z8#ugY&V$|T9!9&Dg{?4xJIG|^MLW3JZu9+$$#Xf!@Rl#izIg8Wy4X*Mq7iV13<|Gb z!x%~Ng>}^nSXrnFCmuc5A7g$l0%+SlMOD;Vifz-jyhd_A;v?$H%beLCW?)ZQ0}e;IE;0K4s-f$|a#y{h8VCnP!JhqEoe8}E@xV5lQxRmNLNTBIYJ=t?>Y}g<0s7Rn zC}eP8^(6jTrCaXB@LuA|f^w90>4DqN%7K+avjGJLxTg>W(xd+}KvkyC2R~jGWG3+6 z%O*?}RvoHI+pY7@zsf)Ee}6dlL1Lv-2w!| zB$wJPDv9tivaGAY35d0rdXnFA|IcL%GH5L^HeOVzaWW#>!8fu$A5c5Wx0Nh{I_?V_ z$>1{ok)oD}8==?;)Twx?=+@H-&e53Zc;#X9-II$cw0d)!HqArR;YEWB!Mn>U3HF}3 z+4t-UR*?^zF7JSv3`4yhaKP(j(P-k!p@jx2w8xIw`&m)jNP517mM_Ot`NCMO#%juK z(?ts&uQcX?csz5Kep)#F`&fV6k~a?{*#cDwRXX=9FiaaR_a3Oqltwg&1^AGxCkm6b zR*bX;F8otP3U7kizD{6`7T2b5rZc}Um+X@O7@!u>N7&5-;pe`V8EvD6~(1weJaFh;&isA z&sX#^>b}YF((cX22c@|Ojpa}!yl|1D1Bk#*8I`s=cjl-s+u?mc2Tq!&sB5H^?DJLn zah!EL{%9m%MF#fk#}32mqFrycwgIA?RMutn+E%^Zg3EFd+?gmVLmgI-ur@vp_=X8n zMZhDKPA<0R78mF++xMo?mL0e#aCUA&t+K4&a)NXti7V`8=0V4}Bo5Lw7fUt|7;|PZIZE-tZeO^GprSrj``s4cz5(nM0&Mxx zkIozSB(up5FNIVe<0!=lVjZ+l?Rh-ZWg$y;Fx=-m8TgNlkr8)BkgwC{`++Vl&HkLK zZb7c)y!;9iUCl~kEmJNK<@fK)_V7VQ&Pu%h@s$y6980C(hjk%t~r z>;$&#r7^eq;1|<|AwO0IQn`KE_J}v?LphlukC5~tV6x1&EM1kBPaW%?h>Zpn{7j1U zVhea$H0o75ihmnYX2_NuaPj*w_4r!uz(u64UF)$sn|4z{{`L8*GRtPD*4Ma%KZc*0 zoQrwR=mvHOHMHN%Fp5j(OMGOFeW8>Q%Bl^BbkFsGQ4T1f^W(HpbmPcwuPeQgPz5IRT)HRrSVYVkS#-SSupevacip&(|I4# zNEWqooO5inb{s{EqJ8N_ zY;}Hifz}G3ny-(qNYtBd#+6BW{%Owx%ky7=xM{F+)lBP7|NTI!ige--W;{3NKKxn%uLn zOP{tS=6NKR7aTRwH_{){+#-vO=j*O=+`Vl~KazA<%rk20XeL_yRZnPSHnZO1P!w<= z)|Dt-rR2DZ{1Zwv@O$Q)Ye`Juh9AXpigfsm3e+f6LdC@)dN=ABkq-sEgyWW@dM=Go z8foU7QU_BNGK!nNML3s7qE|0L?#?i%z(wSOy!fGDXyS1T%-gB@PN>Gc|H^qYeo2m< z!9!XNPuZ0=(}S(_{E1D)4S-BA@PY4)*+P(9hQ~vr7lLeS4Asn$w7-I>C2QE-a4Q`T z*uJI=vfj++^)=#mW)I)B;yLd)unG*$e4+!42mv&uXdSr^uM~<%o*MbNDMu?AU}40k zIjlaS2rt|Pb&6p4UNf^&m@{qQE+w6q53Nu7wwTYEqx-~BA;~_YAbZIau9b=Uf$x1~ zgHP)I4lLY44kgDmT7ERkFYSH6^z;^Lx~$vQ$>j-Z6A?h`4P*R`0o;n4rd(aXGfUsW z9dejnb$d`e{7C21wN-QIIFhTHoAv?ATJJVwDv^po;qWRmVO@29PQbIM7=2Rl(YGL& zLw|YD@niij1#6LglQ`>7wx}u&!)0f~8FD}OZmrh}pHm60@sOf3Pr@0zEqSwFE8ixKcE{q_KsRIt+k zoNi<9Xeu#!qHpeqht_b7B(L)m^@K}V9{$6|{fd;kZ^nmwL=N3LqrP=j|u*&a-~0J@6YPY_S?_D~Hlk+N3-b3s*X@U})XxmE1;J zs9giwRB*#p4S@Q#%|f)pALRlT!8B(I+Z+dKtyQXI2I+n3^$p_KUouhktSlJSv*&g- zoR3Szq}F}<*bW=>q!yHP=Ua`Q0S3-OPWdCY<+*9CLB-vbh5_~6c3HH*i-}OMDZ4LT|LsFNOcl~tRq#3dxKe=8GJz5E5z*1QA4hl-gDf%LHBBCk! z+|5`g1Et{d`c9~sEbkRLLEz~eI~DQZF9zCQl|i;2L_U(JW6M|gKunfbc1~j=d6R)0 z-5W+{sxa!0-F4LL{xV%D$}Pn5ZjGS><5+Drd9o+ykJtUK{tx$mk!ah7hP8s?FSW*k zKE1j{wQ-sZ?JH|OdA)u}9~-@0)RFe>Pb6^iOgJb}S2-=PtP`KQ(IFzt)lG^p6Mpo{ z9UC1MvQI@T;;vf%@6-jmZ59|5WL-M?gMG(9Djf~VEJ*{pp>LtF$pJy4&Lp7XYP~(( zm(JgcoIB^lA#5xd@UzB4WAved)%Cmee8H?Td)=2{UP=_$Yc9WX^@g;ncwcMr@$iIE zz8nFv4hT}>H|Cu_xbWh(`kdL-;y>%TN{gg-5^P_;n@0unHOM&{NKj$X+GkqaB2NwN zg}S$Lid`>(xf1QG$a>9GrJ=sja??EhC&_4bO$m#|6*pH)B8kjfB$?>LLARY7h4(Wl z;_g370PIK0NnK0zc>Wt1-mTjB50ntoCD_TZ5hU81j8Y7mRT#Yx7;8jpcypOU_HwqB z;Tl@-xRhha6L=7x<0V0gw?uxCR=5v%V!>&;v zaQZj_634)HA)Mn%7Y=Jy4@w6A=yLWFpeW@#ZNpw2XO9Gqg!~k|Wy0y=>B!>ybvJNj)+F{TG9h2mIyfm4m9(h{Vvon2>)Su>68n}(n`PiB4 z7{i)|VoQJ}ne+wGtido;?36}A6^P4joIV;o1t`lwW7O-ff==b9hS$`RM#mSBw`1%ei9D&rtkU40RtV?k~4SC!X_z0$z+L6urGVwDS z7pWvVEXl$bJ*fKRX)e6``!a-B=%a{GROY1^SaXW)Ep&`QQK)KsB0BTSrP4wZfGAu_ zF`B*zTi|<0w(Q%uL;Uwz%zOqzT!s6oba_LGPsa-u30L|#hyC(0ZUMf~E6ID&uorZJ z%YTEa+l)e401IZQ+<8^{z_;f=S|v+-g&#Ifc>p&ZRo3tVnQ|cjjPB7aFwmo*&EhR; z`SD0jV;5QjR3Y&0eKg`)x+cjxE(J~HFi|EN^a1;((zmhd>@}i!*ggi7p-IeCUXIuM zEErBihn`i%P;35XPGfsjC~h9^_<*;pn-e zfQjKk9i&+oe25Dg3!nA<%Mh2f!*=f{P?#0P5FFI>(LpTE0;QJDzgc3|S^hOyEW7>1 z1q@#kYF(piKd{Feav!1`y2Zm z3F3&Hp=i6A87?YvZQ{!QPEv}fop7_?xEXD+!0?B=2#gAD(p@s#Zua||&c52yYFxP4*4$b;$1d5#L*r`NSTZ<5^j>h-|Rcc#$M zG-#KZ(ZI}b4wJ=Y^#)591<2|*O&?WL5=n0Zke)%xMfI1p?n;p3(zmMq&q;aPYT)@c zf1>bqx3z0Epr-U*eURNkz(%5_DhrHnIvkNE+Y#_d`7}CN?S(4YusNPi_d}BYTZ6FC z>6cI)3%@fdYAQGTHn-lD-4^qEqEoOqG7ja>GREn79lV>2LAz<>E3&VsK#;z5b9@tj zSjc?MAEHm@t?QOEg=G!yMMCJ@CT1#(rMH$Iw7(K6nL&P15sjiFW*-6h`)C>K@z$%z zSrli^3;rwRVHOa~hDZ?Nm%6|VUKw?=hb5~!#zNkxX%jpBys>f7{XZ$~78gtMf1GIv zlA@Ug&dV@nNk_X{u%z6Y^NGV+ccz8Z*@^SDvN+1UP=Cbqoym=e~OPvy!?bw@XELl2E|CyIvNL z&}dHdk#-uoGhm^~KUD|MG2fFuyV5`S(-P-yP>(#BH}}1vet&_X)DD!gWI zv9h9ZoZ%3-W6>l3EhR4#y&4vd#b({}&B2~UCJXti>&5V+anH@R*54y|aUI#qG2VMA zim`a#d?)t$W;au{VLY-r-%n4g3905@pvEJ-uY^v=&07=-U;Avef6PoLdqv4S%r$cU zSL9IiGWOgyp}6?zGY?#)??rgi_no2}_tg`;2XgXf<)3Ej4U84>epKYsg+lt91(7p3 z2{27nJJT$s9QR4mG%-?z7dSHZQ6FXt z9Q$>2$llf;HifNpExf937@y#zKo{&EIng0 zbxf?66O7G>F&l$s@;GM5y2zS=N5Iw`q;x?o*Eij3V7uh>!w~+;tKZ;EdDs^4yweou zCY}hxN8eKYWs?n;yDNi&Tik*Ar#W|WilJ_yep~~E! zGkfSngr-Gs?%UyKS=&}2_yjqSI$gJFftu)#%FflCRp?%7E*J@Ta6LVSD8evET8c)w z?9h1km1XG|nwf%MMt}Y|{Q8&N;d#ZRU2`%>|B2%sATmSQUGFH!r5s}#Z*g&^fR*fU zmvhiD{(iHcQP*p3oFCQU4*hVd2J^B&G*_C zea;Q`&;e``G}74!FKdzb179ne^NZ=q$+wE`gr9K_GPLSWjLZA|-s=W`d_?p*-U{48 zCKb`F#_{K;(DvO*q}Di?q$TVd95LV>IJDo{sXUIA0f*mVE}09jh|mmE)0g_@KeGv# z2t5=N3=CL6usaP|5C+|bn?ajS9cP78>P>AfZtbXbfJhlbxFRn?5k>$#Rz}RwpPg^v zZl}BwuC@VEWE-q}X%1bsm@7pwjLw@^zvoP?+HC5c#%TIX1%_P12qoYUn;o3$5~E3r zDaIA@vp)wv-1J6EfmB&}ETB-v4}IE+AT<|gh#jUcy+x{(F7w=NzB@0kVQ3vD1{%-= zpo>G#pQ)J6Yd$nhy^gH9@<&($yXK0JaL&8hQVCG`sj({aY9dlV9W5D1q!f}kl`*Ud zq^e^p7hIVR%;I@^_^`0a@+NRkGQQ zzxEX)q)c#DcF7S}t}~caDM0hcg~n!S2Onft9Y&>`Rq<_Zo@$!#(zp)nr?szFd9dai z^6Eqo?Wo?L$|Bx z(s6J{;0pV)ojvJ?ZA@%|EmgzD2CGNB1cl_5Kv+|X>VmXAApdi&R}7Bjeh5;BF>S zU8pB$_tN_DrcYM%xI59LEKlK^Xzu3*q&l`BP)GXr^u^&6j4`*kxD5fFl}^dmlyIN` zDY4qYp1=XKf#n|v*e5jcWcG@0sc9#>X5H}l-icAEsvKQ+@n4ZjAI{=$D3*nU+I@rc zN1C=om#pVC0jOYFp%jumtJ+kaJ(65UHb+I21&t7S)efh#z}(84*)3`y!f~-L`&q*Z zJL64(XadTNUy3RR5jNUw!7^BdIbkD(KU`$FJi9VFx1^oJr$I>j(amTK);zF%_~seM$sF)&~~2P~ca>Y$6;N!egzmSKD1^J=015;Xl&RmKQD zG2Sa6`3UORiq!%vc_n;=Tp(G-W=lg z1lJHKB`8~#{0KOPsF)CQfe_la{Pcv?_6MFzE?IE58y)3=BliQfb*MGSLABhL=DjjG zwQzZ|sgZ(jVuG0)q!jk73Fsxm-bhT^@vS&nTU-I^Q>5!2-&BekaA1uQ38Ni3ONn9=5*YJHIK#U?yp;%Et`5{G3b|Br{dEV*lyo zy7$`>i$*kMfy{hhK^IM5qK6d0D7Awgr)>^U&R2IyTIc+yJ%h5^n9lUF6yq6OgedzD zNgmvj)4FIrsOH<)Y7FqZ6c1J}E&bLrpto$rfP%_w3rq%NNO)_mqIzAIFsA`iL9tz* z#G|3wF}q{7#wDD_=GhJbrY(O1?YETctzfbFi$emro+by%;@{xg3;ZcXcldec1W^59 z1b(L}E1tw-w~`tHk~%;FGfJ`5U;cYrWBpkI@EY!_&pGQ))^Uh(>DtAI1rev<@nH`1G}3NiC-6JOC$Y4(gPfJ2{_sfZAkVNL{LzX4JfQPBTY^TC z-@fBrq*KYX*(GA410pA^Qt;B5MD2eMUyQm$|N|EjMQp!3uToU(|%$h8Cjv4YXp)G@Z)sJsfLD$OqsFL?E^4MUsC|>w>@j8pHDA^oE)~u1jZ=| zDjm?+g44YBz?eAXX8tMlxowWtfwly9vG29sHqZ+I(*ZsSd7iD1t=Cd~Q5uKT-f`)O zrZxwGWz0wQg-vn@WvDm-j^hi5>#(?dUL~`6>vbB2LG$VHt6T*&6gvYk>4wdFpg_Fo zgFxkYu?35bD^n6hz@~0BNpX&|NpgNKFP4-e=1egoPN;;D=XwrMO5EodU`#P!X4k&| zhOfowPk1=&y~;d)%WdAt_gH}74wxs>bgzp_P!xIRW7q(LBDR*S7P6w((o2PmyvSifT6*qY9YM*(mqEc304_e>qJRKL*)!h!IQ4|rh z3wxo=_+~BXPeS^V1NgD?n+umvQZZjdDzaG{qMyALFey-a${JBzt>@|R;lOT_-!o>b z)m|!rv+AVjGaT6cDs?DGm1mP!!lvijSxLV=|1p)uK?`Q^Ck{Q|*ObC=1g37Lzzm3R z?Im%)ur{?SMbf<ocLy^9~M{QWxOf?69r zwpfMWxF~_|60_u9I1lu=xvcWy73?={ob&W95vW48GW{|Y_- zhel2cQ3F*8>dN=q8XD4k?&ojq&mHZW-(4QJQuAC|7AH9&8%C>(()Kc#q z2UgsztwQgbC(iS6V}rzxLM{!@=z=0E@$kKP141y@`TMxrYTw49Oi+q>w+sb2av$TRxMm; z(meO21O-eYBB&#aI@miJy$Uz1z|N3*lkz|?kL3BQd!Fi#4({>&O3E8=@!!-)X$IFX z{`JWwo** z#B}$X|4hE%uBH?(qKHCZ8I!SA8^e_9_K;eTD>w&Q&=45pgx(T6ng%GdYD1=@j0!d;)SrXk)_vOS@Eawa2~WyZPryb11Y znQY_>xm&b;RGc~n!gv&Uj&)7eTW_fE8k82>m;VtZzh825Z1)ePdkFNRB`N9vJ&dg| zJ%Cq*s(K7lV?!B5X29^-J!NqeSscbeBv!~Xs1Y7|gi6^(NcJR_k?T6StF}UUPbEBl z<9kv2$&4?X{nU<0W>tpDP^G2LN_C8?^eh4{S8Cdv@?vTOuwC;w!yA)|P9>ehkI28f z=MD<(8O~>rRdb2&#xIfc6k=VJEZ>A^g$5O>FZdEtEUGTEn-NIHteU70DUAhz#vPQu zSyZnuS%B|amLB$>zLj^hM@j^`qtN|L;AGh_Xm26UuxFeW?3#{JuKtAC-l@0$nM1i_ z>hDcMlK}14q@6qL?NL(6lwiQ&xR}}}LT($%q!NT-uNCCZH&**{v0O(5aGPXL0c)4t zO^2V_NkQdS^JdA~ieBYh=3*6KfrPZKU7Nb;O9I$WgGkNY!P1KI74hxy8ZPIi`w@OT zeIpy7*09)d;lQ(}jTzP9zC3OcQ?;NK%@ytlZC&Y{5YdH;Rve6T?9V*xwFHuEhqCD` zRw&y`JkALD(9kS+GJOtTo<`$5hjY}Ogr@%GGz0noLMrXQc90cwI-d3jFPJhA7*fa} z=-IoAS4NbNzG9WT$$%SM%>cn{aAhQX7cQi^q2HPpm9{bIZh-T@w;C$+aDWqX>0l#W zQs8Vb^YjP(&d`OepA;>>_SE39^{>whrGRpShE$a~ft_t6VB;j*Gb;g_#ljUsmuDo! zd|f0*KbZ9{6pG0tRTwEL^_F5yMRHt5R{7g>^>SKIo^e8ioCWmEVL8q56SOwg#3&<= z0aND8^O14MU+Y^k)_L;naXB&9SBD3sigQo+iN|Ayp7jFK_1lXxQy+ z=A7UtkKhu$Y2EPfqlQk~Dc)n(;MXmn8UqE`{ue%t)SeAqrA@u*^B@Ti;n1qtBRy!- z>K_ZQdtJ$)T9jVLSVxB-(&BncDMBA(h!&_lSGoSUXd3ID?NwnKyA-{|uQGUGls`wF z)8t+;{4`nGIcyp7ABeV=-1g}Jh#}E>&L9!y0AvComaM>fowi*Xv|0}WjH(0PAuIp@n^+t7ez8|#P zP=dA#YI7|}MPwo@nvep(Q{yF*SqK?REBS+5iFrBKWR{)lhMY+gnEKkZxVptO?I8Y_ zXc0!pP5MGefWMUL#;v|C)B}UvDfY#^q1V;4th=BSyi-vg1Ej${RwryeEJQY!lIB(N z%Ap_zlY~ic_@ym*oW7SfW>G*}?cZj_boV&Q)RF1RNS!g>-2g)=)KEb?BwVMJTCF1{ zJ8z_vpPvt4H*AnFk$K8{Qpa&BdW+g7Ixlm+x*Px~jW#-_q<0=GDWhlMQ${S6OE+qF zJ}VIkyvJhwy!3ort}G2flZ{g4ttYFc%$tFBbgz$%$KiW0{qRHHt4JF89kg4+#%OPQ zp}{*!CoKgF3yA!SqAh1FI^kZubTSD?ub5w@X!;bzcriB{Yl~dvdcCvG7nhEvN$c-E z29-1*Tw3i~wjAqlw^X+4(!>jMy;=*a8?vcAl^RNx4k)4BZuwg(m^EBSrwLFGjUld&6-sr7 zO4T{Tg!SHDJlieVnM?QZLz7X%$DmTWPV$w-pzUcEcEo~8|DlG^e&A`t_|`S zJOC-GP}XdwObt0A!>n^C!Dy*EvRzj-PJBCS=L7KJ00^o!>c!q%4DgK*csHf0ey58f z5Mz|P0n)Ma;Yi%!Q~{Hl5ul;ouT#&`WO3loPHf(xYEg>7HsuIFSUe*bEqFW%CLR zsF#9Gd4>>?mrs|1T>}Y=CeoWuA=n-GQT{AA%GCkMTB+vEoS$b21A!puVIO=a>4_Mn zOi;y=sS0uTk^CQU%Rx4^ikGpkDmSw2x^F`Sg* z&k?BHRRLo|h5QdiNt4*7Z?S`5ChmF{{M1q$zbK6RDST-$OA+J)Geo$Sfn%jKJXzm( z&Q)KI)2csL=N%{7B;;hKF0@re|3?Z77&Fqr;g&^(7wV!V@2Q((eHJ9E4-sBa?^^yS zRw3Aw{& zfO?OjL?yN*!vy5YT4!t9zN)2d`{*<#rX{16I+C@^WsG z{*03K;S8KE{^3EEW*W5~C{ARgH+{m*03<`C&g5;ae7}lV<+av~lca|IRgi*{uW`>0 zHCg{zZfEE!T`O{nIjLRj*4!W6koCL-bvq6Tq>NFgln*XQxD4yYuNgcq^kj*2z-|ti z9w75K(EVkD0%Tdz}PfU^Q=8&7{PUBjVHvB9*N__KK_UiZi|Gxcn}tUdt{^By25tL6@r zR*Yt*!B5i7H03#Y2I{`-7_}@i?FFTK0S*11@(W!ofDWD2uTI{(*X+hFHPezWWyw9E zzO_8R#nOX_{}?=HPSN{H-82u&ed-BhR~z{hxDjpu2~GQfAl61v{J$Sr(PJfnN&V`@ zarRrH34kYbfv`Aun;BFehvf|z5r$j^t6o%P`cf{f>BO8y^U7JCiD! zoTd_q_LHGSB)(0b7?Tfj9Q?&iPtlzHayNTMJX<8Aj<{7>SE{+743*48lC;A}(J_@aRci@uMf^y_V3-bfazh(*DAC@yl)C5a+1`VarF&t}v*Dqx+Uj z$x;Qlv~h86nS}{TJqva>VwrYo5afrPJ=;8}p6An5;Otu}w5ni3HEk0^*l_ZbFm`fu zau!t2DUQSj?#|AfCW(=_Z1hxl5@l&F56?r27*qPm5i=)$%R-Q*BmaQ{ib-Jx-yR>f zbtMS?0~vrkzp3txTQnk%dE6Mn5<59{8p_qJW2p>ikH_^}PcbewqMmiUF8DG^c;lfh zV!jOc_7$k)n-S@S+>*dsJA1H$CgmI2gsPcnW>H3yhBTpMvdTqrUl-&deU z^OC9p&VL1vb&A|fd|+i4lLW`{$Zww3uTxf)bn*RM8VqCJ`v~7XCVVg8wp;N14>Vyg z;8;?)mNR0H+%j30{NthMNmI5JS?F#}@5jXW>$(WT|62+L_DFLh*swihUWM+$pJ=xQOWOd(_f?++KHjIH27_V1URvFR^` zl%V&~(Y!3uX(->Wo^hM<|HSb{ZQznrrTKVkCnGF#)WpytYy~ikAoVDV!{rN(9EKRA zwYgsgI0t z9J5t%ydQ6U->8$xKP%KGUfP|LIT+4)#8QL$#c;aEOaCOFu;UPTDC_Mm+#mg7D}3I> z^s?X9k(RCDn`70(hd!4}9Uj-94X0Y8}G^dI}Fz@Ur4b;sOtuRWm06 zov^?!3qL}uL)DpSe`A<8PnNTw4sw))^GoUHUq6OWF-Ps^q7>u4bicro;U23TO?^WU`K#_`8>$>==3@;r4te}FJs9Utqhur0Z#*A$ zS^DNQYZ zc{LA#n$MWEE?#YI)=?2P`#^aTTv3&#{pXUdFzX(;F_^j|8#DPsnoQpgan}HR5I3cf zQ6BKz?_*{a?u}-RR*4Osd>iN2deQHE25I~rUMH+tgrUxhxBBy2_OsO40ZuuuaXQWI zvz>{MBjv;$SWn07F)#I3X2~mR>;mJ|jLrM$8T^8GFBP4#1lt6o5`T2djMP<1Dt=!M zsmvJy%qnwI#Kw3LKN`Qfd()cE7(6~x%8Z#iBlspXrkA3mkj_LjO_Bq4ETT3^2kVrR zQP4KVnJ5LUr^z7P#AQC)HTGzo7kf7bAP~qc8=b!zAA&hi4C8WPbR@B(Ws|8slhb;- zrDapilBMWDjvBK&Bis)Dwc(m$*+Np3<>mS@j$AhDW-+=Y4HcEAp;`yV9J7+T?=QbY zYd)?0I&`WG`*WTgbDkG{hi|;XB$pm75xQqile0QNfr!3x6ed9Xb3|>|(H_h1C*GcV zW8-7nykN=6vKlpB%2cg>54WYi5=D&CXg+Pd(No?ToZg{8IIAlq^z7TVMT944UkQbK zSG*1F1rdGUfD2t+?urHuuLxW?k`#hDbnF(8^`*oVr>?B-{ZjQyDhw;|Pt70fVe6YP zRq{*^hZuh=`ts^ZYnuz92K7TZPpZfm8AWoEIO7)PXx8QJM()eKbac-$b-HgPmhY51 z)_P4_j+cPh-?LZdsZ1N{sDZKK3s$G@oqRoRrv-6GBVy8QzNFSeBP*uZZfckySTR|t zPGDireMW-O7~v_xWhir{cEG_hP#)su?0dc9eVZT*3s4UAuf_Lge0P8i>^dLsmgnLN*){3b(qk2%!pJTz@!oybl_`iBJeZ3C{Qz#l z@#`YSJ^e)pjtkGi-L!OCkbge@?`~-};h(??K4saz$|2B9pEugw9A3FpLo~2Yt#N6H%qz&Cf)(1FYZQEzWPMktzyCH(9mmCa2*kkGB^VulI83L%#T7_iY)+p4J=ZEj za4@j+NO|I)aoCN1QT(3Iw*Bky@)$>(gov(&cffVj?3&18pld`+*P&S!t~WLCc8UwW zU@&vj1Zbm9X%wV~0;}=VPyr)nueQ-j%ci76b2u@I`hixYQFQM>zltOw)I$bujLdts zkB>JbD_QeiI2m%i1NjwztBrXa`Jj}Ugo9^-o17fl7Xq$YC&1Jo6cKkjch1TsV5nu9 zMOew~X8a+VOoc5?N(Oq`vu3)59WH$=x+=nwz>j96TWy8U%p8{d0#}Q?biD%adymsf zdCVSP7~O`BD#_fOms}X{e?PTGY7uI-ke(JPEGSyh z1%N?K?xp6MnzvcGU9;x>ou{n(ka|5?ao_;e3`l7Z2T;E>y9Fz5oPKz2{fHW9-^u$s z&pIhk#q*brde+?Z&Ds1RDJu{%9Mmyp%>8;7vp9K))20l<^h-35+Cz!y3J>ots(M39 z*?5Z4re$~9E4rWCF!p=zdGVNaCzj05FXZp?)^rD51%YA>sEWlx_fr9AaJ4YYIA`7w zh5UjTl(a{N&%Xr>pXp8&`9QLb&w7_rSUtK3xZocgc@ZFJ!&Vw2q3Mw{VqAW)zRQXp zSpSpc+)c^8RP~np@y`#Um=chxst6*n`*{^8hPE^`)U^{1tP}C)wdN5*#!nL!1u1?n zP{QvFr0jc;@{v25mQpo4;X{?iHXfovbp32GqeYd5^ z`f6;|z!r4cueJ8favKWF_jJ>9o@@TZ!VKl#EkwT{VbWG-?{k>ApvZr=2eq2-4fynj zG;#FZv1(U2w7_^NWbpBfl&+T?>vA0AnG>Kt1s>-^75%k?Z0cMo0ux+7^#l?k<)1wn z&> zVKlgl897*_8NJd7oxyeJO~{OjP7sEr&Rct9*hN6fEjU3=(p4wU08c?7i9L7rQ+2K! z7OaOPU{JTY?!C2V;?YhFx~{E_6*-UvVu6;b)*o8RW7xuwYEkqS zVt)`m8*!&3y~94<>^!;QsAKzj-w66%CR}u7m~5rjan{j!zAcGyE9&A?B-YzSE#>ei3O@wBQ{8vaN15&?(lJ>kh2z)QR{R}kT|V5*dNXbtm4MRdk{ zzaG}1ysIgP!hx{xBaidpZcD%2vZIIy)=v5l@iPB?4~J%|__C#?QqqhOnMFpH?`Dp^ z0^UjAFQ^Tubtlo<7X)$+^AP5ZGdr=70Aej}`@2qzEO3s$-^LO5*9=4`x)-PdXtj#r z%kA0_O4#Z?)B{(S{}B(Q%%uCKPyDsu*xU?wM6H-N-$d?sS?_0-y566WI&{6vh4_^AhjjjV`B1uSOT#NSQ;hls zlj*0gfK{slynecH>HBiUV>Ko;sdK)nil6E0$GkPnI*Nq^figcU)dUMUq?5JsMmK`2?0W6?z%#4N`=J-1$t&vRU} zL`s%mdJdXlxAXp)cALx3xNzLe)sxqH<37RMJHEn6lPw^?vmRHz@2KCbFcr09CN&tx z%bGay!QVO#y9#fH3~j5~k4gHLq+gFg%UIxJ6#?ss0J1Qfn$Q#MW7MX#y53%DH|rei z#|${8mzk!cVvaUMlYOfHLO+%$8+;JYwRNGb=%mroKUJ)ttW4y@pmR`UR{1j@@eZ|# zr&2h{4cdx)fF^G(C$xK42KK)&Sy`qybgK;bP6J&Tts#f$KOx>3OkR2f0O`w)bOX3T zZb1y^jC4E(u?_%bZ-HTs>5AuBgB$N2M!vZ)s%AbGlf)`XIiO7z7 zaE*L)z}X+iR*(rpXD04oH=t++EG^H}>Q`oP%;q*_Q-I$@AQGlhS@xYT{^ zS5`^G>O_t3<2IF`(!52|(~#08I$Z(9uEPg11o!NBIgn zSBiby9o{43`;V}Q zARya)xtGcObiqBu&;lfZDZ|0(WKMhx1jYJ5Erj*CDnMBT7Ty(O{!B2fxs({x9;A*U zUj(u4B&zNs00UD|`W~$-z;%nN33y00lT^PGs-MeIT_j>5lrjIH>1%K>su(ZCz zR}Qjd{VC(MVh|7Vhy$Re@$lxN{s6n;wQ@W;>1mv@Y6@HM_K{4j*O_(?a_E2FS!6Ty zjJw+5=MAeMV2d&3TC!={{LYY^#O)@u?^$DGG?tb2OMUoU)iyd+Bz8!ICdO;t!L_Z} z9QiXgvd0X(JKUK#7#{qgK4b4u8SU0ciYf8cXdPYYxNxXA$^3dFd2Ma9)KAqXZ?$9d zj+UP`*fOn!BphOFT`GxG?q5x_gOHv_oo`bi|e9KCs37-=1bgGn)m+>-vh95@_ zwd=w@WzrmcIi-s{5-i2}{u|}KLW&)CXPjA-kruS4$6Pcqh4-4ipne0%VwuTNxIEJ{ z(nIu=?4};TR)i@!QLKSiaSl{XFYR(FR#m(=GhK24CJ*(BWsy5X4evcR$|D;nR;eY} zhMn?yxl4b2LNnAZu#S;n?SGX@rGSpTwdpfa`n~mXJ5)HN-U+dEO}dn5^)TyyX;Li1 zrcWDc2zcFG05r|2_Nm&4+yu$=!hvDy7{k0VNakdSGd|zVLsZZVuftwGV>m8}K={{% zqqdd3-Xx>~Z%1>g)p z1ss7zaE_Y$LP1cP!M!=d*$$>?qI5%kE|uTFLCeNxU-WZXa_TEMlk2M}4fWjv`A-Z5^iPU=hY zf8&16ZMz3UtmeFi`sYZ69hk>=78d)Z5CP`RkDDhTPpx8~ypO zGX3oLzq-Tcf@{VhUh@jp>*Xrege$VFas%5S7^XYBE2ozd+Mdzj1*DiNXCq!p9edxK zxN)Z7TrfUH>%^L5@Hg{Hdp|1|d|Fb+jTcdw?kE%Db}r&Am$;`P-q2CqpI*lPbZ!Id z-#mk`5q^xHn*8A^xct-sv~m>yi=ok6 zS$TfmF27)IGwwMdbqIKPR+87#rNmU2Oxv4)Vz}S)VJBt=>Af^A^uv=;Fled;GgN@W zggg?R=vSPsSLGUymn$I;j}>W?Xcx!p=MS6`+9%!*OdYk+@At_mjc};@nO(ZqMl&eV zfVS2`!}aO+qQ%++WpvTPJ_#PDow$IX9F_P zGa~2X_U1RSI?d?*hm^F#XNkyALCcfFoaU9X--AR?`>(A+xTb&9dzlOUm_)?)Cax!C z2Y;zF+4RRZj}6jb2Dz@@6kKgOC)zy!#c)vpskHmDtxEBO^0SWY^WQ>J9W#^E1DlkQ zF`(U7bMM>a@Qbn2_d5I-vfK+4#r>Dz=H3->K_@5$w zpn_3QVY;B@7UE4sITb7KO;uT}lKDdrCH7Fa*IDxLbD`ZG_Toy>LI{qT=);d3Md=Qf zmBt!n)c-)Wg)%v0DAl{VhbtbVFD}LC=|(F0nGQ*% zR-Rm3Q&--bbOW^~%IJhpsOBm2VcDnThnpWQ^eYbssy0&%$@hK2O<2w3#3;i$rhqD5 ziI^F7G4yLA5sG4Rr6K_qOf4m75Mc9wG0s+kjCqSi>3TAy>~cX*5MW^S!|TsvneiWj zVn^d$qxnz%?$oq^Nn3c@q&ZB!p zwPefd{uNVrQR0Lk3ix-A$hC|hn}L*Bs0_H_KhU%BgzUCU=p@yB^7%uZ$+a}sjGdEz z@yq*ifI&ld=y2rMzTA^Usj-fOgRxY+!0v)nO@Xp%pJF^7zfh03KqKKp{%OOgC^5S- ztQak)ILvzS4Q=idI_}>=E>-D^uSMH&=c`{Lii?Vi&gUK$eC^hSLoMnR<;t4qps+Cu>sRFBrn6{h zB^fx~aiSkC$pox^uA6G>u zG`f`>MR_V+etRVx1qt-4TkE)5+I@T`DnGW`fYOmd+UEjzDrld_0=iR2ImfoJ$#V`x zrpaZXI8=mT zh%)5&_VZppazwfhmHRBF&;D3WkGXr9EQ^>a(=Y8trwibG?`YUW&%IK+b3ekT%97>G ze^mE{8u)u1-x)ha5<4ixnvD4Ap}~T2&>sgB_Q08|#? zQV(j8xu$mR3ZaOu_}hq|w<_N72$wT3BBX_J@nd40H_&D;2B{NsI*$R_87weZ*l?42CRoi=Whi9)c z5Bdf7@5u;d%cS~k?TPcuCNUPgB}y?R2XJ=r^nLAtfYTh%#D_bjNL-1cYdUhGQbj>u zIs~*j5a^t&RuO!zz|Z@helFX?CsrxbZ$X!*(&D^v{q{FIYE4CDQGK(Cm8h*0bjB-3 zX`&x&T-RZ18u2c@)h;X-a2Zb{png$`c`9uVMG8$dmlX{_=>QPj=RtE8k~toUNXh3SDkrISJ$ENfeGLKDbX9~Y;idNb|ugoiR`C$M`b(%CO^Y20!unr_YP%JWz?M%Gn*o!z~0m3-ae*MZ5jqmdq6 zuHnOe4lxS6=s<*21bfw*WP%>HS5<*%S8(8Q7LE<&AD(Llx0N^w{Cdk2(OD2m-`12e zXQ--QibWk0*)|w6-PdRm_o*F?$)2K;|L!Lg@TX3e(yl<3vFm|+ft8NBD&Vx^A#ic@ zt2ko*-ra z9JvR@CIpQMfF@@NYR;=eW*Sa1AeH-)@aJ zl?Oby!tyFsdJi0KoE-nO9>#w$|0!7< zC3d!gKkVBnF@UmrGYN+bi87?b@Boo0zmn}i!sXz*UzdhL4erH|+*b<1Sq%Li{(RX+ zD0+)48c;SrvvL5dC0$&+yoXF{iK~*du@+Kh6k3IJGBwP;B8AP!)%6TvJ}X-s49|l! zBeM=kcK{_jRCH0`0wFZDW5}RWhn4+L!d-K{hz{XEx53wxV|PQdYD$-h1*T-t(6>`suCCF1nZbZVbeygt}`|8wy! zz?fxM&o-PZ&L2m;&G`M}(}k^Azg0DdTh~XR?hkMw)NAuC6y#9zt3M$qCh|$jA!{r0 z8+r5tot3grUeAW}Q3G)2-?rk#7aYy->gVoJl#&@Borq&i-wCw|*oA#Dgc)otp%CMH z{)Y5J``1zlSAsmL)ggew z&C&kob7ITF3zp{2KqSxudm-kHkm+;(^d(koLJaF;h}w>jE1tz78bk0CZQC?#r<=nA zpU*Tv>+>;}w0Vz8TRHZ7tJjRL!iEl1FMdjuH?I^zM0TN84F5=@e=?iTTJLG@;8DD|3Qhk~>igg5fo}6N+3;{BaxauWl{AcM|mwDCp zytIhWOBW1>!9vrnwxgpoqMx&p(1kkw?Jut1b%gYh0WQoxHL^$&p0AL z#QD0~cmSk9M;-)-A-_;FMUPcASOtyoq$G^ns$G{ymI6y94HuzcpZqW(PFo`>8(o>6 z7D_Xn_u{dMxUm2|%(mz4kL6=yGQ-qG>Cw+C&z?^DxpP+f>%!5}#SYCAlD$1kzb9(f z6HsjUlNVv(spZ#n9asQ;f6wevC9q5z;uD!gV&LCROm^|U9BOp`eMkm$Z#wIOcNRoj zviDl2B%+8f?Lw|jB96YF^ZxP>T$W`%v2|pzKPO_%Cy5X|8|xd|iUz(h=Y-1(_rjgy ztG^DOw$QDaGNQtVYHUt&JEnjE|j4c&;49;XvgC@Xg+78t?F?^Rr;}S8l z&&HzI`hxHr!3TN+Va$EQ%Q8Zl{j7Vkl8fB<@4?EJmR;Hhv=RKCh&sXn8;_%eJ*aA1a)o4XFZ zi1j_6rnfEpRXVklXcOg~F>Jou<26C4c@fby&3~XA2bS1;Q@oFVRaT1#PAhetHT}Y+hzKk z;J%;@4_}6GU__%LuJfi6T>U+>FVL7viBb#fBlWx<2j~0A6x)R;kjc;LChQ3RLhM2v z$L%ft!uoqTM7O_i~vm>r2Ph zqJ!W|86rPP;=^mGw#XBdtrXkejeCG@{ zVml0Fo)(9=;uwG5wcB#_Ci(SS@6+M`t&CN-XIGR={6g7aKB!ti3oheve9^M0pWalp zOC~PWtxBBsw-?rL%lKVrih`Z9aJ*Dge`}Oa0(sS4RC?&l+TvW@_cJI$fFECCy(lsG zw63bbtC99adYaV5uq)lWFLARQ-rsh6N%yY4MoA>N!xY$e4Z-n~bgkBOcN z4WmQLcPX6WVm4aMeFn|mVukCnl~Vm6{VYQR?P}AakkB&ScUrIRcTUO%tBCEskiP1G zu^TG-;1VEw7oB@z85I?p3lq9#a8cI=SqHgPT`u4Tldg*+@ zfnjOY?)uelS6KMA&RqMQ!y+rkpO5%_vP8gCYW^AES<1aH$h_50S{mo;(~+RNQgXln z9EDd;bTiBpuWNbBaZwD{PafOfHyjmWqs$ti19WxNL8-;;qw#+1?L&TR2pY9hl=k?HtL=UJAkC#yR|Zw9sSY03Oe?LHeC1YUmZy6HiJJqDT-*4i$RV@3TI++yX^+-KyU@%BUv9g{;Vk(hFhrO z#snKOGFc1d-DsnxXqf?0EGZ#?J_L@(6h#HGpcc5EL%wyX45eJ|tQ8e!^iRg(KOvkNeJa79%mn=1>!w7k7eRdv?vdJXv`_Gks%p(jn9Cleidpg zikcLuMP2I~nMEOyU-bv>UtMtHB-qw#ZJIOQT_ynRHZm}1;c2Qa{7LGN`2L3wZfpN& zoYEWUZo8o!1~*8Zc?|h@Oa16b+X4B%&@lVI^e}>k&Zrf6M5^v@;y#1cU2*qs&b_!{ zp8jBN->5?^^2b{Az>KHk+ls?Ai`ZoP1U>;~-QiBkszC}1M{jbtMf5kn$Z4}Wa~V^) zW*$<#nP4xJ?cXDD^QP+rSmp~qzS@-p`fT#^DDN4c?uu0U$0q@`JrWUdWzrqN4O87~ zyLwqmH-$8V6i?p#T5I=c5n)H!zFeO28$(3JZp1D-^{mfr`ulcL(K4M@*!6-8b{x#l824Yv@VLs?zq47H+=m% z=r8l=Jyyeg9W4V^d+)mJm+>bKTp-)|8C217iBo#Mt@Y}`F^AX~OMrAAsONT7V=KXU z6wz(2O(M@}++p_Y_r~@*CX^S!h&-lopKH!W4jfXs$SZL;VMdk~FGG;&>A@Bgzh((W zTH{&YC8#J?e$TZD`f^D;Zra;dwJ5m#qDRTCeLYkR#{RRIygZK3eOz!7FtUc^)`N6( zdtJE(i3ScYNWS4mdEE%0VBh@!dJEN1BzeKh_n29Z0-oO6P2O+yvW#k)$ZKofCd57D z0X<0>i_Wv%eeN%h{L1$VKHs+GivC#msbSbU$ID6%QL8G*HVg#9$iU$;j7pbA9Ob^i zWblK*BX9pT*b^i1OWjEB<%o{#gvPx~=KALk4gERW0@-c@%`1WO9n&n*4!m^QkBZjH zj7r@}>5RzMakPGC?8hv9t$I@tbiSW#XvtDRyOq}lC;gSB&)X-94Y5+6bu*q-vK%3y zCT~3p8PVd1Vn81O851=VNZh}g(Y22ecyj+2Yzj`>!bkv#-D#uh&faU#KK)H(nbVc> zNi`LIA~oLlUHVSJHK8=g^lThtv$xnk`xTqwt4wQvk%BXP@g^+9=i}mx{75L>=HavI`*;!rfs4IST`ngQ41CS3ovlPw&ks>YBT~M^H0MwRaW%%3g&js&SzBMTMfBUfPiK z?4$#D>oNG<9!>ny}_Lut2%2iYKa>gWP9TW5q9Q|P5*Yvjdy7MAjp3p8xt_k z!BV}IOawm!u2<9W?m}IWOI#ps?m1Jgs-QMz`aqp8FRFYj@aO<8ASj_`CC)X0QY`RK{TN8ru4hRyl|fIZ+_{q zjswAu1VZ272O@@VUvH(B%t;yoXzkfZCLM^_)2q0bvedKaa}8Hf?x>kjFZ%(DV?_oo z9QPUHVkijWsUo&##C5UM)`)|SzW}`SDL3}*G|&CukF8lD&xWG69Yu6ZS=ZB^J z$yMr8sq_-t(XXYvkx;R6DgL9=kKH&T9j>M~S|hS|IWs;7kIN~JRR4iUSKnrF>zgVr z=*4vB?nC~?l3y+Zbo!^IZ;%hBrc__CPDM9v=bZlo#qd-T7ok`t-hT)6dp_RjPGaO8 z;uI{k-wIqJpmZ-+WWVu*git(@?J!ic<>LpL$UhUay5x(lE!+6yC~YMUzB|3<=Zd^)z|Imwl~N!Z1@`{Hh})FT%VzSq zd6J}NRC3r`Y%Mw1{$DS{A8`~cXWdtoKh#eeb1)ihZGEm$TkNCbETXCuSP(kwQZFUb z)57+&Z}WpTEG8Z!;57h`&WmxEgDUa)UK6&bQ;e2dLG9gzi%%y_DYV3&OPP^F4o<$| zqLw()X0EW-y;XmoVYp8mH_scg_Gqu3dOdfhN_U;CN>a~9n5j2bm0`sOWlR5)uq>>E za%XUV!|=LLIc|=*xAx%|$4d8lQA5YqFFY$f4H{Ajv_>>jfAg?r3dAJcAEC1|FOi+W zC(6+YslK)A{0x@!$c}l18AJo8H`L!CF<)qFKCY!Q$OkwI@mcdDE;Q5u<9FhxLrPW7OnD<5oWRxaNSV@RKhyCL{a+FOzU|@WKH*EQI!qpB2Nw!cwEs3WmMS`1smvG zkc_?a>*@I|K{a+Kq*VybTTG%L5e5Z0+LfelLY4GOZY?M0TbdVEi|gC)-JrQMJnk&d zi>HrKhxiq3DWs#kzAuXBq->DHug5dcXlbOI82M4)tycAWMF=F{&T?z%MN;{T5K8N< zHpW8AsY%$+6-(+RY4>cZ+cQLxLzNg2s#wvy@2Pax<#Spp{sX=IT|5AHulwc!ef5sy zuM!7DjE;i+XSz~p8;$8c(vgmP66n4%kUvnpcM5avsoK*vd5vTAEJKkKH_P~fq93g4 zWG&XxHoTn6ORyK<7%im!jS>Gt{qaK?XBF`h_*J56gG%ThKAqNTZ#)_8&l$}z@;_F) z8S31WiC?_yoUP(D^_mvL${*JTOgt<}!4$>$fCJ$FYf-YclxziGK8EdS0>~VJ3lfhd zwT@<)woe-~F_?}w%3x>dUFBC}JZ^Fb8PdJyGI!2!wuhvSa#}o0ecSstrDS58^X~at za7E`U&gf5l*ZBmTzZM1nM%8C7o)Xa*fFSRa%Ves-;WTJh0Z;l>>3n&gzP|iyu$tHm zl@5PZ7`M&(o#A_q-&evpPAx4zjAT|ULW->btBo(#b=}bKc!Omvy}L;)6<0xZi}y|b z*&!1O{cl!TV3M(HR-ryUJGb*P**dbZ^I*i*^h>U>;B4%ov2kFSh-W6o=tTfF2eW_3 zcTRPMS!Mtx<)HZ*DjXw%lUw6`^^P23n)Lt3I;*fax^-JOp5VcPLvVL@2=3ar2Y2@% z36jR$g1dARq;ZH~!QCymJA?%LPw}t4&e_j%E~@DZ?z(E$oZ}ng9W-l|s{~+@2O^Yr(nJHcxW=bW|36~6aIAyg3U#8Ly1||Q1++*aYEb6F(>0Fh~9TV z%rvNFObf0WfN~qu$T>-uD6S0C$ah`oV5o_#KYI7S-ETsPQ!713sKH${8NQ`)gRv^B z$@EjQL&GI%SzhwjWN708C|@SxeQ(1=o(6f*lpo~+MlN6PmJ_*dF@XA)+D{w|nWAOB zcR8^DXBYlhVuMCBSJbsV7Mk~#qs6z!*~VH!3Z5y4NT0E3sQ%7V1FDc8lmn#G&WFx_ zQVM)0Tyzj=GHQ~vo{`xj1|L8+t0p^WBR+mOwnwrvnPiwQr$e0d!DOZE5XUf%dRj4b zG;n^X9{3El`@~1WW-|H$3yD0UDGG=wc^%2y1J=8?vY&-klTyGofdOXhkeMlYSZF25 z0xHWfT8r)xB?8PEdSWq%# z9zZOf^t09K)0S`nB=26otMdlp`AH!F!}3J3AZTXNhkGiB9$ca_{gZ2WPw14_WTgdP z*^4e=9bDO{h@*M_52%;82yyNZ*JYe!K-nCBakz3hca$iUhjvh|UoODM&EKt8UqrUY zi72{+87N<~Hu;nR#y`czp`MZNlKBUuGTo_T^E;1^PT#`So0gB8~`OYo9@lwa1~qP4dG(ugAprQd3Db0bZBQ9p3x+P_yE8GV}b&^co`C?_v7RNRMT>uWx&I<|eT$X+y0(@uudBI&p%+bYT*-dektHkf0weM3P7nUJ^4x8-kpxI!IZN+8(VLjBt*5~ z$fV}y_%OGdNsbGb;F*|So04pHK1b@o?v-q5K z6P0b=6xu0R*L||So;NiyJ8EGRAz9l5|oBN&Ws7y1%_7r-y*?1#~VlJz)ROns%)Tr_| zt{blKH~HtJFX#)$XqrwMez-K z^LJAT5CYZIH^#9Qrr=F=glk4gnaFBrGPS&YURlLqqHSzVrU9xM4Iw$(|A1bK;hXGM z6`DC*QcN}iyv6|3hLYq>i=Tap`_iyPl?&6pPAk?z#%SU<-}n$llRrdo*~8XM1(oM% zuh__?-4#|`quRRkWjm)!dnX^dvH{OHFH=d8xHM4kjm}gI1iyfUcyXd-PNS2xhxbAh zgY_~5R4vD{_s1*e02<8buB#M8BbE2w%JC8h=fEN$yFJb4+t%L+RQV4K#SP)eo+9`^ zX(5NpGA*5QnOgSH#L(QFy)!X`4P}RO`pytk(D-F722}oZCss}LGr-zABU71lrsXmI z;77gBJ8)g=qR^-Bh$%1ut+poC1AM4^E`UPsi$Z>JHrM=XmW?xW_-hzlbo?((RII*} zzTsyWXuy%CUCw&P1O{_Pzg&hy>zRR<%y~1Nc5C6==fegPg_07md;qW5-sfWndYg5X zsiBZPJuO9b9zDos!XGksBWu*v-tx#N{XuRZ`h+uWu+)Ur;|ZF88H&R}n3d-m-31o5E7sGT*xTJAN{nD&~! zwjMUh+dX1q#_D&u*ao=QM{SK;l2ZzmDxfKfH9J z{K{prwD~A`jCGxMMq>2^dxXbawPW+7slhP7Q9)0RU@gzne_b+h;b9;&AG-^-8%rjz zKtdP@1dIYf^a&MInQtx^!lYsP1~EoQnM8*Im0sccO(kp^>0=7i^Cff@NW0AH27${r z67i9}$*gyfRJhlBikYvQIxky=oc*9LefSJ+k#a7Vn&a*c-#=A;=zUEywYYt_AcWW% ztDUGb%dwb2q{|q0VHO`y%{~|0`;8Kwa~mVEnK)F=A3zy3^&`ZV9J)wu^hf=-F4@k@ zb*P)Yk@KCH%dUw{2+L}JNlP~?(V13?PS^k;Zyodg==q`x3r-G7&HbF8OZ=!!KWDx( zw0~WSxs7ezDD{Nf*o!vI(c#KlLCt(^Fx!}nbCCs5~YRH3Uv+AQNAX|D~(w9+f?JC-$tld(?~&cHrG;UYTt8~~U3_ky!6 zkbRp6?be0V$jMNFl_pI7xGahdzf9Q>N7${0v7NFfFnpRnWP*3L zHaqvQK@@J)T$caD4T*Kh6Xc02k`&sBrpozX*_9sB3N$>sfLk>7bU8c416(`OW$S;x z<1@hwG$J8+ZqJipWA5#NpPX31^}SIMvZN>B7OWgkqWTZr0(ZrV5qt zN1`Q!11TzQA0bCh!^)}fe6AsfaEc&HB=rh&o{H{L(G%#%oCy#I#?g&`B8H~Trk>U- zSojKU!btdcTKqD>mwd7WOCASC64)1X?c$p?%`VGPI-@>M91|`#U1E-bW*D#9(%+|r zT^=x|Xms|@*yVUnimB^;NA^L@{uf;hxZo;0p4T^kUGlF0O-Ls&t?EIb{txIB<`C9r zRr>42i+A2r0a37cT>71&x$6SjkT) zm|Dp@-xGH%k@_aQdYbGrG-Xt3`rgrrS8!TH^%&UOKEttN)$nr>?LhYv`%J17h1TqK zhXmX4Y?ikzKv2|EsUt8OLLZ39oK*9=)l&p!PkMQ{LR1FZ?s9Z!4keO zBO}$x98|L@xM;k zuy~#`UraWf;MtlGa!Oam=kYW`s(J!r(k7qnZzTTK*YZtNTmc0$_>lOUubi=pc-%*E z6DUD0M5mS+=FB1HiF;uAbSGC{AKwZJJr7+De%6}Ao0NhcNVyUKu#hwYtvRg6_~m_p$^=ygW!hZG;Okm6-#5Hd7^@`7l}qjvylz1D9O@f|)md&!XnC;IE_AhLA@@ ze4kB@b0h^Aj*hM?STck(HKy8UCa+CJ^W?8alY9)?p3+jB?tC)jv)^@(QV%|PBg9%4 znXg&fbQBkC+E9br{cYElcW2y+HGbc&JT}V@t(nb5PmwLY$%lmq>DIj)qiEiWsSgelu`GNF9iVxf!d>t@fAW&#P?ezyX zuiB^6tLzg$4qOlhraHzp2%Cz27qKbF$)Je#L~%1dn2_Qox4===8<{kdQ`IvnAV|c9 z3BcVFRAY?$@^Rnm-bjfcs24ZNAoks*rG{ z$ioTN=boSIj-PAF;y0F$@<X@!(z(Zqk1)fxYa+`PAuGBq?^!P!a=c&t$m4Cv`QABO$1%vOIslBkDMXg{ zNi80?zd9!Q^m9KtLg!V9r9~LM)pv(`=|m zRUaF0Hi#?t=I7{`tr7dhgXYD?0M&*el@Gyj_il6JQ;Lk&p<`?EYy=>-ATw ziyI`JKksWOS^6s^a;ukLD}H=!sxCsh$4vOezsxD}*swVb*98V*o}f}bXbR%2|Irt4 z%9`k^zBLbZaWJD+Ot)-3cs$(d(++)ihgm_U&I8xqA64R?jj+mm)sSd30sq?4PSu{Q z@rB=jKEJRH#hhR3S{9#-@&`Dd*tOMS0!7s*`=(QIiwl~*=6$)jdkcv z{`nRuAHHz7WY`V=TfbZR3$jh7)UE^xPz~tw(RBA{6cd{wE^w|OTev-ode115kzefA z9fmY+bZXc676UUu&cCH+*r91bDU;S6jc|GGFoI0qSLoZQhsM^$5@Laz-EZ5=4HLfe6F&ekv~ zEmd03yoysL<6@Kn2n`ybmbW%`6L90)ulX|+eGK|yl)~R+sEou*T)hrFf8sJslq7si zu-nLf6WjGRRz>0a69Y1WiTAvRg1}|j7cY&D3%%u@?d5ccnDq`}oV$l{o)7QwTi>Xd z6NXE6+ADsHrYoFtM4{UC6JsR=mLZ5}stNKu&sgs;E%)7wgeAEvf2eN7LZ6)hv@K!I z#lch7`Nhqs^_se?F~_2$QNN*w25*6xll|mJaLg7ozRq|n* zTMgG2G{;M)x2f94TIVc346_MyDOj8gxQRK}V9ZNdW_kOHc+C~8{*=tQ{Kq3NM0`s)Q?bouVc6- z65z^xMOw3kg*dKMFebN-;nfzXiB^EZSU76X(va`FOm5p`uHEtxr}0PI4d7|CJ(X^f z=({!oeG!v%uW8@diV1CUm^3=@U0GG1N?t@WpQ~SUpt}dq7OF>5WNy`l-`4lRN;gSJ zdb{(S^x8!a@M|*^psfZ^i7$mJZ}BUsoq6E%865JT3s(32i9T1Q)nF$%zW!I0Fd;CG zq)gu&$9`M2^bg44K#Gu-4OAzTPAbUM1GGAwh@ov-R}B9)PQmJoMq_B|wAn~&i&;N_ zn40gtk@t|Ibdi&gednu>VnB}T0A?nCi0Qq@oIv&l$HNkXJQXtC7$r&wtMgymhdCW( z6;XVrl^g@+v4Q<#@Aa%rHPSck`G*y6@vy_ZpY-tmWQcmiVlb5qDA4AB#_A{dG3Fje z7!RE^o?h8B_c#hB$#y9sXVea#;X1yyzD;cwZ!}C%KD%9LnF|w1WsGKfjmYe}O)-x2 zcgAgV@XgOJ%@Hf!C|X_*HJQa>d~QCu_x+ELBk?EgmAphiFZ&HZ{6QCbVD*!lr|kQv z9XwILP5Qlz0Abl_iBA9bQBZkxa1UDv+#^MPvJLzTGI##Fks;5s&1KRLwO!m=sbvW}+xOnbUwYj2tkLRM-Pr{4r7XM~C%Xo-V<^4zQ(SWf{ zuhdi}sd4l9rtuRM!LEtjpj{mIJiA9AewkZ!+fgA;zHG^m;HrJg!MOS zU~gy3`9d{@uB$Zx<+f@wx+gI7A($`I6T1)->2A(0#<}iSQq#_=C>J^Sbs*@7L(J$6 z&~)>e=x8wlKmf7ycFwt-F7ulF^m>}Cy<-B|vZ-%swDIMI0BSH|u6p@IIACv6kpl^2 zWI#X$&xO0nNrAf^SV;Xm->DYi{P%Kg#64FJM+wDY;uxCevr+Y~^CI|>7Cct`J?4fQ zHrxr`z^v||J$yh%^Vkq8KBf9_4j{MqdD1kY?N>(@@u&sn?~|c4 zk|(`z%2dhhX3fceK%LxDIlMLVPXuy!2BOH6*4Ddy?yTj8%S-{g;NQsle!qtQ;Ndp+ zV0^2i6;|6=5>tH?jC7#<^jAyst%!0Pm?}>dr!1IOVRw{|odEDxzA$12+%&~N?S~OF zue=n}2KLb4DwMTw!xNw^RLQ^c_X%>q z+4M@xHVE|!&4)Z^Z!bcTxV9PqTtXgkMjqvyswfC-Ar=IrM!}jYyjDz$gV!b#d~$N$ zM3h8d+j)jktNuBw6!TQL32yeJlLV~!c^pyUigtZsf6Y*WBNW@lO{c=Q( z-e-4A_g+lkXWb@=6)@OMNg{3ZkJid?<604N{Tc{wIwLmmAS%TgVf^qlg*A;20fM;a zCm4Ob>WD88OPyd=&iD_Ap-oLgsbji~*^82Ut$KMy#f{qEqzFxzaLys06`S|E47DS79LM3V)Yg>9XMLt$anv&~D%;2Ujd6@=$nOahv8idVgifsjBajcl z%7wf=!iAUf2zlsbIi9o|zE{*erU`fbXC%F>kZ?h=|X5A?r-=Rb@YTDM>g zYO85>HGY{eMnv%3`cwZ6rVKQ)tb3_0jzjGao~Sc8Qx0V7^ItfEjL%-J4yT95abGWe z4rS?2F{HP8=Q(<)!9UfNpIP-L$N^c0YQu_^@?NRE!7X2abusK`p&Y`Adb!{C%}hSf zA#+C+uM|!xLvD`h1X80i7EgII2*_q3=XLR_btbTv4Bz)aUBsI#1*w$x>@4?iyO_D} zaNwQ!vyB9C-HXtBDtyI4jPO=#s24*jf82q5Pzfwb1dbEFA4s2H?<676JQYMb6~AG- zqKtoJX6NX+b!1dv&wPpKWgte{9e1qm(D)4!L87RVOOwBgRerS zU~XJ1bzn{kDt&!U8|)Bq)3cb98R46WRrS&ddy+H^I?niWIwsvrWI|7RrN3m2;9WjT z={(9Z##=;{9|rGm(aN+QxOHTSB~DAa9p<&dqhz>Ov}IWJRI-DcM~#p4+}>Qhh7iA@ z%`d-|WYPt^L>}uTOT4d0Qa$bTn#UdbB@mkl(PyGmZ{%`-_-s_U`Ofs~-6E;{ zwb4MzrlG{c^SlS>=3JbG{@PqxRJ^eS*hWF0GD*J z(ashpha5p-77r<0?L7#f3H`4LTR4z`UbU+R^Hfl+f$&fzg$XII zOpndIu%OIG>wr|e?%};@rsb?Au+X`fD>V!)EVBMyrAD4Y!k$*`$ornaaP zlh#}g1lFDBReheY>S%E-1#G5dVH5yK@Iu6AtJwd(;Md}|Aw2GH@kzw0b{m+F$bNiFc$}n0^4>J3g8fc-d16*VGZ=n?ilEa7=doY1@(c6ux)dD{!Cjx(iZtV z)utQf$^lOXx)Eg&U|)S6sFMn?ta^RcFZB27t2g<^29La=6+?B#V@BBfi0iQycR%m5 z8T!(Ss^#FLlIzMZ?DQTH0;^gs>2gE>`&n)9P{LngQ(|t$g)1{4F@sQ0V8pvz1%q+E zBnG)C?+WQpi_MGz#{J(}JP_A+Q7%$=n-@i$m&C;Fz zQ=hK9uq+2U)_s1h^>xgixi$h;NwnrIDGCA+v)GFG`4)M7@)MwCtxP}z&tS>M`-qSD z7cXYPp2-Kib^nx*{X*N>vzW8fRvzc)-(EIl@Xc_C;LJ2rAris<^M*!Iyk4zv0!^dr zPpr4qvKFFZyQgrKj~WUG%{@5Fuf(f~QqD8vel8=m1{i_AKUuZ|*q&ib!(_dE?~u8G zo)td^anW9__h-(6{s%`U&Cs&(^3evppT|92h`a|5yub_3fm_}I3nT(@+fvw)LRV+z zJ$UX3`SPmD`k2)U2iqha#}iC&Bc_SU;H9lVkb(;oh#a$qxbVgDX7BO}9gBpDIJZA& zVPy#X40Fdu0br;TuBE19$WANuHSWs>hF5&cp98^qb2WY*JwwYO2z}bNjHxLOn5Wm{ zBtW%*kYXbpZG0`Sac0UvH&Y|SoLt0NLq0+sBUPT7n+JO*&)6**}`OH%sShKX|9O%+(b zpU3H?<^0rC& z(-Xb)X`F9r%P@$CqM57q?8-QfXAMRTln1kw1?bF*+sr>PQc|Q|z$*1QFDL~wrF`P> z)SVhRfH~Wz)%4J=w=);9;>x>YQkF^KrWD;p)-}B}U!_w10R>}%T?;m1?|-~VwDPkh zMr^j4@LuJ`3iXBc{Ly_bA-eXdzpGvt>OLR+A#lWH6L(D$D~axi@3~KFwv)hGYEEXf zFtB5=9Py#U>Qk_6&dJvlTY=L+7a;-!8F387>FM`He!D`4m7#Yti@|Ev?>hK~Wzp_O zcpshcji%h#i91r+-kpET>AU&;yBu|_Xp{AR%1>DvV8{BKR=hN4oUY3jNNTM7j?D2S|Hcgv)pWjg+=R!)2rvkkPsmB zYnk@lMnd5PSJ#H=pGYnfjdtxOIjOS-_?%10J(+-JxgD@|q_$Hbe8O4}&vdLP1kETL zj>V~A+MM+A-P4s-csAIGe`gZKnx(sR6Rxk=&`4GXBS?N=aT2*Q@5mz5=dJ)u!n!G) z(LCI4RfP&F3>^-R0t?1<_am${x8U}6w;UO?!p+9YLQu*8d&>JJKn}GA#^}tTZQr+P zR^`pk!O|W;5&^HG1app_3c#ubLwWVa)7E4w>JJS4?)XPx1{{Cx359FnRuwFY{1rA( zljVon;NGVrpeEYk@B4F_jCOhv*UGP*h%dW>Y%ACIGl|y4{8J=~GQvr8v&)3hka6w% zKn#vMAC1?=BlWa0`kaiz$%PN3UahOa-9;}9T-zLhLeTbHXGN2}IPht~uiWLBhvnkt ziyQhsRir}Y+V4-OKi$tO!3+!+o(>m#S`T}=tbR>eCL0T8Qm-Bv`Gfxs0N}l#HVTI= z&+?TVD>j87KDOW%)^W#apeZ-hew}UPVAVLu2?I4RLAX%i-Ccir^^fZGm=CMWuly)Q=49oPzwx)&c35Mss=Y*TTw3HSu9b**H_|u2J2U9iW9NWAy*!`j`Ad3=Ela#-n`S}{xuKC!iow$>}?Bt3u zPxEHEy)EeMRbCkz?JGtp1;SYN$C<>oa?jAUax}}TmA*39MD;KMq4l_V`k=~{Rqm_2 zwv(yyrrEuZ@e9d8QD;V!uGy6rGy!;lfCqRiKX7}x(dbqLbEsU!7GL48%ZWkOKdTlZ zP1*E9*}dGGdh?!!2wyis zEU)k3G7Iqu*iMBPW=Wag;SjrM@OI=L+?_hfQ)J%lSDpb6Jbj(J_1m~3Xp=R9Hzbi8Smu+b!||*{NYAoHm^X)VHp9)l~I@>Rbr;eDh!{`wFEH^oeyE~ zjRIx`Dv(}(qK8~AIJ9TXed^ZA@0`!xENw~um2CPFnS5Il&3MZkQzF~ju0`8rJzeMq zCRssoKVRdo(F<-LO*sgx#8mvzMm|rwrGceXx+W@Hx?E3hyp%)^C-^*>WAS`g&jBW8 zikm5KKR&+=<=5YKrXgA{bk|B1Vpf~apTokvV=;V2Pu4Vi5(^HbX1qJNTa_X<=nmfI58T9(~#zXP6Red-9uT6s=^2BWwKoQ|XwYACe22tO8D-%7s(pft3eq zCQ-hTB!F_`u|1SU{sOUAU~yTF_&8`@Tn=Q`HUr}z@h zSTXX?7#K?W*xrvo*mp$gyyP>Opt*3YSp8dHdkJ8s_u_h)_T@d+#kjm5_a`v1MqlUy zxud4QeV{Zh0>1h>jbc1NO?R&%1J`lT~b}sD*)KZJ!Zj7j+E;k zQd9NG3{iMrBev{k4^y+UU!!EY;C8tC6t*EQ@ag38>eX=}danEh{ZpTGMQ3&y>*iT8us&r6zxF(FO^oQL6Dt!juF|NMX%V{wit0#L!IHpH}AnDZ^uK)WZ zg;twv3Dxr-VZ4kTIlq8Hp2vX7_f3?%ip*h6&*q@#z3BhFO2?QG70XjzW06oNDj#0w z1(G!p*z})Lf1$Csnq9Y z-$^7CPxZA;smG6!NqKwXq(6=}f9vQ~yw6$zIZUK}XTKRK(c^ zJRumyREIg*;8P;x%8MV^DP7qFVh`wI5iI!xS6v)?=D72H*PvigvYso8(`D6B(4rN7 zZCUeWmdWv$f0P$ejmeN9FPV( z9u8fzJoMc$KhwMsE786n+*y9L>!Kl78$b_$Z5H;{a+So~>yGY+6( zOd#0~X{>D_5Ul8~nHL5iya8GapbvRaQj(&dXs?*%SI=jEwRX@4FUwV95CyWMJf?v$S zw?pk_Eo7pBj-on#u^YhW_o&n3;pjoqB$~>F#K0r(6y4R(){r*fh2I~#L|oi4wBt9>VE{e^f&#p}hJKZL{X^m^Z^(n0QN`Yx4!QhD+|vP`7ZHNmMJ)tltjT91xrN{ku{9 zn;aRp7|@zC$v&4`tFOn`34JLI*cvO zwSpqSLlIkGK(5nnFgy)M3o;Wi#LO z8Kev_uBBw8WT6l==^y~67b$|8zjvA_F7|hp>79cL!wZ^-4uM)(Zb`3hYFfav1dx|S8D(k_h@sb=6YwwKL(T>hsx8&caB{HysCRooBnSJ% zr~{3O@oyVfr&oOU86m|Cqabhvjp&ybWuFehbM}ve`D9*l?ii%Pc*j^qaxyZ@m{o{n z8xprHb3mih4}yN4NJHJKp=+s$d-~wDr70iC%i#WTIxx5hwq|xdMQAR?g<=D}Usfmf z^qNbe$c*tJv4AHCWnm_Gn8c-Y#%J2PLG4XU@?@3+$f35H5#LbQ>Diwt7fgt=(3`$S zB!Z9D_53xIaIAsh%5O04_-|eYhyW_eSh1VClF3;U;6A(`2L-UM8-bY$rsd>ASdxZlFV41rxo%RYy&C$?a@YX4- z(5eDRY%6WDidwd4G)O0Iy57id_1=9ftX8TI0rgR{OK*VVcJFrHAf>#lQDR6e>$VCN zk?xnG+A=8x)RO11ro;`75$LxY_MePpofaoAQdcC54%AjoLQ`{NM;<2McpRxtFj0CC zef*LV$$cs5waS9Ug+T0{Tw)W=Rl+sqm9Q;PsX>u-m#TH8vu51Y)X$6nMkAl$!((9T zV<*7;uY3Eyf0?n^)lh1$zPyq>`J;*8;6dLsOs6W1R(WCu--x%G?p?C~GV{e&D{OQe z9?%%~21n$50~w{vX4 za^<-W${|Jauf>nXI!#edv;B|Y>AV0wl%#&2%vey6yYOsOb-2VZaD{6Rz$KIJ0n~Gx zk&zHb77MrGx@t_rr2*Vycix8@kv+Z6)_*{TVjlxh`DGv=4=Z&ghPWrbB_@R4DZ43P zT`-xqPd(9w-8g_a@^)6-22V^!~w`P%glNC(N~ zrq6W{<^ZPRD6ogE3i8{T`Zqu6v68*WoU}*Wro_kHfMZl{B2|v_zZ=|G<@S$T{VB9Z z`~?50;lp>*u5Zh@Ry6(>08~}CUN}R5W7~jh7X%=!8)PnZ-5mS_Qfy1_iX|xEY}CfRVY!2rc}%)5Q2kTg;vdLQL&uHa70Y)*{5wrR58DclyBx?z zg5|vQPB%(1Gys7SlQoSxp;JF(BaxUX#_+IE=_Lp;NVl8mJk9HeTa(vrzr1ptP$`kv zDI~={p9EbI{fiJaBmr2(w4^X{m?fHaz_vfC96_p+MnvuWJN+*rBksQRIVuz_83O{6 z{nuk)a=kkshTWa+JFVQ&F_2DXJx>T*ipqV*?F335xZu}myTDrc;QUU$J64LQ`20>r z(ARoYJ5Rj_@A!M|AQyg+V;WyWN^1ff=}P%hFD6BRx_>ie8OSm&xQGW8gtoxz>^B(qNw?dhLwJ_)J{Rx>$Sw0 z%0U%gn>|{krglefe&De;7r+ha4Zj z5czYqR}(=|j=4At)5FyKqcOQY6Sh1GNjRRjBtDj`*`Kv3S+oA6 z@NTq8k{ zE2g9-ehy#r8$m!vCvZTL;l{4Oixvy`tmpE!$K}hY#il`fm@xmyH55xwx2-;j_;d2( z^i&wL3YqMV32qOZrwdJ^rRjntGGCIx`oX&FH9)4=X+$->-$W8725y5ti2mfW_u?#v zC()TC129%kCB9KXkizazH(dU#*H4>S(YHSj1VGzyqBr1VHyDvx^Y%yTse04S`Yw45 zKYQYjQM`22=%CreE#1H)@3?lsR z|02!}zV5O*Q%~Z#rCrD!zz;RoduM z00v&xnO4Sb*6YGHZcZeITI0hOflD`lZtZ+w_|w7u)l3i6(7aMjef7C#M+!yGZ)1ba z)AnWU+=QvvEnO{WVMA1a}M3)N-3)QWX$F@y=Mf)~8mek|hrH*B&ogUad-1 z&sKUmpyfjtnFOC6yRuW^%MYK*=@lY|@hT(mH#nQW3C)Fc`eF)pKkcEnMl?h19cqh|F#2G5+IUe z;`6(}#|{{uE^4$^LOB_mlf*cN7LPql*)t)F6K|_z8waN80O2idU`rQvZs2A1fg!c@ z@TmL8_FLvX>sKaYEgQo}VvW6{RJUm!QiRt^?Y$bvS|ZMAiGf9qbS+7gp)4J2`A)9l z4%F5Fb`dozl8+P%HM~fUon~s9K2nh2kQrrU#1?9NFz?46W8nu&yjPK~|JGdp8dDM? zgL5#dpWD}BO*4wOD2{9WSCfY<6vLbg%cB8+Z8$^|`rF^}XQ7^65A{@+J0V`_b#*$A zd(Z-~bs8lAX)u9iv^1A!-`ZG@x%H=@;7FGvSSx@*R+Pr4Mh z7EPyybJuQ~(Y(bGRW1a6^S-55&1oykaX%KtnUGTMfNUFxK-)G`A`PUi7sJlM==>I= zWddCGHJStcv@Mx^=IZJ~ia3OMC~ogX?b_@lh8kt>Zotz-PlE;0pWSSZ7AG7cB5uZe zS;WwEkloV$Z6gd!Q*+ph{*^KkQ>Fd)!RuN5)Q9Tyxt0)ju4yiFDJSu5KS@#E5OsT` z!mI08+L#Squ2UdGPFg3?#kkrWPh)Puiceq_#=c^{vO=|{tg)pRizn~(cS=j@byJ>l zh{yqbZo()pR;_e=bFCP?2hD+C#@QapS zey(EUXhpE8Lh7avJaXG3jQy&L_-Jr?UC?Nn1F<*bw zM6xgIBmM_Olhs@H+~A~@y3eYwasE^isF3PVzf9Ljf)h(4$_5K;y8KoAkQDgbNAC8H=cxFnOw;^2exbtw}j7Gb=cU^sJ z#?!gnFsQvG5vDM3SxW|$KRk$4mc&oG-X+m zWV>o*s$2X}gup1HJ~+a3T1JSVXLTEc(76vt^I)>yT>Vf-oI zQf}3vC81`-jLv7x>Qf@nR+fr?IbK+bR=MsVVh$-3B()%z+t`nNMKDfTmfY>h@ zP~LpqX!Q~2*l@*dQo0eFFYR4ogg|@!9*i1AxF|_1JeK&Hp&^0 zZ3b-NKtHpVXzeB0K74xd4~=Y$O4Z7MV_pxoJyP8E_4ZtRLVRejLNd~;qX~UIx;3)N zv=^KA?@In8aE0b+c3(iZ7&G6+x=;$e9Jnle2@NKvP8^wa#Y1`8cg~raURP>P9jr%L z@6bo_t6Vj0bJ+D`ydP0>@HhR`O*k6+gqfh~cK$99w?gN2Va0rZ<0f%2(6$md(?GnT zGoXo{Bl3ylX9tdB7n)Jg^QV>x9GfL_|FGA`Oyo=YAT2~TeI!_6t0(0>|MWcf1=W+> z;A-p&*&wNBO#LtU9q1^5vQm&sk!(L4f-DZt|oRT-{M1%8R%*8`ZYwvbf3Xr z%I+P)?dU90n{)KF{LjqjWMz%MMyd9otBjq!*uv51z=f8z(R+&#( zAP4|E{JQ9U1xe`>YDfxHv$ZY?*lu7}cl|-a=<0E$el%e$lX6S|%UXNN>VHJLvO;8l z;TVP&o;;OF@W&#>ZW%8F814qC&AIXYMUv)4$k+W0IcE0>;WP_VsQOkV{7dlz+I8(H z+4tA;{z0|IJ@eil$ie;NIQ~Jc9j#`8akfcA4G-dNZEn2k!{1gS)VY`ke;uju;?#`B zc{Py+f5mgN`e7(f8|jaZWf0q&6B@I1$?tu+>x!IBOn_i?)SF|LNtIbWDYAP`N?4(HSsx-E#6(NgN_Xy-XSvzh*Sx6G0a(93m|c}z)@>Q0 zscxpYh|C@G(tpl1hV_^{st}Ch+ZcQ}b^zVVN65g0QJdM|{KlR*SWAsX>8|vs8}(;% zE!2~>XEcv}KR$IJiaa$TMEbbj;^FPZU1-kzJ;3BmR9BH{19w@Oz0 z?^MMp{aZ)IEI)BxL!-nPS62yx@r-;3w?X!b=gQQ3J_NcHu{f1R{4>?!j4(_fzV+|P zJ4M)x0gEhMVz$k4)2UKtxV3lE4@^>vu8a%-OCq7vC=!Fhr@WAnnNC(e&=q_0_-k98 zrMB6jYoR+ZEVs_wVeeLl+x#@O4`io=-+TW~n`~klVYfr*2FeIV;1|_Pcsr2Qx>?+H zo|sLQS7t(YK`E2agfNJdgQe!rhobLTpZ_%>tJ3Dafl_c>4!rGDDskhhB0%K50V>B9O}`j?uCQ*d>MLI9eyLe9 zGheR+HF8?w%a>)|L-}=5_hya*w$YX%kerD|d|k>jwf{R~i1P9xWLA+O&D=pC`jK*B zsHZ4!FGoK3)K*eQ4eh*~)_1E{U%l)N2A(fED}ymGQ%sRrgA)Pe>eMAiDmlD>bPTvA z5adXT!=F#9KT;0>yQP!ApJA?Iw^E4}h!%3gE|0-UV*lh!kFu1os^(uWk^XhV<-H5T zg`(F^>d#Wt_w^OS6=q^Q%qZ%@#MQ!e)^px98iWq4ehy8h)^y&Z0cyW|~o6&B2er?CYyhq_B=BfkV#Gn`jYts?vOz|*f^@xDC00E%^v z<|RYx9AC!;FMs&3sE%SQ+DKl{cxaCVpj|#jD}N!Lb|(Dn9l#Ut$jYg80WJ&ZQQ4`m zkq%=;%m{1!YnLL=puh&~0Tr%~0NN^uFHK9;Qn~a)GEh(fI_TuD<4^k``XS3W0$_tX z-C^oa%{^*RRFCPPt7tl|JG%r3KG?tOk?(! zUoy4C;DVKJ3cIHars#^dwINtmxpkx#|-DQ>s~OX=p*4Y)H?PNb~BQqA@0y*fQ11ydj9v)J@{Lf zApWKw2BmKX_`#6>L)KS@HQB#^4=E*8x>Gs?MmI=z!$|3o(j`)YFgheAC5^xk7##*J z-Hmj2OWn`K{pIn)|`Y(1hPCF7NfZqs7Q4gSJK9 z*@QHbZlWF`=oszi+@IrHvez9|#xT}f*Nx+Ua*=<`AXI1}6!k0-_LVj+?~_^1isX~I z9nHIDd5d4|FQm84Tz#Bhln+pTkv4k?)L_DZT(W;}w7_P|Nf-##wJW539x^tIfB^ro z)FNMd4-t)Q-{UkSzDi4CeDa%9iZW^KY@@zK1fFT2I9b(O&%o>oS$ulsp}1l?#an4& zN2Gnz<@CjBjB_WQLKHJ{?EmE)dEmU6A{z?v^cR#o}AIrT$cS96$Okdk)DhD`msb zQqP&*7VBB(7VG(O%#}|=UM6c^W-UjAnC{3peNkMVy!&(`FeMOaeW*2yXmntJefH=2 zC^G&`ch{s^s7S?Rs6)^8Xsx05JO5~f^cPw5t{g@m_C`v}rs~7X$m^^|yPI)w4fx!l zCWZ!CrTT;f_2H+%S}&ewNhsSU>l4{o`M+L$@1xIrW?oPcKcU~Vx$k-NDfJPlX=ArC zK>AJo_@2 zHV)K&xq5Tg>7IfG+Nr!1N>ISPS-tiI8#)#1GcAITt zsTIYwczn3}gl-AYxb$e5;*~CM)5&t?Ke5~o8?aC;kNsc*2r`@rGYSD32#)P%=k)4* z&TCVFJqSrqt&&wAS zx{?S_&bE>kL~vLJ*hAc>ehTQbyqG|Yxb;f4^E0+Fjd}*_DA&p-xV1J8xRDrK3aUf= zOluDHG+IGUJ8g{P{KOJY9jy1yMyoQS-GOrOd_ohn!b?gm7?0fdsgV}xfI{U8v<&G9 z4OvrV2Y<=Pt^s-ex(2a7(ck$uS5lti$xC14;*}X5c@0!&lmic%Rbf?{bra-pFZRce zWQP7R`it=^#{2xi&q?CN^4-}Bj0Xrhp44rlxAw03k`e}=&a#(IioNi#Z}URD2tIi% zywX_8U_Tv27%Hks%m6t1@`At4Yp;vl4g|nEtHZ=niIyBmZ5YCSR2DBLf0TGfO%>D>fZtW|Uui^!PD(N@qVvS@dKgWm>1WgS3R0_fSBV+m zt84eX)0VyfKOP_VG;Wqrl4T6^;pR`3#)P8jcjZ(r7{5(=#t{f)R4D~jpSz9io#ym` zzps~61j@=Z)@g4?F`PqsZP?z-&;Xqo4>91xFqVRsd4S1Q*&9fE{JSOvBk)+iyz+o! z4IeFB@qn!qpy$}li8_5~lFN-1c>e+gp^o}}lav&=lcF)QKKlmxEcP>JdLW-oR@cUp4{*I6o3MEA*=e`i zM4V3<%Wi9beV{+!5f}3T2MB65#CfQEnH~*vEI6)p-Oe z;Rs9*Jq~aQhJysbcH02fEWSUaXsS?#6C^UMfnOlWzdvp-j`}D_8MJw-BkKz8e#XFa zLDXVB;xxrmrbc@%7Q_}|{;a30Zjv!301Ff`CEfHX0~8eqsi5N1sM$DJHo4}sn%@x= zMEjFO^YaU_rJryv-p5)sk?Ej3NQC5~6M4Q{rDw(W5Y8f3di4JLNS2U6_8G0 zxcZtK0-%Dl)p~L$pQ#26nSRbG?z;a{iOd4suV;t7=E%E+PSU!`b>Uf@J!+gMPgeP3 z@a&$L)#r3;68-P##@WI|-HCCn9)LvQf1fERax5F=#)k9rb+n;C7Lu1zF4oz*ppTvx z5_oMHJ|-#k>g&^}x4Y8dSWLCBo>tS{&?&;P2(0>9DV+sHnyYnx>}pN&&A7e^9e2R6UROyPFwqRnF2}=sYqT8pql9)zyS%k5kL*T z?u}^xyx&9qfyrw*&KDrUMnHZm&>~qeP&oJ!*d>Uj9Q*@|zS&)riRU@DlvE1q+AT{n z4`Xe&aHU<;v;0CNx@^7yIw&m`XZjr3%fCotlzmARLp9r2q!{(;dwDY7RkO;7L53jE zkL#9d@_mmXuPtSzyyWiPWV+D%NXR_FyO0vfu%qCA}YX{XmAafIEfKJ@Jm>RjrWkHLn-4q(*t>} z4ESPzs@aDu@?7)>t_o9b`5WK>CqPWuMmHTS!446~eZek$nE-7-TK+4>!%Pwak*M$} zoG-6Ckj4ZDzpKwT**4IiJgyE_M2pckB&#&5ngkCKPe=08S1q8ldm@-S&4?ODtxunl zgjDOLC8{sE-&!pur4>VzK@hF@69-2}mFQG#9A05@fl~fa=sk8@7U}{~eSGO65dDtw zYjw07GHqfiF>UERlsn*EwY^9+D&bfbk5q1P*69jjtMpg}*T-}g87n+L!vydNbB!a@ z@x&;XHDk}iCL~?$(LrJkvWLs&qKiHG+Z4B}VMdXVc(`p%>W;@b7-i1nYFH|kI?W-G zyM*S>VWYCPYlYdCfTHu}aEfq{DA@K>gI0qk#$+@CNM8k! z!NpD*5lM!~!>8>{OooW&IAH|ln^NZkvqh<6fycSnO?7E*#r@jWw0IvV^@GeS3%zFz zBAvZRMFpM4;=uxd(|w*|9Q-5^{WEt$zf|R;V)Y*?#j(L zN4zySD)6xU3lzpMN|Ia32ENHFsEi57!R72M#&QNw+NV49vBoZ#d{n8;4&sJ5ugX$ry^oZK7#W`HN# zPY%-dwV^5)M~C_xpx9D`M{>m!h<}ve*iz!#bi{xdhavphCG%0J5ZDTTw@) zR^F{UU5dYNN8-h|R%XwKAI?e7)IhQ6Yf4nUW$UMs@;yz|teH736&inMLT%E&vr&Mp z0(kEr)P}K!zc19*U01@Kg|Xsw9VD-)%weDgh*@13t{JG-lXFK}b?nqlF0LST7$7YoLvXERNi21r#sKV#eQ8EH=GJdv#2H z{};%)V&p)CKq_8*e>SyA&HN|Hq`4UTX8Sm=1t6avs2{0hO12OGaY=}hr6cXkaX<{V zWga%ra$N3n)O+rr^ZqZ89es{Ovz0{=r@&KniQ^)46?`1!o);~z2?PDg20RM3RU)b zfKh-1{6&$0rcfZQ5ah6Zy)aQs(O2xn%wJwF;_^jcFpn($*v+H_5RRj{{PulkKi=!~ zYQ*l#BtzFo9p%$N9)ogz<4*$A#_NH&&WOTdAn@UuhwwuzfRfY_wfZe@uvvdi(4eUz zyDfWeZygT%6;t331I492#CrgbHJ0Lb?EW8GO3b;BnqoL|Bi8~)a}He|L|2yYA}k^ zQxZRyk9S^O6i1)BYE?99ywg@J^7`!uqFxogUvmYPY6?=%=S`GEQ$GUmU9zgajj*;H z@NLYG-YNuGes_g39F%*&=S&skCerQ%h(cY~-3Hvic7!N<@7SvAk7+(k9xUh;JxM*M zG>9}cR>J8dQ1Ztv@(r<4qN-HeaT;l;1021A>>&x;o$! zwMP?cIp8iKoklAqfmSg;73UJZaW^9$k|`1#)#}D;xP>cMPQDS&q6xBJGD1T7_E@W} z#>Q#-YmF2pN~ZOF?cmx*QZWC)`R+`Y*Z`2i8^qS11Z7-b__PB}(R}m{fMNbaem;C& zbC1DF!mkCc?`#NbhsWXC(a?;t?Pb9od%`hSEK`=}Qhb`2WsT=tcXgAJ6{9old8OiS zlBlz!&u$`>T8qJA)v)H$={~DB+iZ!U3iPGGo}xndT-lABkLEReX6%-;)a+Ruv7Gq) zGbvK=x^_3#6Mmo~z*(ZhWrBNETbS*=;CZn?WiHg}4x?X#_MVmJo)D#PdTXk_ocOWf zW}GhqhL5I#^~6gh-Ffu@oAN%i%z+v_&P8HP8Y-!Hh45dwSXqyP8(0P!gHfix9@V9M zJDI$Az5o5rA*(xvnxD1USk5IsSO(|bt7k-t+^1>bZn=NzIpxhtO~yi;Q8bN*8o(t0 zjWD1>w6M+>oFMOev}09x;Be^rOvU_C=|&R`g|9oV_V5nG7y}ax(6Fc%l&-=K?`eEL zJ6YdwPUB+7xZ9(?ZwOg(Pb$^NBm(-Q<8Jw>7MgxTf8p41ykY-UC?6+N{!#&8Z2qmG z1fVb0UF8-G033P>f*#qoD9We)b3ZF0*qG~(L5skNo~o-R2VQUSd% zA{KDymy7~hZa_AMTWM1tF13J+Mlti-5wEQOXt1V0qo`k7ZgpJW+21TD$Z>_80e5o5 zEe6%Zmm-0#%YJrzkQ77zb77*;S&6U$yZuqJ0y8Ww|8Y2XNAuQ! zfVto&>^Jf|BU5ihomW&O_i^dEF8^eR3}cFWt?W7~_WP@4y3rgGp-l+~u29Jz5#RyO6Vvmtu~7!Lkrvv+MO{1opAre;g4YEoq^mWGTG748W|8&j}O6vLOWB z{fzyY0aTV!PzhB4i=~e~9??QJ+=z-E$|D%Hl{2 z-Ir3KF8uRyM~a#9qUTa;fU2=!#H%mR@Nq4u&Hkoxu^Lf{VHIgmGzgPCw=5_^fAaGL z06{z;IoOg>aljZM?8ryAtMfvpmct8YP_8FH@5*2Au?SWxzQaaFw{A18k#YsDq4HW{ zJ1^w>@z&4>7s&VHy;88bT`}WGPy||CU?xNTCz)w<7CtBNKt7PE)RrOMSbA&(+1! zo05JeP<|=33Q2}QygvlK`|&y?4rnN=zTy6GhTcDlUHaiD1}JUPJnsLD1My^arID@= zlOlGyC3CdSGj&-9BK=+~F%>i&V?-CoTa9w+t){gQ&x zTzZwG^{oe*p#!uImMbyZiDpFILXkSy;VNh+Qp@??+9DR?y2wvt-l{S$!cA77MgKg=gx0P@F!&QefF2%ykdtb|;w zY>KOXc;nh?F3@|j#s-v)yYaw2tS7c0AQE@L2};htKZg;e%zYWv>EbkUW=;LtIOD_X z7=7=;mFVbjo;j8Xu3*+qkXO^Yio4KHTtx(NTYeR2lb(S#s@^lmCYKMSL~Gj0Cjy(6 z-SeXiymh*XQdF){XX212WNZDyC$j9ejZEn36vBuc+2g>CY&4yB_mmc8l#{y<`*)1- zUd*$)2rAZWY^~ba~!yx-S7z#SjWXuB$0BD5B zl)Q*XFo?8@+GCbAOBfG8i+Ztt5?nxwk^JZ?U2eGZm|=Vg<=bXn4EehKEwG_)SBeQS z%5r6}{YnQEzw8(RM!D|QbZC09T*eI>=GAF~3aI?sB3zNPAFF%ISmf@H2_yVWUiR`i z%UL>p8F@?L=Zls`D~IoG1v?yQ3(L=^0LMYQM;n5OuHv;DgE;GDNu)?Sv^G`yuw{R<>e=tC*n1aLat;kGxqIX{~!F+be|6#C`| zab!{pRS>u>w{iw~P?#u+E0EppO6+z$k5B!D7A_7fnm%8y%)}kWRr^bsc>NIa&fKzN zjPxh^b~?i}_qE&+VtQ{bvrWfiv>LjgVs`mFuC?u_^6g+0iYvrquK={pZOPNNmp?XW zB~bq8>FB=Bj6D0ZG-#(lFk>q8g|H9jc@aQ{|K~FP>$8L)&sUozm<=Jywgl?227R}t z*UOiv@T%4L$MW=!yEJfKzD~asUa&fu`q-}7=cOFNih=rzcX>FGzgd{!QhrX6R+i<$ zR8aQOx8_Tw#Ihc?!JTwHj~Wf%3i2=ydB*q*fGoU9E$iSqk*h#a>$d)!!dJ44{s#hq z*Zf)Mqm=5}S7(e^7CN;@>+@g8H5oMYY4z5}z-2@O3xgL_z=QO>jQrHFrEzdOojX_P z3r_!U-{f-u@yR;BF_y0Dno$?RnMm_Pn3)nZsR4EdcCMsg>Jz@qMvg!=0br^Bmz4J5 zJ$rIP1xmE)1XxlIK9(6fdPm#&6G{jd zl^2=%>>FfSKfX-tpMbWC5?K!1y0<62cn!Ll&$j~cwTI` z5sbTj)qh#K(-kayokZbh>!d&dpj>m6;b(xQ^2@@bfG-<4f{|yj{J^j0u!p(mg%SJ` z{1*sohs2sVrjy2fUVqJudgN@0LaPO5^$TmcnntI=W#$uAC7>&zJ=Kp%I1!LK41j#_ zS7HU#|9CcoZD~6G@P~ZyE!JwY$`GKtCn6;Z`!gbipJb4*K3#QLWL59Ll8ccXc4&N0 zcFZ{$?Os7)D-o_{AqbI`qHgDfQuEf@npQ2Me<$lw^Q(^pQ&i9|ry9-y?Kr@qAxKP6 zkRWVYEJl8|&)q>D6jh-=q!asU%|e0&wYQYdG!1r3;ZfAAhCx1`8RKt2{!9AD(lG4+ zSw7+X@FTmwxvPJHWhyYX^`aaP@979$HCooOj{w8Tcx~Af;EGM8c{#?RGJdK*yZdT% z>S^~yl)~}LTs;3Fxz;Ay0uI7U{%^%wlT88a3-c@q-WWBt_=G0?0&^i)-dLb=VHc*4 z^!%> zFy-^33CaD((8cB4`C{WCsUq*6X?JV(uRQ<0e&v6d7t5~Ga=bv#J3I@6#7?#<89fKmm;q3b$8m}uGkG2&F^*tsa* zfs;Qy*8l>v}o*Kx9z&BoTWUOy=$%qo57!Z#7$9i}7 z3K>=6ga+c7=XoJ`iNM0&F$O4`@sJNy1HgFx6_{8{Sa7LI3X4!6A}*C4uW9Y)7;cIS zZAYZy#?7{y=8d_6Bdq3q%42ofYvxd2G@QN`$2v7s?lfk51E65X=mSN>^1O0)lN;%z z{e^g>PXiwpO*tJw{a0+C(>91##Y{FI-WD{7 zLDM=4n38i{?lY!k952!gYGNVlgUk%M|FDdW3oQFwebhDa++3MneJK%M>s2{pByTyE zYqI)*)<8Jmi>VpU=?f=++XO0(2NMO?+^gq3l97|tg_R47Ha<=oQtXtO=fZixMCpxv z&!I?U3J95(0H}>LU>$fnr2B)b=L~)ZwN4e)E@3FXFd;ZxRl#uU9w4op_MJ;YKW{6-qBjbw` z`rY0~b=Ko&=J;J!$S9jk{1!QPcsH!Fayo>8F)&!DfUh#?M)qjW*tu><=)iBIQO&ip zzA2i>;AC}=&_Li|RKPUqdd&WrjjIc>+T!a0ml@x1oA_VjmPRB+OF+W>=oo70C;95O znBHPlL27TFa+Lvrjgcx2YkaNIGHEvs9CB7N#WVh9yOrm<3W20>F)twgYqNxCytiok zI)T%QHcoa#&B}pXZ6Z;^I*8?f}iq9R|vE%sGH9W zWJOs%tL2=>b>)-4eWn?Q1kfu$DI>@7cOAmawn2Stbbue_4HkxW_p-t!Y}e_Q$SZ^? zpB~aZe&Ck#3lS}e1ARN>e(8?CY_j@ClK~d-#MYwfv&S4Nf3wvxmHZk;D&M0Ze`(l6 zPFI34cUs}J>{BYzP>oZBkLEGP=eM1O>A?XgfO#gl9WEYvFkVZT>78t8CpL$49P_vHMj2&dIt_@Kdh?~_o z@_&m$nif<0!%j^de(Z5m3uuEFt%orJ2?Oo_+uLRj7^Tw4wtIn96)_8xML40o6t!#P zF($qz<++`W?Rdj{^BoS_Xg<}iaN=??d`#!V+(3qi9~efqr-zv;ie~4GmYMk$`TXHz zh(p^Fh_eUP9ku*wJ}guuxkKO@*QY6u&hhkECkDhA@VN!Ly_tdQJ0O&R6iw9G7WP#` zSB4v^Ud@J|Yg59<*ow_{2}8seAt%z0TCPWz_lt}egy>t%f0{AH8`R!l6zEmIET$Yq z?O9uBI2a7vuATKA`*{i->jhh+sr_mTd1%ChQ!V9x>yl;%7U{TijYcpK(V?VGgs z$DFkl_73BZ%GFdlXTuj|BvU`c(D4t92HHP@9@qf!$Ls0mOrHz$(*K*u0zuP@N2G9y z=lU;BFk>Sv+|3t=d*QwhOaLA_&M&`63S_{ZOBh3aVnp3GS3Fnb=PtUZ5s>cjdg2^VU#D_A$rSP<`jQf5PQx}VMYHqlin z`zz0(c9-M8ev7dm1@2BkAbaJ=xi5c!dz(Y2(BRa^F1V_Rb>NMJce1=68<_LFOYj!*82l z%dmj}&uy8c_0Xy_aLG^DdQtfck>plR2d9q0Qo2y1PtO=6hYeH;e0lG09F?iP5)7xpUxhf5_=%9Pbxhxu&!5l^|9qB+KDJi$82pAGB->O1>=YV4E~V#(th2@JUt zEjmFZqP8+6LGKA*Jt{M!8ay@@3a$Ei2~>4qtISbyZFzb28klbT5O`X+6MqTrWHfIC zgM>NJMq>pow|?VTkwK`;OAnYOS?PAYh*!IU2L&r;0}$O)Htu=nqkK%&G`I7sN+ae8 zhTLo47i_emk~}aqNl$%bjER8^wGOxDx?1b<=3Z?ZsqDV zn-f)>{2~AHL4Vb!5Tw(3EEe4)N_djLAIF~4*aBbgQ{K~PL=b6kNm_e1JDFgvi}&+k$~WJ1@>@U0481lB_c#>Nu}$4)!@LR7O;7Js09dZ<6>7? zUu)rgrpduq<=KY-@q7|(5vC$~p&p}rF$88_XDfyE4M|T>J30+1V{}jr43EwaQrFZ7 zoQ4*$-Z(N$Pub*OO&YEcUuQbH;qjc}Iou7#7WjtpF(uvWUJa$Hf&30fvrGvW@h0-p z>}E3KIy~U>qhh%0T}%_}Pifae4&PFSIy+YT{kH^65@(D1(b+M4kn;s$l}GfiJf{L$4;Z>O<7+XvWey zo*v;|w)LbO(|u3nxtc&Q^}(QfH#i0BA1A@jEVW`yrUzY^h%hx1VAqdZspk-r11mE$ zYJpAL$$#V%qD=B5(#p85tcg#lb61HHOYD90gX>0*0Ulpo&X%1wvy^tS?NjCa>|4aE z#7liblsI`jJcX*frhX`S!_r;q(*3JRv;5oz$a=oHfJA@GFdsEcUmNJ(1E-*5sO&1K z#N540d8`Ly?F)7LU(kfN(W<1Y=Xftjp^CHjI`1J|9-n;n9#UmR4E@Ze`c~Hj+i(J` zc8tf0PY)ySDFY}rGYAP?$60kZGM0`6SVI{vf*1gnJxEjXfLSY8kR?cjb zqy_Ed0qWhFQYbN{v2he-5P{V#+sEHgF6)0RI+X4QK#&jZN>~Tq8Wr#4{Yudnql*6m zl?KlX9kj=9nsi(~AM7kljFKqI+m)iior*dz{D{=6j~@XM#k%>4w-bO7fd5o)D;NFx zRA~{$f&yj9OF%cOYEB*WN+MyC9(1TB{C**cvn#O3FlMYV9tll>7UN;EUU`n8-_T5!76$IL=1>)bhS0Ix- zU>j}7?*OXx?+^;&q|DrUEZ%n?i;Dq^^wkOHS~p@$ip=v%dG|Wnl%wNPZTKsA;iyc0 zQX|mq=vLVxT7V<{xGBXgIsOQ6SBncuefwrX8y zigL%Ebi0*{tz$k9l#FM~1P(gpA5BGB*V=?GrM*86Gx^9O1V-7SW;j|iIKHb_V~?>e zLEx>BglZ?@ycDW9#N8b#9xUVGe6kekm^bNZ?CkP;AMR$lnFNHXoPJ>o=(DR$?`EN` zq=bbg`~wlw9{yYR`Y<6sypX^HF#U?nZbhEpsLcOzHY3=rl=&F5w;bR+Ql1$b-H>NTgWv0(@$Zv6le%Fa6@aXr8dM2 z#%02oEL?KkYs^AKo_vrsN^&6A&q#E3saF2hA?Gzq6J1feD^N2ja45;*bbaRt2PUlI z8Y>TboVxuUHa;m*pEe-icA4gv#z8SrJV&*1XMwkSPz#g_2&$VwBewzl>)=7p1KfLi zK#06H_7kOe2QNbOh?N-IG(t^c0wVsFQR5zJX14asFs)JBbbB8Wg(%wA_Yj9IMxF0g zFUKw_l)+8l57!~VlHtcN!wFB z6~5>#!t}k~2+8ZN?i#U82_it5Y|Jw65{bRnv*wYTA&6f$0m|q>Nk#=3m&$vaoPtb2zW)hh`TW?OkHJO>%?DA|-uAM2tcq~YHte(hMxzL8$POR$S|OU2 z*Kn`CshdTf*YU%YCw427d$PRuUm#!4@|%A!N$ZBxUCj$LofnrED`SRHCZ3By*Jlxa z1DyVN%}ZM@bb=7EP+hS-6UujbKNlba&U8wNDK|0N77z8^7=&8#_Mp7rC)>#o|98~Y2QB2gh+`@*IrQ(uxkNUrc zaejL8TH@niFU6})%BKny4%;I86Ja1yq~E$y#a|#kl_^4Y^w6ctRRBi-W6e#7NqX3J zruZdpMrgr1*>n?TFc*WdWK|R#fQts$ab!ws2`Ha1Gz$(=W&yXr(O$5W&AvuN;dO^R!7jqQoC|GR9UNY2=K}8syWf{3KS}uAYV3L*Z%eL1)UEiOviOI&A zB=%dW^~{nvV8(uCYnGmiEkKR)7GoU2P*3&aHN3&{Xd~&JogkM)1480Zr=?jqdqw`b zRvRe#l#B&=*T3V5dofcq+f9BU1hkME8kjMRGc$Xxp-$_Iljh>9Ub(J(fbAJCG} z#`16MG$*(HSoC(v=aCQ1&-@231A+T&Yesbjwq3B|#TUq7`)-2^wRCvQX_B1o*sT>t z2FnfZS4}*RPVcI#*cOd~7W>W@-4(QA`$$uf?oV^E{gUBo@?K@w5*!sNiMI;;8I=%| zIWxr?VzF$c^5m_TM>xGQeeq5(S`FsG+q<+o3XsEtLDtPNq5`T9UUDK#t6dt)ai z!q2?}BuTd!U+ZsD+9pslC>cX8!aR!10b439_2X^5J*4q&cgIsc9aPaj!-VyKgkx^z zidYXY2x?G1yF|;Jm`H1f@UHgV=;p^HcApl$5t^fVet#Cvv?wF4_#FZ7{z36nsnn$V z(K*AL0fiFZ73~Od5u$qaFngl@MTe<0C)Kf@nLWc{Oxr05s*#9kU6Ws;nJYDwEza)0 ztZHIuH7@iUE?zVxL0KN{Zxs4?cMR|eIAkmB0?MTS{v}EH8RM#;6`G>SU?r!zmlgl9vj=4J>FtTk`1GnM&UzwTU&pjuhEPM$KN<4*P*K zqKWq9Ib*tS+KsaD%argWQ&-ioDcc;U!X_759aN_7cAqp-t~SUehZ|(K5Gvw;(Uhq| zyJ;_6F8cea+5DPcp+OM|?3W+apivZaDO0dW)U6UxQ_9y6LOfnM%f+2b1G~#=8X!+` z3&>LhVoHFVpI}Cqd{jFf-3R3}$tS+UY!#_Rs6Tyssn`eIl%HV6A%o8)pZiKoX$3EC z_0#zD>k2BLiuMURzu*}xGz6>;G+4ext4a;#JPRua1;?g!g~d=a&RRa`oK^GOr6R!K zE8^4UA-w{bHdPyZi)93|YqL~eKLpCth5rxAlwz5V;G`1YQFLCuk~!w2tB75 zX&w6&-z-S@czxV1m#G%KfOVtkBKYJCJu?wPhcbzH~=IP?4~+;QQB- zRa%h!ql2*J%Dqr7e(aAQDEAjkIo`34q)HRMCIi05sRRd+f&H7*Y#&$432AHR85|EO z>cUm_1(}uKfzbr`=E+1Gg3pylX~0#&o8o0Yvd0`3q;c*xVV`jaTo>&p$Z?vg;iXZsk*lzuKK_m*QRIev z?c8Dp;9q)Q+bLICQGd2EH^1RTtO`DR79+?%W_HD(K2bMhze^Y+$ZOR~E9NegE&E~t1OC#bpt zRdCv3cPXkE$F_uRG(WNe=$T-7fcqni+zzzK!!t%Guk(2HL zM0+%rIP;iIkv>C36)#%(nDJt@uK@_twSY~0(irn9>6_`P8i>=)^e~ZAa}`Svvd>Bh z%f@3tGag4qml4w&4leeyOHRXf&VCbM#`lcp6DW)^;=roBav?ize`ZZ!Pc~mK4P%nY z8Mloca1_jmS(BG4K7z4IF{M9IMiIjr9Yq=s$o>35@HAk`tLRE(Og%=UOf?uKt91)C zdP@zEe*G>BP7IMKmHsjR7UXe5z{% zV_w9lP2*w)ML;n*M3v2)bRlL6zsxuEQY!&joe3z&>7tmkgUETLung-tfZsis1l%z2 zg3I25iEZKId1q$GQbH-^gq8}7gQ0QktvOY{C9c_vk36x{8-=Y$0}-Y8Ir)RR=hKh| z@>-i9H{0dh#ANDNx!^RdQN-CFta+K;!#K8hbB9ClZxUm(F3$6GVol$LU^ULaK;h2( zM11x&Od1kK%=E!RY-|Ugi{_^lwS8yY_I0;oAgt)z4#0>}04`Gm&SKUW;NQmk29T!7 z**UQ=-ssmQf1dySb^1NGyJJa2yUK_auD8BY@D_$&E)Eq>)u1q(R@fxv;CV7s)0g&~>&On_KJUSwU>A(9H6CsdQDqlVw zlS%EERNS>8jLNNPk2)toZ(p_JZ|OiB=JQLbTfD53DK(dl-5|IT~)`7lL14lSuA_}_OKu$VA;NMXy7GRM&T1fnS}4KOb?8*f=2RnT5j zPANGqN5Kx86Y0#B;T0Sr)LHjcvn$fmz_`*c?I^Y%ndi-19WyzR7Vffvf-tgB-%x*C z#^+n`st|nRyFwK=4{vXoaOIlLu(ir=EkVswp~6=M+UHB}$7uJ`yU$Aw#I&fs^%X%1 ztcq4A8)cM)t$-Ou{sz+8VzsF{Egn+7@!}JQ$2mZ-Yy7Hv%U{-8WX6tqLj8EaYGf=s z1!b3fBMUPU+}RYC!IOk3Ue?FWIlE{Z8$v3+TXYoBbdiQl7<*F_5(c^F8*b@QTmKST zU=7^m*)SFxwhn4s+P{aXfA`ho{VOOkB*_g7!U2}7>Jaet5tcrZe51hnT z3!Ytad?%kEen&py+n6%n-zqi8iqgJ)ZMwb}LK`8Yal=fsC4oEY;%VHGbfFi{*W<#@ zta%P^-_iTHcEfW0 z%C74^31qn+tG*{HzqX*f{Pz|8>&pJ~j^ZdQKfW>MqHmZUj89)vYL7auztY`NM`4(^ zVD-)a^v+5tN4>%NqaxYT{?fRJ^I4q%HlqS*rRtbIHxVSVIQltC@N_4wSYB`dkdspK zR;0BqF{|g9*Ita%eh=WJ(bx%BN{fk()t<2y`f0ZAT)GZ zZ01{NsSS5xf9}7^^p%@mw5$ebomRyw8Tt%mzd_!pw#Q^z{m}qt+!fTIiGn6#y6lQx7{-AKb7fAbip zx6xk{7oNp-oT$B_W;@CnOcZ7*KU!N_g>5<=tRvIKxOBs2TNT==xsc=KovF29A;BG* zn90;4$10|Ofue6IM^OEW-<{0I#1;!7uRYgvGjU_`@ zXx4zr)D+0@PMX{}dW1&pMKfZcvtG<*U}L06N~|jiv$2 zPF(WnfFs7>hL6u%#^nD#)Rq@!dL zroN%=>KNhz3o3Ym1V&F*vSdW#`Cr%w1F$Pzt9=3A*x3-Fk#8uSO+_C2%h?x08iUnh z3QJKHr*1`G8|uYE!^GYZb(9hQ&T^iu7em0M8A6qn7Rkvk)Ip9^N&fEt zLFcHtr^uOCLx8UbHB;Xuez|X7Mtc3#^pH-czx;G{Pea zuo5I2=Q_P1=3(XFhL$_qWfaQ2o{CTLG2vd-cf$IsGegOH1 zLzIAsmvP|Ex0jY<0SpKkWp(7S1Mfrj*KHVvCq!6K+s4EU982Ub0^Nz;_%4dT)Kq>7 z)K~EjM!!k2%i*SlFWrCi(U@>4x7M%!n1-3CXvGbrrZcmPait5b>B&h#&M5GS3>^}p z109}aTJ@u1d>+50A?lZ3mCvwIZ}tI-uvqgd%%M~I+C&Xe$<%pYtg<75so+}rFy-3c2%gZqoV!6&c;{+rM(+Tsh?+sCobHd}l2}YKqCOLo-Z$%o&K;Sjnj^q$#8QM| z^Iuao#XF)2>oI;(Af4aZ4t`<&)VO=a948}RbFeHsqcUeW!B-4+9u(e2H>;M_XG6h| z45)23AhBf-6OorcaABo6%ID@$5+oh50rrK7gT6$YM_WEM5@@Q82XbHxeW(=B`jKq< zikhlE#K(cezV%lqpH5(<+*tRu*gMa#MnKD^i7Dw=xUleS{nbQ`>$11p?*On{$&To_ z;5(M41m|E5l`(9?dJ>PpnZ)VjDPVg^b;eg$Cmf;$^xL}=N-a7p+I4OmD$~L2aIqWh zKzB8eX*1yAi?hiXs&mL#18#u-4@XDM_n?T-i808(QZON@`wL{*MA7bcN`C54W#xG> zR@S9RJB%s2N`*7MfQ;m!pp3y<2fT}jRvr0KK3KDL!xYXL8M7^23?UzlsD* z1WKxk*v>Ia(u{9d+u+~mWM6dZIOr;8%HQvymGDFnUzUb;R>hB-8Vlzbn$SI zS81_tfIQ8%Hg=SPCgxutvocfPQ3|h_!dXW1eG3Du!9gWUjmeBZBNhT)G|wCa*Z$N$ zM?b@b_4?Qedo$j^oe94K&>IM{D@L;7hy3(W-rK&H3~lNKu-nlGi|2Gei^r&8R zpIu#g!56&`C7lLE|IJ?f^K&l2Fo6{M3)AW`u7g3k@S(QZ-^in;u23}@Kp9C90nipe z)|952wSka&wfn?EE>5fGJ)-d5@waMTUMF3zpmCuI+-K} z>C0!Ye*RW=f*viQPQjMfvXzv0d4x+&v!Nk--V!|2w6%`LA6OZ1u$JCxd>*oUbKu_7 zExc=TSAOWs)?$ZKELMghWJcFg^OdQuh)LaO!9S{tza z(p`?g6%9`LzZgkgQi?YDKTXXnD6BpE6p!AAofqV#Q(eA)Ykx6vmvlw;+A5R+K7WiK z!O5Q`x!pI`?Jy+qADRhc>4D3#aMyZ!2 zD%;wYz@a4wL?@i7!d*U;qBMT?Ys!2!+2BgCGinc;ybk=9%5xbEMqmnCElJ}zautfX z6}v4~^p@E}$O)0*wkd86Atqe;6=sW7r-fF@yGG$rVwq#8FthOysoDDs&@(O)M5ft_}ruQG*< z0~K(od6H*y%B~#PYaO$=r0LITEmq!RK2v6MEHiR0U}fV?+~Lt2vk1>iDxWnP^87AK zAUJHBz}u>X!_9{t^E|MuXzZ37i8;>rwDL18`8TG*!fjY#x?vCqNn|BBLpr=y;{bl}dK_6vBtze# z3tNi8=-GLP{C@HUvU4l9bkiyxlYq)WCCf5&g3ueu2MA7ymEfn^!z|#47r-wOPDqXp zMD*p3D3|n00lmz=clA^@I}MlODE9HCWU=54LX@L{Bd zKLA*bnMlT`T6K`FrVye}-yn5Ld91K->eY6iPEWArdf)YcbV!FGn$y?GVxCWXtn zkVq6D6y~io%`ak#95<8u(%kuJ>yPu6^s4JF4Z;41!fi0J#$U#{d~( za#L~a-2Qg%2@&J{hMWg^YMPrB9RXdp6%3Rw_Yc?PcL;LhD(NQZ`A(k-xEM9^t{{#v|BtJ;j*9B--iIkcKuYNr zP#Wn@k?tH?rH7%1MwAecZjh1g96~yjPLb|Vx>G;|^m*^`^ThZ4{V@wzi?!gKnRD;G zuYHAz`>Uqw#BNgbiCvSCw0F$F+hUH22>pa(Y6Y#)?nkAyVjObiBF?P@xX&(X$R;aN z-mUw;K%n*4oc#VhJ`m;LSA)^Q{kV^t+B(%g^atrS9^8l`i}`cYzz=l?fA(G*$+K2x zU#hs~9HIh`@*8fr{F$6#3M99R{?umqDASvT!OdN^qxe>A_H}0&YsN+{Wv9^mt?GD^ zUbXqtMVw&GJB*SJu=FBJYcCl+9lh=7o=q+1y3UFJM-cFTC!4?DgP^~elRu@8Gkv0w zPqz~+qAH9*)nGAO476TMl)*dWn`N%_wm_TWVQwPM9HCk#4P39Pw3xAsEg)Ga|IImf z@eQ+~l=TA%ZkDEkHEWolIWwzaGw8ZYKm#!DD!H~Y1554U`zTV4Oj0}1EcTICp$wBb zmOwX!`+QcP7zVC+r>7lWI*6@$8S=ffUqr4u;aB?KwQ-bNutV|#Jvpm{<)*chR79dH zxE|Oh*+%+d+l*cyu~iCEJ~Dq~fa{E5uN1F2J^dZ~OEpemt!5)-!*W94!4WiB4~*dK zs0FDR>NNb%>yEDe20g6xL?p_lI$2(V;$1WuQV7vHF=V*+!>e>QUJwLtMqjtb3z>p;kJTu`ieP@A- zr+oM2+?0L?TOly9iS)~t!6ST~QdR8Zb@>D9aqoo#TJMf%>EU5f(~BC#FIqXsE^ZvP zN#Hc+3L=ZhbDK`3>T}qOO!_{>)Y%4d7+q=Z8GQ4sWxKu|34x??+iAWLndg)w*qTyNGtM|D2z;Wrjo0w?oW_w^R!Xi?bzx5d{Qx8AHdCc%}7O_ zHqt_|PB6kK+NWELMWSMU9MQ&GN!41@t+*5@wI7lI_POg=dVsNj+EA#09@d17?k(8n z>QaI*mV#K;lt2a6lN@YaHtsRomKcW4masfbr?bhMexa$})n$D780%@)`vYQgs8%V6 z{!P)&Y}yg|3c2H-l)2qMm}mL-_dXV|PsJ=v9^bm%$$MYtuOESf9vnUUunhL|Ix0!3 z=PmtW3FarT1l$V2H5I-670wv1;eP!&#^snlfj3e{ffA_?kaO14qA_w|M@jhrm}_mp zNW34UVD}T_WSb5ktv>?Fz_F`7Sib|zG=jU(n8~uDm@!11@MG@^QS-#+6AUUw$uJyA z2>p=uY7my+Y?+TzpX-Wg6u}D@vlo252B&X=r}ITxtXv{KIigR*)7z=&naQ!-GgRPE zP>4SQq6(0d@=j(R-x6M-#1dVlZu<+@P_R5Eu|jE;IU0 z2x#Rehs(P-&QnL4z*}3V*KY0IDYa8`zh-*Ha2(oR&6l~rg9Et9g5~ZCjZLabqk4NX z0M|}A7Ip&Cr^*rnmvk|s8c&u}GsCC0sOYq*oo3%19O(BJ$$t8xV0>yA<>qCwx1h)3 z^p#)375?nx(>!SyPR1nF8|~?%Dzmy;VhMEP&4@j?27Pkf{eN$tc=3SNO#Mz?B!?>K z8Bq@z8(Qhh^wk#wJtVt2I{M5_C*NXh8VnjgV;B+PxDFzNZ@RA`?<&7stCfB2c6;h( zp@aBbxR++)k$YHZ!#rNf%Q7tpYZnGV=lnt6Ds3;TbSGXxieU)>Nv5IlBtblPtgoUv zj;Vo%WvV}Xba)~DD`8~n8ZP(7Jb%i|PSPGlt5B>-7HFZqEigefrw?D1IMjk+Ei$;v zA!im9#ysv~Awmi!(SvimbL>d+d<;Peb*tqk&TiA>Y^)#ia3Sie-P6TMhS$-~NY}6D zp@*wR%ahBzMK?3JEQI@QA|HE?mIGq_O8t5+wIH<_j5YxHPH-RPyLmH9)(Y4)IAmMY zY4b{-|I>8x@sidBr=o}&>iFcdx{FQrnQ1seQ@fv-gSQ@Hmr}Q6VOk;9cY68gQu9}v zoY#MxN06nJKJ`T!?o9xDXdn`oaxf*(-0A~f+Z}$kEv-&=TGQ(!4mun|KKIes@2&12 ziw#e@Ij9aORe<%vRzbu%i+Fs%j;x?ZUQ#{AU$vZO(Ob&ANc9Qu{FQLIid8zX$~RB3 zplgR-6kzKzOE^)n7Gty!Fn5cHyoaJI-z2)3WBGZd=P7;KDF1>jTM=N|t2g|70o^0imW;-(!g`mH^fl!B{lN$yDD!!<&&uyp6Kw=#Bk3T z)ns6AHMuJH;Z_E4_E0Q%gbbw*Z676d=GX>I*ELL#rc){JCuqN}-!=4GiK%+VGzG-H zr!n9GVKqImE-6}9e<_HQ&{&V=mJHlY)i9G&@EV&+N^`i4uWZje3E0k(rkl!li=gC^ z%S#bPZ}4V>j+*^FUi%t7$vZW!IN0V=0Yd40n^U?%#KB~xUfh~PU;Ato^8HbK*)_NI z&%zuWfsYNw5rW?;!MJ*!0}L3^)LhuZ3|{sT_=g91z7q;yoHHXEG$R^nW4lB~buP3* zTi!aV%s1I4VQj~F2oyW08&Ezxj@s)Euu>~;=2|7bK00}BQ7YRR+XzEcln+sXF>f*Z03t#4U(4xPuMzS38L<3<%k%gDzF~|3F4My?HkA+FX3z`sMh0+v@r!RC^+FiL7Vw zr=e)t*oRf2f|X+4dyRulp0aYKET@`Dg>g?*f;45KXS0^fM_o}#5&l#v2 z3M8Y#@LPk-s$%PQEi=Bfrqh7jW!0h8%3@>Egb<6;{H4YH>!+Q<_X52Oa1s*YU_tB>Pn`yO=C5;VHsTs$cj|m3HuT
#XcDtfy2&ON3hn-WEK$s9_Wq_&5#8hQ6rvTvA%n0YNnJ!iv7%65&8Tl6E;0$sO z%zLp+0u1Z_Zl(YGy?c!zRsgh48^>n#`Gfiz@>wIFI4YsiH5o#M0IIg?7jjtf_1m&3 zjIs4oSI>L2piI54YR_B=q39!KPsfyXIZ27QEvU@D1R^J z+~oMMO(Jh+hh>Tt;`xVIrL1v9u%YJnN|NI{ac53oLH-ScR7*lX{e|4%Jz1fWh4ApY zyKlzHoNejbWl~&Qs@}O=;5>$YfF6iegxR{ZspKe`R$MJypB#jfC;)n8TGo~^Aod$& zn}nqXMF6WMOmb8ht!0yr!XtFIolQzImH=RSm>peQ^OB(31?*_egv8*Bl^D(Yh?P*A zHJH42k?0S%As)^z_2wMwnwfbBVH!<=$nlf@cg}+T_10D&C1dM%vrjor!?J`AV-KRQ zZ389Mu%j(oWbR*C?km2JAWq)i!V&t4Kv8*k(SMdsjf2-)@B*NIX!B%X*j)MK}wdkqr2ZYQqXzCl6jJz_u4!3cre({3vUF`9>-^ch$YA zfL}vRt+_fS(S8nnY^?;6ySuQNTI0+(mGbQU&0Mb~Y=t^?DcuPz@xdr|5N$i@E=j&6 z@-Fkt2W2@_UCz-_WqT0}jNG(!6rMN$4%6Qyx4N8Ke?3NF817?7#lpDi0)8PD+St67 zf1%-A#a{N=M0iU+J1Z6(dC=LIhNL!_XDFwI*uZRZeVpkgTSi2;X%SDG+g|a#Tr+iZ zKlRm3Na~Zxgd}x|+l7yf@Kd>sxKmg4s0H3|;iOTDQj$r>tgm}@5$J=iNLM+>#)bH5 z`Hw#gi?~O$W5hKLl4QomFF~7e1{=S~##z{_sb7iXXz*Rkf{l7|3$JTs<~IQ=FFg`9 z`Z~+hNcsOhOyEM^;{i#yGDd1*>U(g7Md+%clDay|wtY#+rQIXphK+NfiGY0dS#7S| z7a2d1gjulzi^=f;F=);XD|F2tAFX36Ux(4oP#GFN48mE0$QN88{9h@-BP>T5BWF{G z)o1nFOGz{py|RF6m!^;hrlmc0bjZTkXXM3W$esPR3le;i;C>+d zDh>>@MOO|hLwv&dOwn%$p)R)?E|$P;z@g2`iw(n+4sTdhOZ<-km)L@GnaStKr@6tM z7;N8pkq$RHO>JIKvxHs!9TKULso5tj5SA%HFr0CdCijU4sc04eCITC!WfEzfHd;aH zFBR;Dx;G@>pcRtMxSD%fWKjxeev;HhacgW|4jk2H^q7QOwL))jH0W(67Y~V(IxS%F z_w>W`f;r*Jr$Uz*ytU+Uil)Cv15$Sori+#rJyG_NmZRnx4-I;~7W-zPvQnhmBr9iqus+Gld4k3BFylvi~T$4o5dbo#m6{h^IZ%j&_x3 zo+jBbPmYY<(RRJ>BVB7Ajv9^%TNXraTxU#y8!}r7x;IQzB_^v}Jv1~IKQ%TA9hIEX zp!*?9-&k%cx2D0RMoe#SmL+~_Vc_q0Ir)BrwiNlH)9=UJlCN&{*m2*uU<+Y)2^pGo}R z-xr{(60(&t1sj_>+JlKWhaj71KgsB8ZhAD}Z6aHBCM!{=qj8B!O(LJ!Wz_fOr&s0g zvqWz`-h;f!o8Qf%G@ng-HyW!?Y>zpj6?*(-#pGGfHXVV7pH>it;-hIhBYk)<=jSBz zus`#$$;6*zsL$faEcTw;yLo)Ud8uq?`Z#y>m#GwYf)yzc^vN5 z{5_0eeY{hV;Y2@O%n>?OKEv;kPJUGpw={Rov2T{t803w4z3#uzdMhY~Y7}CWo^m2u+p~6ms&B?Hir@ST?f!ys zpCzF6%B*yZxX&W$mlu;*D&!7ZO2E~#N@)Pn6sl$YOUffpjn|!^CNnA>N+fdFJ(qc) z;rvWQrtMvpJKU_D6!E0FH)!juTUq0aMTPBh> z?=8wL_6eR-@U3M(4TR6Ur-v&!>`Kb5rk{h9qNf$7o&#IW4R=(qEQ3%ED7i6U;!=L8 zwvdRLsEZm=u5XBiivupg=^CRC>Odm?V; zzq2X}e9D&O-%u;S<30zC_zFpj(F@;;mZRg7rHgxaOXl{HM#CxMCG95M%<O4XHV*gbS6i?tD>s4XATitUVVKg-Ve3pic?;Tkyrxj z^L^!)|D5c2mUt!r`~sEoZ)d8^R+tyxQom!>)8U>%@ zjlzE{W8SkUj$B6kR69ABHg6cTrG0=v+qr!l-)~K0hNmdXC2+g1q%Uq|B6F#fwzVFO zZXs2^|5N1aYs&}KWQw!8&5iMb?$l^gr?d;<3slZgp`)}J5Sb(2pU6q|Q&NhA-`V;K zos`QfdDD_Swd~od$r=piWpYe`VuW>jss6rBa}@(a0lf++Bv$?Jzm5(dehj+*;LLwf zll_@UZ8l7v|JE?9wGSQMW!vl? zfyG3D4{|(zQ0!2azW!98du@-btxm4K)5=1G%ZWDB>_z0YOc$>7$K3Z-6q!wCaSogH z$Kf+$Uw%^Xmpv1c)L-KA>B<-TrJr30gRam`xeT1WU;#wEL+j>~m3N<8LwOz@#&a^= z^f#&(NsyX)?4Hr;VN7QS54@S zEMmhwzz9(c6l%CN5qS%K57Qo?(OfnkrukWEJREl-b{+}s%d(DNBQku+qcxA=h3mEW`$ zcz?7@K{i0qIzoJ1a=M{;tj_J`{ikuZBPFsy5Df}(RG(#Um zmv}jbq#(_3K2_1`$bsWOb0hoTqlO11C^9RkuF)m*sj@z4Xm(mNmt6Rk!XJpn#o1kU znHIpE(lro0JZdFNrxf#wN%f+!Ed%8$G141{yr) z!6f2y@h-&si2Sa~h#y^5Xk84wjD%iO%-kCyGK(L5sp5WuehOs|cW7T|-!XsE!9}W8 z`X#h?$JPr!Lj}Uoy}v1FU;(lhu&U{NEM?JP8=IXIF{Tqdb+=z$H{N1AEEsbG^7g#r% zso%E~o00e{_2=g9>l!Iu5~N20vO^T9a1&Ksn@;SUDrFVHU znwhD%_Ws?FqIs?`p7w5D?i?--g-dcoyP3uGe)*U&bns0N5f=G^!E9WC`<}h}#JJi* zypbvZrvU+)t%wn*TngbfOl|jD*2ktf*v;~%1hoKZrePRb(L=e8K2Qd-nt1I;zQ*r! zS=-r5aekeSJQFZy4Zk(;EgZ@%u#2YG&*GC!5AlR?gNP9G0$P2t{ZK(Ia?=f8SM!9d zCB&Mf!m3(3&(o)Aagw~W+Bib0K;4ENq!Fkasj4H3Z4dm_!$6ccX<6Y1N?^}W+!uWq ziiMb+Xp`}Lr8xaCKp9#4O=Hr-sCzj%(O{can>l0rRsim^T44T8(Otu%oIW9^cr@ZM zox}`J&Dx;#7elL|XjfhUORTBP)gg^;#&8rWeTvo&C=Ul?rQg#+#JDP%oxNDHO=1%P z*+;rfS9c6OQDP=Fy~5l`m71MUBDVg60-Cq$o{4iaLz*vjFZ*{<%8E=#w}5GB;#7p? z-d&-Qax&l)>I}7DYOU2S9Pa-;;gfR@%Ivd9SU~OMt%`8|Ohogr=~hf=bZ>>Bxn|hu z34`SwUOxN6K0+ew#6S>8%N}^mPEp9sh^MFWSLnfu=eny=Xi>+@zl+-|BB+gVR4|A- zhrn$qILCgE+e=xAPsen2aoLG40z@ndZp`J?+|7Jq+ zgYVsoUT-3Xu=9rl6#P|F)A;{Fqf6F6IO5`6ACe+59bXY_qCYNnt!CB5B`c)``A*WS z6!)t>gXF3v4JC`upDb;g+=)OAVCXPIdISiCtKRuclEU-M?O8&9yu_^W`lBSHlb;Jt zORH(|oZCi^_y(v{280ej->aXV;xg$v48gdIHc?G4P||m@q+FGSyKewghvxtlV7MVz zSGoV{?KV@}W|)*iJnlp^f=>m6e+r@1EXvt3d*%8x349w$;YIfR zlG?KL2BL#hdEebHrRmyRsQ8kf8?H5cAM;qe^R2|3lXu&msrI-{$JbT3=b6e*4qgvp z&G>z~IdEMKn$uX5pdp(tUPLOP$N6}eV}mtRJrnvR&;`-A8^kp>_wNK#xa1%|tDMk& zFf>;+2$n8(!>C%h8r7OyKRb^y&=p-WY^HEfxHuwjhE zY^1_*VrneH^Y;uF4oe$aIT$FhX4CaA({vYx=pS>)jbMmKs;vI1`<0%crZ5+|t<3m+ zHuvg{X_R5yfnONz%fKGP=Mk^CALUEV{0mLcdOJ=PWBZ{3Cq^+&h{g!!y>S%<{-^(R zk^goQU{_LodfQ%!&30#aXfRzGoCqZ6)Dlm0FmyWX>Unr03E|8 za!t~gmooQ@QEj^yy3Ai?x;hdx{hX!LZ$RIj3zV@n_~!WQMH;)ZUQq5 z9yVNHaK@xQ-AlwR2$mhM!2;-dz}hiZeT|6lvtg29jJCBVTuYz#(V8@*?LOY~i+G~i~ju)YB{Xe2A6IByg zAPiK_$%|xr1m;`WkXV&8D_^F22;q@5c%1Cggx!YZ&M>DcX{B15M4JS>JQZ z(DQhLE>V)EZ5<=~6}R%kvYqP5#%uFL&Y^sX8f9=at(tcVX2FDeoL!aIK%Qsb)k{1j z%0y4f!3(l4Bd6GB(ATH9S%C)gVcBbHZsE9YvGAoafd>|+m79NbnV93i^d)x0k~ys0 zgBYJV_dTBe&yO zip+jCi#%_hUQ4MaVgfO?vmW0_dM^VM1&xhf2=m>R25p>wRz18``5tlbQ_K2UwY%b^ znOXcG&C97sSpmU&N&Q0Z!x~MkuGP6)tprcH#umD__qg&=VRFMzgw)6nw1fuW`Z#N3 zZ)jrn+UYjLmBCwZ`1t;!5o=0uA9|lawCJkYn!loigY`s{wKQ4NGl*@sVHDFT695j)YnhVjI^+F1jKlXgCMtNgAm+Z#Ktk#R$Y8SnIa(@MpI$YWaxhuSiE@bLj_r! z-f|}wUke%M!d*%Wa2}{iHX!cErt1h+iZ z#A$gyG?>CYfV>@BinCjs_4c(HO$6jh|MVI!_(%WPd~TFtUF@UXrVxZWp1582%^<~> z&k5Z5dukWGut(XU=R&`4^Nwu32Sr23%6#Iqr;O@;BoY;q#U6c8VaWhhEN72iN?C7s zg8TlmABH$^rrH#GLcB+@k$yxQr_opQLlHU$_I_C^(rv&fE($Ff+(&NbD~Lgo#+0R} zCH9eT1&4dX>;TYPR9S`e{Gn5%QE!FsTi_s#q_h25)QNB=+8?aGdDm7%K1nP`iT2y! zxR;1XiG{)OEp5COX*|8qL}FnI9v_xv9twy3XOj+|xWDjVAr7g|l{Uujy}P}b3k8w5 zwxTgqan+?5yaZ2PPme)YC_lAy^Z$Y_eI`R9q~i(+e*VNT#yMdhJ0uBhQXHp z@zDHE_}i@)ET0lU03A4HPOZt`Sxq{POE@z%mmgZ3T|^-CLgut_bO}QWPJ`fV*9IzW zR+27JWM@eYlaU*PqZUy1puH@L(}G6WrT?x`nCNCXMZbvv)t~9R%QWzK&Zzn(7&P^n zWa)@sakwW<09@mS<%{G>mIk{O@rWn zi-wR?_+)EOeG^cXJtuqj^^1z7ieSgVMK;~?QXJ1%Ko(CYA!lL>0Ly^4L*vx6g9)1Y z_9y#)hQ@zit?FN28o9r7lM0B6L%DY{da#h}T7;~AzTfZf%vE(VPl<*2f$(r1uLfqx z7!q3KJ}(wan?IuGF|%Sc6+NwtCW$4|u zf1%yYAuLlHp?Rj!F!1q@Gp+Vc z7=`1F-lOzx)|~PNahs9#&@d5}8;Eb74;GhYfUXuhjwsh1*vJ|;MR(2n3QJ=aotS>W z?i;&B>*JHoXX>Wh2%}SgEy2Vo!q@qX`fAnlomV5*B<0uf4-Msi9K;pff%7X*@NvyQ zj;9l@U%T1=>8L!E{v8|XY;0k;bYOIYh)oTAFjFzVJPc(_eEdR5%AuX~-Z_Clk0Bxh zV^LpWNfDFQ(ChOmocecO&#(AKMmFTL`voL3EiOb?S^iuKeBVd_4U1$%g+_7Fj5vTm zxSjq+wPyD4_J*mPjfyj?zI)HlruS{AjUt1NG9IbU#RxZF1eo1HnaGPrStk+esIr4q z4d}i88Y$(06oxy}tUhz3qSAetSohUet#n@pw>Z&seO!8Z1gCvn5Ts63{2d7QE&BFd zgl(dN>VB9XWKmAk*Zr8*rMf}l2=#;T347jycM+_ZNZ5z8-o_}mPdIZR_kd*HCx|F) zs;~}c^7RrVYtL_bd673!5l>5f);s5_Z&o+Z1Xfm=6{qbJ(wSi1<6P%`UuhQ4-5#Ib zDba5$v0}w|1j?y|A|P`#&Y*xVV5_V)}(eCGBlM31X$nJn#yz%CPQTDG)q^#?oJvhKZ>I2K-wB*kuNe;Gb0tCyVQqY zGZ`1=&CUoshTRH%g7|oe&9Z*8VZP04yl}a>~5F>H#kTjCnV=Bda$Lf5Xk z3l~!8HOu2~8qbzQm-x)GBPF5m5RpvZ;Lu#7UN+77Y`2JSoGLTz41w$qP4pmk=$ zMVjiLY8Jlk|I*}IT$^D?q~$=MeIGn~aApApT?a`ZX2V|y1_?nJ{{>5d?spu4x+lt? z{3Uu4aIyR#?K_ZopSbQV+;{v=>oTgp=6xg~@RJ|rFwVL051Rv&BWjpW`ux^rY@odul*jc{}{mY_rKY-p9-I6491 zzgQF*y(=as;z0!7rP_NZKv{{vmh5Q$4YIhS$g5lI2Smy0zaRS6-K4}U{#2KhoHbs{ zZ+_qz7P%+ zm}ntj=t6`Q0OYgu_Zorc%nH$@M@dgh{SbNo@>-ze<*-I`+l%VHepa&CU1@ZX;MjOn zqjUt*-R`}%NTX3IG%5Nn>MYaMOlQ^W7nY~FYpj2H&rO+dE{?$GwIqL3M8|&g41MnU zV$%DAz%c0$G`!VA)%7O?i~C+O&edq21Omlp zV;l_Kjm-q%4-K&cIZ#}l|NHuj?x56ac;I>cyNy77C8N#9)(aMg*sR9g|K(h5(QF?_ z$t=`69i`@56n{54>3}^VE41p$dF66x+30)NuO=j(lkl3DDyi5g83-{YINXflEXl0? z?)opZ-+qVn=B!FEW7bCH743p(bY-O=z>92aV?4xb9~2tz%!4A#V2^&3^B#z8m0ra? zZw_8lW_r%X-j72zuw*_W_E^bk6s}JAS?5$=J2y__ouas%J<{^Vpry@mgp*_!k$*nA z3DAi|za$m#^q@}x_kGlKbcc_X z{ovG*IwhxOM%vwHsl(7Ns*SqIzg>WcWE;;9k}1#pY&H4&Y{2(#R5bkD$FF^q`yU62 zimm#XRfJ&a8yvi5I;qcUbZ`-@{ZNybgLjsxrHSbBinV5j9MyFjtNh6Xb29 zWb+uk4;Z@Qzf|KMnot9Nfi93@T1dS-0=uOA)iA zeTU#d$G9BzNV#%N$RHMC{L|^1rrXnF6r2QIn?z*p>-40F7lS>P9rzy0phy z3H@waGi3~FW?%3=FN=8B;Rwml%lC>2dAQ-h6hx=_dDWMz6Y*{P-8thd&%l6dH+IVi zey5^4aqj9@1AdM^VtNE+!OfR<6LucIz<6b0JgZaf`o` zh~_xc$UGz&9?QvWa%v^~vXRHAc!z3n7-a(+_|1qMc*fLq&HRRg1XI0Ym z5i4P%p9=h0g|@Hb(DL$Qlg%L3y;;oD2Xf*8KUzYnYnWo2xPXfMM> z5pq+QW|z5ZYWsaM?bdp8w1$#@Jvvk_1bxxxmapm`%F}0KMAHSm4MI{!m z#HK5!;z{~zWLC|pzf@0n>5AqeR;>?;+yo&?PeMFB7*3C~bIb1UP$zST*So@OA_||> z#lBl-Q-d;dO&HesVdrf}*%i8g5VQ4zDy@CN&*@|rWfJfwZ3B6AJc3dCZs|_Tz$lJ# z-iJf3lG*V7d>VCp;!pEF-HAiy5}6cA>Exp*4M6x|kXIXh0bSzZax@5{Yk?H_P?*FT zy&iOxCFmCd4$kBvPn^UDshDvDokcdhvP4gQCOm8kNp^PU4E5~nl$=G{Q=GsSp3fI| zCb{^1m(Q}09TfaIiND^Gth2(=O?|*xZZga?B3v?yGipZid8xy_`Sfw3lhR)Jgz6b> zYw9%u+uNi+&MraS>u!AS*bB%*lpVY9?xyYFh)!NSeg=TmP%U;Ko_mcV7QKRS>U;Va zKx?gUEv%f3W6PkO)mqmg=q#HLsO^p1Yeb3i1k1v9Dn8v<1rk7t^GtC_d8v%VUsyTq=YkGSbc zy2w#ddb8F#IQPquBp}rI1lSxnS8N-k|5VfxL#hed21-FpCJtZ8TU~zOmprfzgpE`k z*w&`!r`%oagzS&aiD$k+bdEKpeDDSd|RAXUTb}{}?4jmp419yv+6(cxaiv8u-Q?3dY-V&{W7`)_y@0KQ0$8RxxG{-QkR0t;@z*fSyKNK&QRV z6ju#}h{$*So?+AR2-?v)@0$@eS3O_;vSyrtIb~aI9Od3KhJ9JH=6|TL_^N>YfD<<} zV#Tq*4d>?2riCNefm^`|q)D(6u3@N&4y z;jBa+Uwp<_@Fi)PG&Xk2Y~K%SZcGFpEz)2%3_MSek_Ni_%6aII<$?PwgM#-;&{<<) zdaC0{mrcBc1}SA^mD)*xVM0K@t_`|xFHi28soLEIZYhlFb+0=ZEY)Lm4T*U6 zIeaQ#n+_8W>(uAr%Yd+!IHZZxKHv(^@|$^WkFmUY`_r8~RXxc72e=j81Hzd=)Vupo zftwLbdTeWeC9!J(9o@}6kbqhgjA8tkWXmuo?E zqwj7XuslS19Itfw(rCioA#fkY7eo#%caqKcc=vf5qRC76#;;R4!;onj<821c^plR> z&pi6rFbAM8?;d*Uwh3Ec+s|53!S&+%sq7swXj3sanmAZcq0rVBK=CAttIF2rXBeAS zFj}HcPBtotE=Q6XsI9_U=&^tk>U=>(@lzdSfh_oVcj}ltOvMvgX_C*Z2Z<=XbitI^-#udo^4O0DW4*t_5pz*Nf7<}*-JEFV`qFd|H z3=0idP6W&qGgmp&W&JarW*?H6bWO@nQ1A~tcKeE6=sLA|-p;YNX27R7H);lHxRtho z;VmwUQc*G@&K8d;UZQNv1rPg$lr&Ds7A!dH!jn{%c>HE#J#Nea>D3KqU_f-OtxEq? zW0#wh>$nQF&dyJ&O zB$)T9M^*Y7-bfd3l(bUBzKEva_rbPmBDwS2d@L)5LbEgWS8)!%o)t7mKY9wY5?$!? zs}!8;@aro+sgz;7*8QEmkh#57SH_)=XsE7Qj(Nl3))@E4w`$YmxvgN{;zIVP{$Ya) ze(R563LGc-MCyjmvhGhjN^YH3NcuAXO7?zlW4)xwOm(TDgs_vQ=jzE|eq>T7LNEk- zMCLf*4;k?ZeR!4=UElrRwwA*o)^zJ#YA)8-ZVz4A;LhwqqYD2$gD>v3kX7HL(r$zd)Wj z+l+6Mn-dLrCU8&x_4w?)Q5rI5c&}hpc;mJC$`z77TkB6dD#=u)p6gQeyDE+uBsck; zXYaES;`7Q>w+J;u$B$pkJlrM8w^wa`B38@-<9@@`_ky-VGGTIBOm^XYRV|) z*^Yb?+dyOZo1%jPzNR+8z5XvWN6SWMN#lI`(_elzEgxe=h&9|6W}_|$6c(S<5XrVd zpgWmW39H$J{i*gxNQy>~xnBP2Y10dGL{0bQw(9!n_zX0fon6g$1BN)%^#&&x;YqDk`b`V#6;rA`*l{rZc zu@W5z$N4dX55)3AE3parucj(Nz$BJ;yC}j0bLM{^UADqfr$bvHEA2Dg;VhhZ^+4!epEO?dXu!08}MlZL`gg5 z!<8mH-n~srVo4-gT`Sq6=RKS1FIKFnQjc6e;sFT^%DoZN^>mEfD|;do?&JtX$IB7D zV}uDCu&B{dj|YO=!1kuK`g1xc9c;S z{_mCqy}OW>Y36uF=igz>#(Bac<(C-6BmLdy=RCfpQ1a8ZRk(D+Lpc2X9&_*8K z(yXgEn!jjqI>{nb@Vp)kKafAa z5h{o2=|5mfjy8&hMcDa2j%4!Rj)AvucOo$oYh(o9qG{6BjL-hZ7~;STn)Rr0fD<@D zxLMdi>e6|bTl8F70Ut7Ip+6kySoEUgOZxY<64Tu@fhPTkc5z69k0RFRI;}(59H+e{ z!`PaF-5K&Yq2TgrtP{BGC`eLcTzu9TvzfE8VOTj+RkRcT%S$zmZCw%~v&QXwQRp*h zZMIH{G~Tcivt>bG!S)s|W^%US#GleD+~I>_|GbOXqr=jv}HRQv9&Q zQ;HCt^Ro%rB4xi|U}&F^m#VxV%&{j&SDFm|u`KqdsXOfNoHXvVCGqO(sz|3)=G#-4 zM3*tgL~g(%&)XTgy{Kt1{4cdT?6AggSXZmCMt#VQlgm6eATC@8rBElWw9U4w0}#&e zp>MpGDnxT3$1R@otIGxMF$*`>+azVexE>3>*3aJ0+-tIU3EaWDK-g&G2I2C&@)0kl z0!9YFcnS&y@3AWYJuz=SX`LQRFOcB|vVn~TDg+@K7?!F``qYo!^hxl=#(PO%B8;bucu=4GP`J?pt16}OsiF@UDy%<80 z{ZWDzsg*k5w`@fDj9U7Z)W^uE*D5x({=N;#@~wK@cG~;$HJozS!iV>8aaMYmCtOD*jE%Z25j z>h?}M+WXLZr#QM5a+E-4)sE9oPwY=c?;{pfh0!GQXqcF+mQY-egp5aEqQT=Ek;Tfo zwIepjy%TB-cNCnu?;ue6a?pYuy>A|xCgSui|8YxwCL?f4pv_TjRW5&(~wzANR-oo`!{(&L62PR+4W6O0QF!uficNE1)Co(LQ@ zjb}+VPb?=!`c+$9H%9e6^v{lGJE=20+KPQ7y?e#Jf{ZSnoIi|1N`+mG;ghx4kxu5r z+H1Z3`dsA`3_aRll53@*bbRh1Vafm=j1hPqfEH-9`PTqTONcP9MS8xl50z9FM;|BT zuBjuOG>=Y}k3%DE!KkfoQEM7~KVrGPWBmZHoM@qbG&Z(Q!W{+1Y>#Bxt)pnaQE3Y9 z-$xC_oflSfcyYN5?66zCb^lmw=XI#e?pU=>nS+Ees!@=z-D9zdzkVg{5mtUspDTBc z-?>zBy0&^R_^yjX^VPKV68FH`B#*K;Mkb#EXXKu|P>g@EW+y%YgnO5t%-v6LZGtM# z|JY1UQYdQw^|Y_<9DHwaG>IA4Cd=bIA4AF+2qAnz40z8-sH|tw(Uh@&x_!dW_BFLN zmBZ7GjF99^CBPdvPK_7|$y~u{uqo)h>Dh{~`VgbwhA(fKQOV@#T?RMJo?Y;}Pbtsr zb#EHs0WqoX@O$ZBT1o;os|r`(pBXYGplrlK-^ok-;O?)TfWPZkPMUt&wz8<12doV< z$lD4RCv@{SP43)IvpS6aNwsH+Sgy>TklsFA+rOogu+vlfY*o-BO*x8JyGE z{GgV1Ri4&tKjDbPI3uxPGep*2IL=GUE}qR+;l9k(=bu-Ia(Y*5DwVz{C2n()6_Cm< zDGH@FhUKY2xCrw5;CW7hQHfr$4EX%SfD^on&Ekx@PpPI2y{I*xpsDn(tMtt1`yTnj z&vO+b8rQzF9a@u_H#fAk-6T*J%sk+QaF$@?_0o&O`cyCffz(+i6@8K^u-D{@nAS z{yKoaUHc{O{$z;u=@J9(9qy{3Z@gRZFKgi!mz~wOQb#IxzP80_PA^F9f42Yj&fzHO z*@>*AXNlymO-^iApRk4<$(w}BY}BGx-Sfj+D?J#@in#;cwbr81Wl;Z-W6DIhSj8mp&$g6)Kvvun9xZDcs5S?8HMbUr^{|Hv&{rj6>=j$9?2Jvh^ z?5luu2}hDcJhMnL{Uol5m`FQRINHCmiG3+&>mJ6m{7|S7?fa>~2lDf(ZtJ$OA;xYg zf3LSq+aiT*Ox_u~homf8#<=13p|-|;#(q-|Qr!h{FW^F@D$18O3|mc1v#H?u(LHUg zCX43E)=kgct_B66JTidHHsd4o?-N$t!+XIy_S&X9nY$AB=PNJaT{|h6FX1j$rj9!r z&C@~CEH0(k8AoIDFA@RIMWs$Ifj_Wf=_5^@b@gTD&}{C#ts=GuLcx4u~GpNIsI3M*_f?`0G{J2tsl zSKQ~2?i_@DS6~*twx`6ol39J=_O$+3rTh2Z@=~DN@Wh(sK^>m*R0{S;=%P0h?8|mp zrY}E`_n4Wn>&osE!(JWgVDSh?nPlmsW(GY$(gztvG(Bov^w6|X-nsJwma%^*X9R3lsV$ozA!eGoJV~8HoSw#p9{Y6 zut;)A!M0q%i~+G8u-2&_=I?5H;vHMrX(dpEO*z7o`yfDn=p97?Dh2-g)*x2KQ%SO5A4 zBq%e6&p__Ye(AhOp{hb5O#_V%w2AtuLi4K}J)@yudr?>zlh2IsbV9S@-27{0nDZ~w zF>@sa9$!E2pDF(=s^lNYXt6!P(0cL3?Pw;9luzvsjP+$!ns=F0^tnWq*OEKkOtL7X zFdk@-NIyQ}x|QL>LKjiz!(CiD158CAo_N*I%`>X{P2MQF$j2u)m|`>J8*m+O*(ubH zem*#%(Bvh_AZ|SQ2f|V8kuCM?XU29)m@+G)66aK~;>EFYtt753<}rK3isFUL2u(GO z7)aEvCHadgE9(Y$i7)WVVoRIBGQR|xbbbdq*i;&)i<%?FMPZiz)>*dTu82|j$mD7M zUEDNU7(ddeBYeQ<%$#fBb*DW0;0;GqT)^9trkDkrtT9Oo+ca-8xvRUEcBb5~Sp8zv z5)o`Klf#XXmsHiG0!e%0u-freMykVAl_BYSW=%Wora8C{8@ac3`td1=Cm#b>V!TQ% zr95k8($26X+(@OO)UY@}HvAXx)FSt1cP0{2=3OP$wVpn1JG8v!f~A)^7*sq4{th6%su)q$j!;u`CA8xVAW#c%DKZ{W|zE3ud+>qgFX@i zJPxQ0!P{kr142Pa2w;8{LcpY)&~Ar`t3ku7VGASfJ=|$1QdOb}wlo;bG0iIk&!NL%2XYw|3OIh&0qb%!;$0vCQS=SRznZqJB+%rbMG8-9D2oNWy!`=qzn;w)w(0 z7Hc9l2dec>-F4O)Ra1?;Oobz&S|v>ub>K!E_5uF-!XbA%r?cy1+AzjDOZeqk_Xm18 zjJJA-@Zio^!ttpwMYy^tM+}sx0Y`Ve6u9Kf01)ac_U*#dW}yhaTuI zYuLHKI4mat9N|^~l6G6NSaL6Hf)YeJ^z?&H2>oV)X@HY7;mC z|Ft9ODUS-AcM*Ac=Z#SGgI)7FZ$%gKZk2aY(v*rR#m*yp3BI}a95);IXI2wDKUXHz zIO^jA6!D@P$idSW6`HL2YU~>>3=}T5+x8#2Nq^%MaNs??K&A0)>J7r;51KylDScf`nQQ|@z=Wayc?9Q z-7%P%qO}_olZ{wo>WJBj5if(RlruH^;~Jp{P9_V2vx&4NX3j$CYV) zhJGI`i^UV)Z`Pk&XNCvD8evbq8xC%g&UHl(3y8SLb81Gep;EO>tWr7zI|_aoeM9^@ zT{U$bo6RYy2vI%Oziw68Pbk3rYR)gPvj37>`V91zDn(toCko897Q?zpF<5^CUs9dIYnx8&w=gI?y#`>5Q&eZXbDCuvqQbZ$$T0K>^SV9B% z7s)1&NB;ZDEguJJ(fbxa?d9?H`}FkpP819n#gzpLr33r5+PiGIV}}(_=bT&%x7&>l zXZXls?fl9l=j6$~VV z;&FgIE>GG>HUG&Ht=B?l9A<^1K&LbK#rwIN<-yl$M@l}Ze@vXb%dls=aMq&k75Swh zY$2IbiC$f}5U&&=ljXhrgonuO<@=49>b$}6qg0cRJ(jrbm)Fo9 zec^P5eG=2KbO}!TQjNLv7`kIIt+(!4cT?u9U1PWsdh+527r)EZV^WbDTQ!Eo-?0EP z{a;V+U&j}MT8=Zwytgl4u`Do$`j;ip^hh^nmXpEfp7Dw9bP97-7B<^YgzM?Y4c(~L zWhqccJ8fk92s0z3E zNQxZA$AsrVm*H=_8Mh)doKQx%;(W?0A&o+$_f$g}`1<*HI(Zv+&J}<8%p_DuQ&d)I4p@jtMK--qc8TmmbG9o9@qHxlB*6d zMCK{&oV_OHApSn;`Yvj{>FEV47ivGH%hS>+ya_xP2U0`e>9lU;U=mb;=^Mo@S{F!G&?eR-Jh+8b&U` z$BXlQRXyW^Mbn&sxH=hpK1wHR+$6Y zjh{myx_LWhO6@+g7as`%R`v5CF7?U#`zFk6EMGeIRS_*BJZS}ir3d#n3I@~4y2KON zrqrFsz=~m^@r9QWL$D8%3fciBIwfrB6FkxYddcr{t#tk^5UJ*SQ9fL5!>86_AfKwO zQADI(LT&Dpu{aZgppi<^OLrQ=Q{KiZT|)|^`XOcQ25 zef!Pb*M1g+aY?fHf?vs=<2Xs3i;X|93~@m(bQPO_@S^%ul71(zrG46OdNitB>kNIJTh4n+|w32AdvM?|9vDVylISnV(i%A#E z`}5|`i7!gyZm?kXz+cS&c)UWYc8D)l`h#|i*<#A4sWtyPoW|+-4{Y~uw+dfYyoq_R z6s%18dxz%?^(8)SHh%7%Ff9I*ifCw^8GU%G|9upP`@Yo!_6{hRSGB*&~ zmZTT=mR%APkb#+*Zr-+R_$o~&{mH0*y10hH9{Vz?L=8qSBYo?F%??dYS#rdpk3$FJ zj{%e`L&H>^auHICxQ`J1NowS|pKBuRoI{{-+W*75QG?oLv#_YY6fN+qW91NjXN%&z z@aaS6;+8$bx|N*S?X`pl)wRj;4?O8$kcztP)caQLH~UVjQ-FQ^_S9~m*}@gbNMd+r znL$%3cI{<~Z?cCnL-|XEDMDT$tTHQaW|KSrd}X>X_2YTjd1^h)V}==cKAkOTdt}_j zKsG96Px{-uHIYW3TMN{WJgBYz@?>9fW={R@m(Ra(+pnbJKNy>Mp#%%f z{-C`CrW&}QKDAYS9DD_uZC165UenTVj4HS`fJAb)HL%QU(YQ#@vP7SIGUk8y3~i3? zDAl}7+|`Q#0DqT>nWj1%4RB;^R%OLARR{Ck-X**?o5KmNRpCx>Ues3*SJ z5EhRmDbc2(>(^j;Drz3ui);H8gd<^a_CEQXR%*tu^)>6uvMk)PK|ldjm8NrkZXpBM zb!3{^@8}vYc_r(Gz$0qp!r1krf;B}V`(&BWcS2R9XAvmf(iRst5t&%=X@-xoyH<2D z(%X;t4Td%*xI-nHgqg3EIwW6E!5IHU%pUCRDX2I$-g(16=#hf@;%cw+T)*AH`;k)w z5;9(tsK!hP%i!i4YW~@T1HQ*#WdMvoxk?HP2};)KKvy;g?6GD+!~2YINI{l6nO~$X zQmAu9>CJdX(aF|1GFC%q*YzaL5ZOSo|I=PfV)oge0xD{dA#y*!KSJ#By2 zvT!_>^B@(nZK=aS-KJfWR{IXzxx?EtbN$E)kvC$WRHU)XOYhI(^nDsrNC(_+Q$fC* z?H$)p(M*#CP&9dcpNRXIp=0`?L$5&O_BsuZL4E5}^tbr7)qPys?ICL*br+W-V270# z2Z-k%73@FMJT%0}2n#&Pi&8Vg&Z|Mwqrv0XAr4a`4*ioESIU~(QWun`+L(^Z1;<^pgK9qSSeRzWT{vo2vy3=i4u@f8^RA*Vwvsd> zCZ(P-z!2g!wUtOu@y^w`Ol*||Tg9Ld(WmY!N2=K?>$)Di{sIs)A|SSbj^Z<_zPZ`X zN#|d?tCwQ3gf?d;?#5)mZ1Tb z*f^*B`RZ@Ar8%#7tM%K;g%CHVB7F?iJznV1;*kv5Ek^pYsYv1b+YLpUWPDI#CQwfQ z#aqyZC!mz}e0gJ;yxF^s_QTFKQbRVdmqx9_(&F^M!@KuE?DPD-E>7(uQkjP8h2l?z z)G20eKKtkU@%!~*yy;IF$u5%!_bE|#e6eqBA8@ACTSuP$BGzVdHC<+B3X53j4xCl+ z3ke*!vtr~+<#9JU*w_c*Pn{}0vL&KfsOW{`sFBHW*&LU)mTaXu%CoTS?#hYBwqUz< zzVqTaW2oc8f9QAlb3Q|#Hgu=3aiAxeuk8&1nc(TCFh%E5B9vfpv3#7iZkYikfDQgj zY|DVSMnopr_!6g@Og#2HZPD{IZ4}u9=VAeDXb_97$T_X#yERY)io!Ein}xRs_xHDl zr2Ph0I4@JV)eNd^A-^EZQIr`o$trt@cM3wa{ZAd6TX>xyUSp5|ohh^tgGabf#{08r zRRlb~fiC^Cm~iriVGCy?i*1c_+sey5q_ZnoYaNT5OsZ8oYCfjjoYUy^FV{CrJ;oPo zJp!M^1q8m~Q6H-DS$G;HQgdl+rkJCZ;Kh0`3pP{_Y!!Yu}<*Q%hH(;HH8tqr)u4|BIpe|9mA$ z&X8p@3s|*b7%3aAAKiM(OSM{o@8BV4uZaIzN59P&cz~K?470XsJFdGlEA{P>Td^jz zmd00!0)Kl^BSmZL!475ZTg(%-7|Ut3k42@QCH#viqOkAA)Zb{!=I}BNv0u#!Bq!KR zfJ~}Gj>Q_MhY0d&iJOUB6KHqmR(%rQ;Y!kDykuw5$dgpDBuEm2Zpi-_nka#20j%WE zTG8+kuODcoGKN|CPfwUy7AjLmDJ-ehPYyY(mKwAj#qZ`q%AnMH;)Q3{3Kts3JHO9e z$LT-2WOXHa^c-%x2jkx2_X@0@75hFma;f#2O=fg^%-`zikdo-q?FEiL0p^5U#bU2( z!AMCR(+UPNk&yS3J{8`(QL=C5Ufi1RRI?wPl4bL)^LLuQm^(dJ*GufwVRxWrhl`MgB8xTYp%-Qc+kV;LJ6?8tswG~ zq2W@91!gNuw$tFbHI0@n0V0$vK8uK z?S;%-Qo_HIJuRdivOene@+e!wDTdX$De`~ZJjea$7+@}U{N}`~^_T`j5R?1Ix=Nz~ zuOh$5twV`6Ihc;FeWm5t_f@A2ke;`)fh#e!e8y2t6UCoYzh?1I#7)Kfs-!B|CxXR7 z8r7hYoKjCs#W9F?J}*9Mwg_YIS&=qr*CxaZXUgQA34w#rIG8zKFhqj?^(AO)2?@&j z_?)AqW6B71d1zjq^%vYR;TdQmcLjZ zlu$FD{VDXYN_~#ycEzKRrMWEPyIPBr!MA-%#+iBT+BO`Mp(l!0H~UOAU-Gb-5aoWc z?r^GtKjCYkU*WzsV1E;MM`raJ!!|8cx_O3sq=*Kngr?PaMS;=5%#<=Ru&J%NBjp?q zc{%Dpi3|QjZCx&&ShJSxq!RK{D&2_485~T;c)~)eI$Q`I3Mw59(xS`^`rI`YsU9s$ zM?xxaVTlN%rioa>Ta9NOeLsKi;?8ujt*4m}m%{Aqo1ijcrksBu%M5eQ`NZ9wL|evC zr`&psj~~kipizyy-`6-QpMu&rDd4cNYPiq&MqdqLKw-w1w6;&=XQh++rgNRU+~vuw z=mkl}EGofIES(EGr$JdF*Qy7;qpE?|4Z;-9a9XtYFnu*Yr`pkTh<7th%792ecGMMf zSBpkW@%dWPGc)I=ydERvjVb)?{vYYfs%@sd!wet4ll?Ha9$c#@q5ArZ-#=IlH1Q(! z6D?gDoHult6W;6BhZ1fLBO8eUsnJBJMO~# z$(Qm{#>xUER zxF|)(wSIF9lB9?IDa%+=!qwUP$gfs^0A-r7HYYk2^I)9D4qiZiK!&ZbYuKQ+YYx_A z!ZV^A<1<~`iX~&-bw1>&NSrd2-ba2Ett)HyeCP@HId9g~>fjO2W@0l)5MCxQUI|#? z|9t^=f*K?WRIcetLM$@WW#nDg*FGTQFFq4pl5(&ooy(p9^{WIR=@;`Xb|TjNea@S9 zHV}Ok;-y7k>h>MLzm%fEGhOf&0jjcXNd~-5tb&HnHE~uU4a5vT|S5>V@oa6I*FQJD_5tK|2V-i zfv)Bc zmhg9DO6t=auQ+UMF^r0F{Suxzc6FPBHT{srb2y4g2H;$g3L7Tn@4@ikTrQ@}Q*3!qEO;`eile2Lpe z_yY8-Vx@>$s{NyJ-xl+#KG8hr$dYw&{VTXb0NSoEdtBte`yb+<`a{AG= z?woV>>VfnOVuh^%PnOa){az>jhOJ$vrlxVmdYAX_%XqcfEccw0_>gnE8tQsA#Y^z% zMr~G6IuG;Z-4$lzmd&^V8zk^r07PD!8Q@%K7IbKrh$R;ZC)@Blh3fW`z`B?6Tz z{mEFT^OfY*d>=I(X zo0a%K?xpW#YMr6Qu&vb#d#jZATQ6M(ar|W4@>c9m59yUpK&#Y$Ph5F?$Ox}q@IuwL zk+RKy91+%y&zt$G_BOa}8?|vDS^`8G#d*KaaKa$RHMfBDz?!%iT@%4flJg8j-MO;kFd9t|)=G6_yY_{TOQw`K&fnGXwci%~|D%#PZw?E!q z=kr3YHHpXsF;l&1E#^)DpBO|6?RW#RF}dg3%D|Hi6!SuYrNpNoJCOaEq8Ez+`e-S^ zHB<;rC|i|Bt`KZnGf$T=L%UGnv*s}$8eXlJ z0&Y*W@KvpyZ8;wCX0Og*`#$UfZ|x}ODYmU2uhZOIux=Y9lj6w%?GQl$hwz}#p<1v& zVcAt+9%rL{^znCL&u!93jvvk>P@gKs(=pYA*Z#%8C*tnrdmD0pk zPF`ow?)^ky)k)~HlWlDcIV|=9 z_}QQNo}iSW@}&h!#m>GvH?IbPfaEoBVaN2t!>&P%9+9yCAMM9~w8Oc>@(SXDC8i`T zVL$N=!#%ZE?>H|~iy@{ug>V{WkuYm}ra@gb+ywQ3dK>y}sU$|6!%s`-^8jAfjFj`X zE} zESI5gBwQaotu^^#S^RFgZ%=gs0<%UGqi>=%C~5idcJS2vT3%jCfc=Y-C&7n}hDL+V2n1|fK>|P&#aRM1ATLd+T7rLxj-7`D zk|0l(DXi=9B7jJmK^o~wx;hub^2$Cyr1&kbZaDhfL9o+mY_$V?|FSpl#szsZ5?tgcdI zL(E2G9!flTpV^Wt-|EW}g)>r3QyK@eS>&2u`IKwG;O31XUgnV-KxpDm7LVdiV^RRZ zc7^J-Db-8!8dS22`8lyse;X-6Op=sc8PXdujR zCAP%9oKm)Su3w2YRYzO&o;}b6x<%Vtc1NJ|CQmL)9gYq+l7m!-J# zINrR;(1EAWyR`7_)5}uCn0HWVbGs@f+gzjS+bZXWdX!Wl+hJ>1(Gez=hlsQAk(xRO zrk;tChgT)ps3%F_9wZIhT+3^{2Fu2TzF*;SJ#Kq{baFB zX;!|mtMa=z7L#*18x0uWOD?}Tjy^Lq#qy_n+0v+Q#fP`JTX;F3v^jL4*O^5Yg8qapC9jHrEIRaFI*62jX9o?r`n#ZHX{G+c;Lrz#+3jvRjf{sg zye5Vtz(dBWDR++MS#p|{dfMu@QX7d+&!(4V#|CSFcv$1OQ~(7a?B&Mae~h;C2M${%<~pXIyG2K}O?**UnjyFnx9A~B zMtMQkYgzbxlkiQSWwBu~he5CSxwM^3eJ9UPt4A8!8V^~(GAtLU?+7;;6nlh%;;${i zU(C@63q(MmJzAbZ_MyUNnv-BNR~2)K?JFiwG-eeMbaPBtNv8k~(L8 zZQV58595ydnsEK`(zA_+`YIStqY2)cOx|C*ceQ#Du-zNtmJ|{#Hn7v{l>Vp>X49CG z!%_V=62iUTYS;ygP<=jtBz_@qk|JRJkg};QU_VVf-@i^eh5B(*D|gpcU*Lw^@8_r5 zxSA_W%(AuDhd8KHv1TZU4C754ihlEK`z|&gpS=_@D3lJCf~Iu-@YM)jETK&MH>xg45yH44|^~L(B9tBOxY}ou)b_V}9%(jYztOv`lu|EGwmiF;PdRsc05JZ5354ap2>jJlI)*l2PO+|^9Q-kDa+cwGtsu!X1Nt8beUCC#+B&;9 zfKd)X7ZK|9LaPFL%K6;T0N=TBMS# z*uS>X=FY<&Qq?gTES6l3I%M-2E_9@gSR1KhHlI6hg@!+PVG-P`6KbMsZ__e;MI5$2 zydGgmURJ3aBrMrsTL2?{wELS6wU4|rAW&HQV5#Hc5dZVs{9^-hg@6^Ax$2*ac`Mh2 z(v$tSP0%(ms=Sw6Qj4`@2NC6sv)+mqo;`YJtsIEUX7H&a?JjY5=)EH#E3J2n?kq@^ zweEm4mDYE&y++$S^M|fu7?P&#n|~cOo_)E0Ww=pe!%b0_OTNo&=(O1*+uNW1uFmQl zO_hKCKM(_739X(>lctowAceVU}GhyVXB!J5PKJCDnD=*1od z_toE(I-9Q|r$~kq9S>Z*jk`q`^(IH=`&`u7+qlnqMQrRF-Z$NssntyjfgzBN;8>`T#)FvXvLo(IHpw+oqcK3EA(1`N5l#XH=8| z3+;*meP&tD&1bkdHs*|J!6HFyH$GF7!cF%|u4&fV?&2xy1NXKab>W)Eqpn0$xRsXA z62OIImA1ysU2T?YoYmPUV`}DenlN3R#Nf!c)u3bt& z<3ad%tE&C>DSA;<+Y1xmiXJ0H?r022?{rhoT|Aw)uw=`HNC+~2^t;e0k>Rew(Zt}_ zePgn-g2lOKaYs19=c$G}Wsf8)AEvv^RPkr)RxjJ>MK`j@^qXFy-R@!hKW9mkJYXPff z^1Mk`-iiy<+(lj^P1VB6SiRB#g1&zaNJQN_czJZ*P5Ho&cO(6m5=y)J`{h2CJv)9E zzFLNY`Y0l{3K34qvjWp@sT!8?20Uf>50QM+n*liH_%D_uLdN0eq>t6JLY#0l0wV>F z3tHHcTt5E;Vf8oCm2mPm-gqH)^AUFPEqe8&C=}!d<3A6C@KB6us3d2zN(iEz|HI2q zL>qwatE~V0Xb<RKz{zix*j@3s=-SDung#}&rvsk8IWWFo{5$}64zlxVx``4`f zN-7+bsQgSTIop=th533}EpSPAOO_>^pRu_qSzUwoS`j;vjq!Px z=n(lOW3%&M0jI%B!^*(56=9vXTE}udvpF#4kVk-13=Hw2FrCS==FkeT?~UxL8(5)j znJxTbje;_Ms~3)KIgD{8gO|RLFahCh_`sZyTe`cdc-sGKcYT@6bFktn| zmuZW+@H}cZ#-mK5H|5y`1w*obof_6>*9x|zQUS4H*Qg!~>Wg#?qC-hez#!{z__XSg zhT-73Qey%&n{eWR2z;16@H?vyO;e60ouSx0QbA=rfi*Ss?=6H5h5A9cNtqhvOKdH z%7=2wiS-qbW&lcXx%9{p$tcAZmZ9(iwQPA=0coRj6QaG9^RF$& z6z*)LDk9?Wvnba?_R!U|g|wdbm=xbU+S9$lshAlnev0=tSRAN6WXS$QD^ zWR3q7I{uGn^IuWtKff|2rl%W_C#Lwjx|yV}@n4%y~sBdrhuFV_h zW4msw&3yHp=Au%?&z6Mc;Ys?j=GKzj>|N?)9<$$F2M!|>ULDt!o^-L$nD%ILQTO-) z_1u$RuVadxak1Koo1wB}*L%lJtnmYgIn+Xclogqha+;RxzGY$^4$-kG>-ut%sxMVN z`R71EjhI}Q{ov)xq$Mo}Ko8mygIStxkm$HEGeZKnC&W)#ZvH0{MFy=>7Gnd_GGEK6 zC;^=CzefVcRSQg}e3#t*Y6K~RD|i^5 zS(qYN=g0R%*Q~Qbps-DpgH@?2V6Vg(0pS6=(=5H(VlVT)u)o!wF;>RwbGUw!7;}og z#`|F^$}w*ifv7_tA&RU^Q77D8bec!j1toWYqLpPGpJpN5%_-m&Q{GBHFt3QWjw<#S z9ny){uG9)m)Zj8nFdGCo2Xl;00wtSMO~7Cq4l$0moI`C~uWuq4B-)JWbe5%@h!!~JxqWU!tz5HD{7by^ze;GbMU8)#(Q zgZbY98|ld-A6$r<$9kWy+9v0*ZQD_UI1F9V>Jj8`XJ_rde4{4Qr~>c?GEpMYN#`>6 z)9bgGtM@H1yHrfoCilF70AgnQldK|4w_Or<{5rCCt`mlJl)sfi!N&6O@#D=7PX|vg z6S--6#Xr*!bpb%53J=p({sZo?i(C9=pDUfNy}T(eISpv0#EMUxA9ZRzX!DKrNW*sS zT2Ap#Z#=44P^=W;G(+_nqVd*A2*rYD)u*x?j$nkTiPZWOtX4SozGf1f^qpFlt1orqBkM_~8*Eya$4u-joVJw_<`)=1l%=Rn2d!nQ}3KjY_f z&9cULI`Xz^f=Z%m9^jtahn%K>!9%{0aFRu2J=YUH6 zPuB|c9Dsc*1OsM8J_P>)KH^ri5fzLay5lO}1U}e*<1&-PFQr`DG{<~^&ZJJ}fSRZF z&?j9_$25-gbH`)1H5%tcMo-mDb-amNt@Jfp>r*1j-RUe1i+8?ke~wNVr*PS?_K8z; zqo>(?=P5TSIj+X=4v~MEU@Q9>??Y;Komsf-_hNLq13t&JR7nI}h$ ziAkV;$stA<3^gehx=3yxZ7>?d*4EQX4p$xZf{^^NIR|opNXFB}7Ps58-KET*30@m7#6QCRpM{y9|qJy*hA zX7W&}y`S=>+lJq=utE5t1v9M9-Ksc`-1>|j(J&q5wp7ca&8y5)y%J!wk5@S6i$XTFCIK*Jvs;ZxA0Eb>uy zm?Z6F_CFFgDbWs@a64n*@1pArz-ukh-b zqOPY0JOU*Ao%#bX-i3$LFNMyhg{wd?Hu{8wy{Gn;*<9`Q4Lb`eeG=*T(fb>@ljNCY)k`049P&O2bbRHh zxrNdadIrvh?O(UEa8UmKnTpEK<|kE*m5tZ1UXaWOPFJL#0#}}gIMuyp+8oMNmrx_< z)6UEqbqq>!XjY5J{MMGuNO`seB%!9HJFKk7T-~01IY$EaFF&W2=yRuba6->qv}IW| z)IUuqhGt)TDBlP#X(KSa! zG8rK~wdXNPH}g-`HCSCp23bPoX@W4Oa%vqab`W>*p1SL^!J2+gdE7FZ^WRrn#Kj7D zjt`_A8cc%5eB_#@)TAIZ#F^x__RQAwra5;?7DYpy+0lo%niIr5^h~-qPZbp&l}Wim zNiwLx9jbT(^P7T!WY-~DJi{8$0REMxRF;%ydi-^eNDfgvjBJJ$#a)kuPt`KrSG$9IV zD-)Ick@y0r2{^(ab`jz}P@k|Xjy8+x=V6c<1(>rq3UZ(ziwoXw>HdY|kY%pTd`xbE zNcmMXMB-0j*065~)26*)YbIQI zhB`gV)p(O1I!WQ+hE}AKxUzWd7gHBQ3?l6N7b4zU^HkA~QPWwU<*coN zk>~@REdlOM_0Qxj=`X42ZM6IYPep>%=tsWDOwDau%i<~S1SzUyb5X&ssl*3H5pmsz-}u$} ze9gMs)14wOKN(W`kgL1PLM>_U_FA*OMwxi4tMraA?4H6xiVf-(d1=?15#h5>xGe5h zL})+bPLzPu!iEO@BzCB#hcVjTg>-lDezCV2uL#>y6|#|I{0~}i!prJT5^p^6!@IP; zpYvJ1CTH6%X{}a!Uom6xrKqgbm7LL!iJJVWK%VSR)k-)u1Ta^Mz~&^x2V%mN3^vw4 z0bP`H1!V5OYhprUeT{|Ggaq4}t7IBIZ{>2K(iOjngqZ*M zxyl)PBzcm-(dp~Q<*?^LvlKjRvo^?1`DRJQqJ#MOaM@b^S-)`QVU6Cgz#CCN?~;vj zW4|P;%N9C4*GOP>eGs8rr;ay^o*X)jlOhYmTL(z#p3m?I7bHptPXpu%0xU;Bj-dv? z=h|MntaRIWWtdphOBqQ&fEA;ntj+3Qx!gWeYN_7qH9}z0kZZhq*hNKQjd*+yPyT%E zleO?28!=i?fJ;54-EL>&wwN{=5()pT-0i{#Q0G9ynR)j$4Eah8hpizmjxQeJgDnL3-i>8hK ze_dU9RFl^d4lXp~#Z5hzJq{8?DuMgKb~W`{O&wIXUOcz4P6fZ)Scozqx$vk97ZH zo%vMO2I>Ggr-rJvZ-Qh*)}H%lvdSCx`th;$lCWXjA#TC-hE>-ShdU!Y8p&PkaG?ow z@n|&dN60-s_Gp2Q?8lI&yQ8i>jbe9}&JyMKM{9kShZ2~nwJ8TMZMr(o8&AGdLpypTeLeD@=e;u z#8A~-N@M>y4|uCG?WnvT19t``>(n*fZ}{^l#%lXeG_~s9oT2SjbX$P$Q_7xi2#g8( zSU>-$Lk7LJowI`Eh7R(bVv3atuds?#-s~Un^X*NKt?r7uA9!Cor(bkIiH1%dya|yC z*j`Qq%D!i)fw{6_BxDeO{+bu-n zn@hyAeblQnZ@0zAF$Ep zo?o7`fV(AIcOA2WU&8VuXnw{4gkIP&uA zkTlf;-mr~>m%f8r`eT0VICGo|!Vzc`OlJGPG+L@@o0n)DO)U}j_RngTWwqwx6l6CRzi{3WkZ^VhQ`ctxEG zn}Lm~iyD4M`WG+W{^_Cq==YJ$f6lXKpBhp>4u{&<=oaGN5#+At=r*C~&h-Wb^po~= zTPPiqAyDob%MLA+G~wKi4Eg&_my+pg|1k*-A8>qSfb{X01LMP{Ws=tJ=}sW@x15` zZNw}#n4MmDC2+e)apj{>6czIa+`Dyr=Snl4=N>IcRe}&YGr4q zNwxT^Y|Ry|gm9UzZb%q^(hm0JlTz3Uf3GOULOnp8P)fxz_Prcio;#JGpC6em6nOa$ zm^C6`DXu#VZ58+qefIvDha(X|;PGuV~J5LI#_0i@OXu=e!RVN4|K!y|+wX zqXXb3EWK4)?f0h}f~Ixl(!w>`Br%V!?kF%kR_SGD#7)L=ORmoR>LzT~fr2A6r2&|$ z-7+49H0hI41O2#^-(eXQ4W(Mx-pB2F2a?{v>z;6O(*skIXz0O`E7uBNMmAWHx~rIw z0~^vLvlH-IEZJa5QhO;6B_L4S5YqY*=N4(hxoe%4x>KLRZO@Yz9CBJ8SZBST@QvK# zXQ*RRCMKq9uI+AIoLDGD^dw`Y@m?t1I`FY+5A64}Ti&4J~C2KbKG+%RpV?Ew^HrPE<9g)mKfqIzySAm1iye z#=^gS7gs5s(pI>|9bY6|E)0ezp(GH20ai?H zLKQ*0Zb^qV7V!udoP26tp8^}c3oI4UUZ4kI{mrY3r!do0 z|3fy0vK4>~V_fZ0RpTi<GaYj z!aW%t@AEKF2s;5-s$T}8_b@%?&0lv24!R6-&1!~cGUZ6Objs<9cKO;bN3Yy5qG|_W zt^6^Ac$+X{nBzR%l#K+|-XH@7X5E(j{lfewN09*aBw+=Ven;3u5B!6ZZfY|fks`D7 zz%0vdowmjf8@Drf5I0g}HgV&KBMApBHzB_T+O?@qe_PJY&maK~+SUo|NJh|L83T_^ z=<2EqSv9{@eHYo-{KW>!!<`LdSqOe`&*U_OXv#b!I3U~6dCn^$(!%j&@H1YeBW!O0 z6&z6g&)SQCpes4f;sDb;dMN`eom@X=)zXju>0R&O2>)suq2g?<1{Uml%d<$3sgs@^ z;3ky+zwts;sW^XjU9_hi$Cjbm zo_Bw~0m8;6=cifhZE0Mq-JKkKhLR^KCdH_SF^qjSpdN?ho~cb5lz_o)z%>3FMz&M} zGO#KGuaVDrAZG;IJtQK$Jj)1(eorP?=GNo_Yi|JCgDl8;knD5UY2^Ko7m$V`cO#ng96nAiw zjpDWH{ja39Lp^ooelNruWv7%Z2!O7)L9^(H!>U8cfZGmed|95nEO2E3qd$P#P#%EU z4=i2k@V9ML`s|CV2HzN;AP-@A!hqW~)gXCSD9TZ$e2>DToO`ig05&%9{6(|!w8ab; zUg!uKL4pydWF_Ky=;@jfCqFcE;kMGK-GT!R31HoQk+7K#&5C8xG literal 0 HcmV?d00001 diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index cf4a5eb7e5a5..f00a7f585fab 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -289,15 +289,19 @@ Navigation .. table:: :widths: 33 37 30 - +----------------+---------------------+-----------------------------------------------------------------------------+ - | World | Environment ID | Description | - +================+=====================+=============================================================================+ - | |anymal_c_nav| | |anymal_c_nav-link| | Navigate towards a target x-y position and heading with the ANYmal C robot. | - +----------------+---------------------+-----------------------------------------------------------------------------+ + +-------------------------+------------------------------+---------------------------------------------------------------------------------------------------------+ + | World | Environment ID | Description | + +=========================+==============================+=========================================================================================================+ + | |anymal_c_nav| | |anymal_c_nav-link| | Navigate towards a target x-y position and heading with the ANYmal C robot. | + +-------------------------+------------------------------+---------------------------------------------------------------------------------------------------------+ + | |anymal_c_nav_obstacle| | |anymal_c_nav_obstacle-link| | Navigate towards a target x-y position and heading with the ANYmal C robot in a scene with an obstacle. | + +-------------------------+------------------------------+---------------------------------------------------------------------------------------------------------+ .. |anymal_c_nav-link| replace:: `Isaac-Navigation-Flat-Anymal-C-v0 `__ +.. |anymal_c_nav_obstacle-link| replace:: `Isaac-Navigation-Flat-Obstacle-Anymal-C-v0 `__ .. |anymal_c_nav| image:: ../_static/tasks/navigation/anymal_c_nav.jpg +.. |anymal_c_nav_obstacle| image:: ../_static/tasks/navigation/anymal_c_nav_obstacle.jpg Others @@ -492,6 +496,10 @@ Comprehensive List of Environments - Isaac-Navigation-Flat-Anymal-C-Play-v0 - Manager Based - **rsl_rl** (PPO), **skrl** (PPO) + * - Isaac-Navigation-Flat-Obstacle-Anymal-C-v0 + - Isaac-Navigation-Flat-Obstacle-Anymal-C-Play-v0 + - Manager Based + - **rsl_rl** (PPO) * - Isaac-Open-Drawer-Franka-IK-Abs-v0 - - Manager Based From ae212856bd8c7fe6a8fe4f76c5c86efd4ecc1f14 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Fri, 7 Mar 2025 02:41:14 -0800 Subject: [PATCH 08/12] remove redundant code in play env cfg --- .../anymal_c/navigation_obstacle_env_cfg.py | 28 ------------------- 1 file changed, 28 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py index 6dc77c07d771..14ddcb916867 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py @@ -204,31 +204,3 @@ def __post_init__(self) -> None: self.scene.env_spacing = 20 # disable randomization for play self.observations.policy.enable_corruption = False - - self.scene.tiled_camera = TiledCameraCfg( - prim_path="{ENV_REGEX_NS}/Robot/base/front_cam", - update_period=0.1, - height=64, - width=64, - data_types=["rgb", "distance_to_image_plane"], - spawn=sim_utils.PinholeCameraCfg( - focal_length=24.0, - focus_distance=400.0, - horizontal_aperture=20.955, - clipping_range=(0.1, 1.0e5), - ), - offset=CameraCfg.OffsetCfg(pos=(0.510, 0.0, 0.015), rot=(0.5, -0.5, 0.5, -0.5), convention="ros"), - ) - - self.scene.object = RigidObjectCfg( - prim_path="{ENV_REGEX_NS}/object", - spawn=sim_utils.CylinderCfg( - radius=0.2, - height=0.6, - rigid_props=sim_utils.RigidBodyPropertiesCfg(), - mass_props=sim_utils.MassPropertiesCfg(mass=200.0), - collision_props=sim_utils.CollisionPropertiesCfg(), - visual_material=sim_utils.PreviewSurfaceCfg(diffuse_color=(0.0, 1.0, 0.0), metallic=0.2), - ), - init_state=RigidObjectCfg.InitialStateCfg(pos=(0, 0, 0)), - ) From 7e85c45721aa2ef8f9f2d67a8ec5231b0db20ac9 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Mon, 10 Mar 2025 20:30:31 -0700 Subject: [PATCH 09/12] mv conv2d actor critic and ppo runner to rsl rl library --- .../rsl_rl/actor_critic_conv2d.py | 229 ------------------ .../rsl_rl/on_policy_runner_conv2d.py | 67 ----- 2 files changed, 296 deletions(-) delete mode 100644 scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py delete mode 100644 scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py diff --git a/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py b/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py deleted file mode 100644 index 49ef69efe038..000000000000 --- a/scripts/reinforcement_learning/rsl_rl/actor_critic_conv2d.py +++ /dev/null @@ -1,229 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -import torch -import torch.nn as nn -from torch.distributions import Normal - -from rsl_rl.utils import resolve_nn_activation - - -class ResidualBlock(nn.Module): - def __init__(self, channels): - super().__init__() - self.conv1 = nn.Conv2d(channels, channels, kernel_size=3, padding=1) - self.bn1 = nn.BatchNorm2d(channels) - self.relu = nn.ReLU(inplace=True) - self.conv2 = nn.Conv2d(channels, channels, kernel_size=3, padding=1) - self.bn2 = nn.BatchNorm2d(channels) - - def forward(self, x): - residual = x - out = self.conv1(x) - out = self.bn1(out) - out = self.relu(out) - out = self.conv2(out) - out = self.bn2(out) - out += residual - out = self.relu(out) - return out - - -class ConvolutionalNetwork(nn.Module): - def __init__( - self, - input_dim, - output_dim, - image_input_shape, - conv_layers_params, - hidden_dims, - activation_fn, - conv_linear_output_size, - ): - super().__init__() - - self.input_dim = input_dim - self.image_input_shape = image_input_shape # (C, H, W) - self.image_obs_size = torch.prod(torch.tensor(self.image_input_shape)).item() - self.proprio_obs_size = input_dim - self.image_obs_size - self.activation_fn = activation_fn - - # Build conv network and get its output size - self.conv_net = self.build_conv_net(conv_layers_params) - with torch.no_grad(): - dummy_image = torch.zeros(1, *self.image_input_shape) - conv_output = self.conv_net(dummy_image) - self.image_feature_size = conv_output.view(1, -1).shape[1] - - # Build the connection layers between conv net and mlp - self.conv_linear = nn.Linear(self.image_feature_size, conv_linear_output_size) - self.layernorm = nn.LayerNorm(conv_linear_output_size) - - # Build the mlp - self.mlp = nn.Sequential( - nn.Linear(self.proprio_obs_size + conv_linear_output_size, hidden_dims[0]), - self.activation_fn, - *[ - layer - for dim in zip(hidden_dims[:-1], hidden_dims[1:]) - for layer in (nn.Linear(dim[0], dim[1]), self.activation_fn) - ], - nn.Linear(hidden_dims[-1], output_dim), - ) - - # Initialize the weights - self._initialize_weights() - - def build_conv_net(self, conv_layers_params): - layers = [] - in_channels = self.image_input_shape[0] - for idx, params in enumerate(conv_layers_params[:-1]): - layers.extend([ - nn.Conv2d( - in_channels, - params["out_channels"], - kernel_size=params.get("kernel_size", 3), - stride=params.get("stride", 1), - padding=params.get("padding", 0), - ), - nn.BatchNorm2d(params["out_channels"]), - nn.ReLU(inplace=True), - ResidualBlock(params["out_channels"]) if idx > 0 else nn.Identity(), - ]) - in_channels = params["out_channels"] - last_params = conv_layers_params[-1] - layers.append( - nn.Conv2d( - in_channels, - last_params["out_channels"], - kernel_size=last_params.get("kernel_size", 3), - stride=last_params.get("stride", 1), - padding=last_params.get("padding", 0), - ) - ) - layers.append(nn.BatchNorm2d(last_params["out_channels"])) - return nn.Sequential(*layers) - - def _initialize_weights(self): - for m in self.conv_net.modules(): - if isinstance(m, nn.Conv2d): - nn.init.kaiming_normal_(m.weight, mode="fan_out", nonlinearity="relu") - elif isinstance(m, nn.BatchNorm2d): - nn.init.constant_(m.weight, 1) - nn.init.constant_(m.bias, 0) - - nn.init.kaiming_normal_(self.conv_linear.weight, mode="fan_out", nonlinearity="tanh") - nn.init.constant_(self.conv_linear.bias, 0) - nn.init.constant_(self.layernorm.weight, 1.0) - nn.init.constant_(self.layernorm.bias, 0.0) - - for layer in self.mlp: - if isinstance(layer, nn.Linear): - nn.init.orthogonal_(layer.weight, gain=0.01) - nn.init.zeros_(layer.bias) if layer.bias is not None else None - - def forward(self, observations): - proprio_obs = observations[:, : -self.image_obs_size] - image_obs = observations[:, -self.image_obs_size :] - - batch_size = image_obs.size(0) - image = image_obs.view(batch_size, *self.image_input_shape) - - conv_features = self.conv_net(image) - flattened_conv_features = conv_features.view(batch_size, -1) - normalized_conv_output = self.layernorm(self.conv_linear(flattened_conv_features)) - combined_input = torch.cat([proprio_obs, normalized_conv_output], dim=1) - output = self.mlp(combined_input) - return output - - -class ActorCriticConv2d(nn.Module): - is_recurrent = False - - def __init__( - self, - num_actor_obs, - num_critic_obs, - num_actions, - image_input_shape, - conv_layers_params, - conv_linear_output_size, - actor_hidden_dims, - critic_hidden_dims, - activation="elu", - init_noise_std=1.0, - **kwargs, - ): - super().__init__() - - self.image_input_shape = image_input_shape # (C, H, W) - self.activation_fn = resolve_nn_activation(activation) - - self.actor = ConvolutionalNetwork( - input_dim=num_actor_obs, - output_dim=num_actions, - image_input_shape=image_input_shape, - conv_layers_params=conv_layers_params, - hidden_dims=actor_hidden_dims, - activation_fn=self.activation_fn, - conv_linear_output_size=conv_linear_output_size, - ) - - self.critic = ConvolutionalNetwork( - input_dim=num_critic_obs, - output_dim=1, - image_input_shape=image_input_shape, - conv_layers_params=conv_layers_params, - hidden_dims=critic_hidden_dims, - activation_fn=self.activation_fn, - conv_linear_output_size=conv_linear_output_size, - ) - - print(f"Modified Actor Network: {self.actor}") - print(f"Modified Critic Network: {self.critic}") - - # Action noise - self.std = nn.Parameter(init_noise_std * torch.ones(num_actions)) - # Action distribution (populated in update_distribution) - self.distribution = None - # disable args validation for speedup - Normal.set_default_validate_args(False) - - def reset(self, dones=None): - pass - - def forward(self): - raise NotImplementedError - - @property - def action_mean(self): - return self.distribution.mean - - @property - def action_std(self): - return self.distribution.stddev - - @property - def entropy(self): - return self.distribution.entropy().sum(dim=-1) - - def update_distribution(self, observations): - mean = self.actor(observations) - self.distribution = Normal(mean, self.std) - - def act(self, observations, **kwargs): - self.update_distribution(observations) - return self.distribution.sample() - - def get_actions_log_prob(self, actions): - return self.distribution.log_prob(actions).sum(dim=-1) - - def act_inference(self, observations): - actions_mean = self.actor(observations) - return actions_mean - - def evaluate(self, critic_observations, **kwargs): - value = self.critic(critic_observations) - return value diff --git a/scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py b/scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py deleted file mode 100644 index 9f11a8d38936..000000000000 --- a/scripts/reinforcement_learning/rsl_rl/on_policy_runner_conv2d.py +++ /dev/null @@ -1,67 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers. -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -from __future__ import annotations - -import torch - -import rsl_rl -from actor_critic_conv2d import ActorCriticConv2d -from rsl_rl.algorithms import PPO -from rsl_rl.env import VecEnv -from rsl_rl.modules import EmpiricalNormalization -from rsl_rl.runners import OnPolicyRunner - - -class OnPolicyRunnerConv2d(OnPolicyRunner): - """Custom on-policy runner for training and evaluation with convolutional actor-critic.""" - - def __init__(self, env: VecEnv, train_cfg, log_dir=None, device="cpu"): - self.cfg = train_cfg - self.alg_cfg = train_cfg["algorithm"] - self.policy_cfg = train_cfg["policy"] - self.device = device - self.env = env - obs, extras = self.env.get_observations() - num_obs = obs.shape[1] - if "critic" in extras["observations"]: - num_critic_obs = extras["observations"]["critic"].shape[1] - else: - num_critic_obs = num_obs - - # init the actor-critic networks - actor_critic: ActorCriticConv2d = ActorCriticConv2d( - num_obs, num_critic_obs, self.env.num_actions, **self.policy_cfg - ).to(self.device) - - # init the ppo algorithm - alg_class = eval(self.alg_cfg.pop("class_name")) # PPO - self.alg: PPO = alg_class(actor_critic, device=self.device, **self.alg_cfg) - self.num_steps_per_env = self.cfg["num_steps_per_env"] - self.save_interval = self.cfg["save_interval"] - self.empirical_normalization = self.cfg["empirical_normalization"] - if self.empirical_normalization: - self.obs_normalizer = EmpiricalNormalization(shape=[num_obs], until=1.0e8).to(self.device) - self.critic_obs_normalizer = EmpiricalNormalization(shape=[num_critic_obs], until=1.0e8).to(self.device) - else: - self.obs_normalizer = torch.nn.Identity().to(self.device) # no normalization - self.critic_obs_normalizer = torch.nn.Identity().to(self.device) # no normalization - - # init storage and model - self.alg.init_storage( - self.env.num_envs, - self.num_steps_per_env, - [num_obs], - [num_critic_obs], - [self.env.num_actions], - ) - - # Log - self.log_dir = log_dir - self.writer = None - self.tot_timesteps = 0 - self.tot_time = 0 - self.current_learning_iteration = 0 - self.git_status_repos = [rsl_rl.__file__] From 5c041ddcd033bab73294d9b7d5eef6f405d3b9e7 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Mon, 10 Mar 2025 20:32:50 -0700 Subject: [PATCH 10/12] separate policy and sensor observations; modifyonnx exporter; clean train and play code --- scripts/reinforcement_learning/rsl_rl/play.py | 12 +----------- scripts/reinforcement_learning/rsl_rl/train.py | 12 +----------- source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py | 2 -- source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py | 3 --- .../config/anymal_c/agents/rsl_rl_ppo_cfg.py | 1 - .../config/anymal_c/navigation_obstacle_env_cfg.py | 7 ++++++- 6 files changed, 8 insertions(+), 29 deletions(-) diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index 0da6231290c9..fa91eeb2b1d6 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -49,8 +49,7 @@ import time import torch -from on_policy_runner_conv2d import OnPolicyRunnerConv2d -from rsl_rl.runners import OnPolicyRunner +from rsl_rl.runners import OnPolicyRunner, OnPolicyRunnerConv2d from isaaclab.envs import DirectMARLEnv, multi_agent_to_single_agent from isaaclab.utils.assets import retrieve_file_path @@ -112,15 +111,6 @@ def main(): print(f"[INFO]: Loading model checkpoint from: {resume_path}") # load previously trained model if agent_cfg.policy.class_name == "ActorCriticConv2d": - if ( - env_cfg.scene.tiled_camera.height != agent_cfg.policy.image_input_shape[1] - or env_cfg.scene.tiled_camera.width != agent_cfg.policy.image_input_shape[2] - ): - raise ValueError( - f"Mismatch in camera dimensions: tiled_camera.height={env_cfg.scene.tiled_camera.height}," - f" tiled_camera.width={env_cfg.scene.tiled_camera.width} must match" - f" image_input_shape={agent_cfg.policy.image_input_shape[1]}x{agent_cfg.policy.image_input_shape[2]}" - ) ppo_runner = OnPolicyRunnerConv2d(env, agent_cfg.to_dict(), log_dir=None, device=agent_cfg.device) else: ppo_runner = OnPolicyRunner(env, agent_cfg.to_dict(), log_dir=None, device=agent_cfg.device) diff --git a/scripts/reinforcement_learning/rsl_rl/train.py b/scripts/reinforcement_learning/rsl_rl/train.py index 664071b08a6d..8f06c5b3c194 100644 --- a/scripts/reinforcement_learning/rsl_rl/train.py +++ b/scripts/reinforcement_learning/rsl_rl/train.py @@ -49,8 +49,7 @@ import torch from datetime import datetime -from on_policy_runner_conv2d import OnPolicyRunnerConv2d -from rsl_rl.runners import OnPolicyRunner +from rsl_rl.runners import OnPolicyRunner, OnPolicyRunnerConv2d from isaaclab.envs import ( DirectMARLEnv, @@ -129,15 +128,6 @@ def main(env_cfg: ManagerBasedRLEnvCfg | DirectRLEnvCfg | DirectMARLEnvCfg, agen # create runner from rsl-rl if agent_cfg.policy.class_name == "ActorCriticConv2d": - if ( - env_cfg.scene.tiled_camera.height != agent_cfg.policy.image_input_shape[1] - or env_cfg.scene.tiled_camera.width != agent_cfg.policy.image_input_shape[2] - ): - raise ValueError( - f"Mismatch in camera dimensions: tiled_camera.height={env_cfg.scene.tiled_camera.height}," - f" tiled_camera.width={env_cfg.scene.tiled_camera.width} must match" - f" image_input_shape={agent_cfg.policy.image_input_shape[1]}x{agent_cfg.policy.image_input_shape[2]}" - ) runner = OnPolicyRunnerConv2d(env, agent_cfg.to_dict(), log_dir=log_dir, device=agent_cfg.device) else: runner = OnPolicyRunner(env, agent_cfg.to_dict(), log_dir=log_dir, device=agent_cfg.device) diff --git a/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py b/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py index 458f2dff8ef2..09ae4a4da8ff 100644 --- a/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py +++ b/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py @@ -138,8 +138,6 @@ def export(self, path, filename): ) else: input_size = getattr(self.actor, "input_dim", None) - if input_size is None: - input_size = self.actor[0].in_features obs = torch.zeros(1, input_size) torch.onnx.export( self, diff --git a/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py b/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py index 384d77ae20ff..89aa36c9abd7 100644 --- a/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py +++ b/source/isaaclab_rl/isaaclab_rl/rsl_rl/rl_cfg.py @@ -46,9 +46,6 @@ class RslRlPpoActorCriticConv2dCfg(RslRlPpoActorCriticCfg): conv_linear_output_size: int = 16 """Output size of the linear layer after the convolutional features are flattened.""" - image_input_shape: tuple[int, int, int] = (3, 64, 64) - """Shape of the image input in (channels, height, width).""" - @configclass class RslRlPpoAlgorithmCfg: diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py index 942b4ee15d85..1245e2031241 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/agents/rsl_rl_ppo_cfg.py @@ -60,7 +60,6 @@ class NavigationEnvPPOConv2dRunnerCfg(RslRlOnPolicyRunnerCfg): {"out_channels": 16, "kernel_size": 3, "stride": 2}, ], conv_linear_output_size=16, - image_input_shape=(3, 64, 64), ) algorithm = RslRlPpoAlgorithmCfg( value_loss_coef=1.0, diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py index 14ddcb916867..b74aa926b422 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/navigation/config/anymal_c/navigation_obstacle_env_cfg.py @@ -79,10 +79,15 @@ class PolicyCfg(ObsGroup): base_lin_vel = ObsTerm(func=mdp.base_lin_vel) projected_gravity = ObsTerm(func=mdp.projected_gravity) pose_command = ObsTerm(func=mdp.generated_commands, params={"command_name": "pose_command"}) - camera_data = ObsTerm(func=mdp.image_flatten, params={"sensor_cfg": SceneEntityCfg("tiled_camera")}) + + class SensorCfg(ObsGroup): + """Observations for sensor group.""" + + camera_data = ObsTerm(func=mdp.image, params={"sensor_cfg": SceneEntityCfg("tiled_camera")}) # observation groups policy: PolicyCfg = PolicyCfg() + sensor: SensorCfg = SensorCfg() @configclass From aa3d6434274552eda8189ec32c71714482205ef2 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Mon, 10 Mar 2025 22:14:39 -0700 Subject: [PATCH 11/12] fix policy play: handle inputs for both mlp and conv2d networks --- scripts/reinforcement_learning/rsl_rl/play.py | 10 ++++++++-- source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py | 2 ++ 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/scripts/reinforcement_learning/rsl_rl/play.py b/scripts/reinforcement_learning/rsl_rl/play.py index fa91eeb2b1d6..a6e38f13f6fe 100644 --- a/scripts/reinforcement_learning/rsl_rl/play.py +++ b/scripts/reinforcement_learning/rsl_rl/play.py @@ -131,7 +131,10 @@ def main(): dt = env.unwrapped.physics_dt # reset environment - obs, _ = env.get_observations() + obs, extras = env.get_observations() + if "sensor" in extras["observations"]: + image_obs = extras["observations"]["sensor"].permute(0, 3, 1, 2).flatten(start_dim=1) + obs = torch.cat([obs, image_obs], dim=1) timestep = 0 # simulate environment while simulation_app.is_running(): @@ -141,7 +144,10 @@ def main(): # agent stepping actions = policy(obs) # env stepping - obs, _, _, _ = env.step(actions) + obs, _, _, infos = env.step(actions) + if "sensor" in infos["observations"]: + image_obs = infos["observations"]["sensor"].permute(0, 3, 1, 2).flatten(start_dim=1) + obs = torch.cat([obs, image_obs], dim=1) if args_cli.video: timestep += 1 # Exit the play loop after recording one video diff --git a/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py b/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py index 09ae4a4da8ff..458f2dff8ef2 100644 --- a/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py +++ b/source/isaaclab_rl/isaaclab_rl/rsl_rl/exporter.py @@ -138,6 +138,8 @@ def export(self, path, filename): ) else: input_size = getattr(self.actor, "input_dim", None) + if input_size is None: + input_size = self.actor[0].in_features obs = torch.zeros(1, input_size) torch.onnx.export( self, From b80366721481fea34e9cf6cd449ac19bb3167b44 Mon Sep 17 00:00:00 2001 From: KingsleyLiu-NV Date: Mon, 10 Mar 2025 23:32:45 -0700 Subject: [PATCH 12/12] remove flatten image observations --- source/isaaclab/docs/CHANGELOG.rst | 1 - .../isaaclab/isaaclab/envs/mdp/observations.py | 16 ---------------- 2 files changed, 17 deletions(-) diff --git a/source/isaaclab/docs/CHANGELOG.rst b/source/isaaclab/docs/CHANGELOG.rst index d874f7aa41ae..160d2e3457e6 100644 --- a/source/isaaclab/docs/CHANGELOG.rst +++ b/source/isaaclab/docs/CHANGELOG.rst @@ -9,7 +9,6 @@ Added * Added the pose2d command that generates the target position based on the position of the obstacle object. * Added the reset event that samples a position in a sector of a ring area defined by the radius and angle ranges. -* Added the observation function for getting flattned normalized rgb data. 0.34.9 (2025-03-04) diff --git a/source/isaaclab/isaaclab/envs/mdp/observations.py b/source/isaaclab/isaaclab/envs/mdp/observations.py index 686ccdb3e48e..12e93b69d287 100644 --- a/source/isaaclab/isaaclab/envs/mdp/observations.py +++ b/source/isaaclab/isaaclab/envs/mdp/observations.py @@ -231,22 +231,6 @@ def imu_lin_acc(env: ManagerBasedEnv, asset_cfg: SceneEntityCfg = SceneEntityCfg return asset.data.lin_acc_b -def image_flatten(env: ManagerBasedEnv, sensor_cfg: SceneEntityCfg) -> torch.Tensor: - """RGB-D data from the given sensor w.r.t. the sensor's frame.""" - # extract the used quantities (to enable type-hinting) - sensor: TiledCamera = env.scene.sensors[sensor_cfg.name] - # tiled camera data already normalized - rgb_image = sensor.data.output["rgb"][..., 0:3] - rgb_image = rgb_image.permute(0, 3, 1, 2) - rgb_image = rgb_image.float() - rgb_image /= 255.0 - - mean_tensor = torch.mean(rgb_image, dim=(2, 3), keepdim=True) - rgb_image -= mean_tensor - rgb_image = rgb_image.contiguous().view(rgb_image.size(0), -1) - return rgb_image - - def image( env: ManagerBasedEnv, sensor_cfg: SceneEntityCfg = SceneEntityCfg("tiled_camera"),