From 1fdc9c538db2aa7fa39b91384b5de786c1cfa867 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Tue, 25 Nov 2025 06:32:48 +0000 Subject: [PATCH 01/32] added openarm asset --- .../isaaclab_assets/robots/openarm.py | 179 ++++++++++++++++++ 1 file changed, 179 insertions(+) create mode 100644 source/isaaclab_assets/isaaclab_assets/robots/openarm.py diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py new file mode 100644 index 00000000000..e805ae7ab89 --- /dev/null +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -0,0 +1,179 @@ +# Copyright 2025 Enactic, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Configuration of OpenArm robots. + +The following configurations are available: + +* :obj:`OPENARM_BI_CFG`: OpenArm robot with two arms. +* :obj:`OPENARM_BI_HIGH_PD_CFG`: OpenArm robot with two arms and stiffer PD control. +* :obj:`OPENARM_UNI_CFG`: OpenArm robot with one arm. +* :obj:`OPENARM_UNI_HIGH_PD_CFG`: OpenArm robot with one arm and stiffer PD control. + +Reference: https://github.com/enactic/openarm_isaac_lab +""" + +import isaaclab.sim as sim_utils +from isaaclab.actuators import ImplicitActuatorCfg +from isaaclab.assets.articulation import ArticulationCfg + +from openarm_isaac_lab.source.openarm.openarm.tasks.manager_based.openarm_manipulation import ( + OPENARM_ROOT_DIR, +) + +OPENARM_BI_CFG = ArticulationCfg( + spawn=sim_utils.UsdFileCfg( + usd_path=f"{OPENARM_ROOT_DIR}/usds/openarm_bimanual/openarm_bimanual.usd", + rigid_props=sim_utils.RigidBodyPropertiesCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + articulation_props=sim_utils.ArticulationRootPropertiesCfg( + enabled_self_collisions=False, + solver_position_iteration_count=8, + solver_velocity_iteration_count=0, + ), + ), + init_state=ArticulationCfg.InitialStateCfg( + joint_pos={ + "openarm_left_joint1": 0.0, + "openarm_left_joint2": 0.0, + "openarm_left_joint3": 0.0, + "openarm_left_joint4": 0.0, + "openarm_left_joint5": 0.0, + "openarm_left_joint6": 0.0, + "openarm_left_joint7": 0.0, + "openarm_right_joint1": 0.0, + "openarm_right_joint2": 0.0, + "openarm_right_joint3": 0.0, + "openarm_right_joint4": 0.0, + "openarm_right_joint5": 0.0, + "openarm_right_joint6": 0.0, + "openarm_right_joint7": 0.0, + "openarm_left_finger_joint.*": 0.044, + "openarm_right_finger_joint.*": 0.044, + }, + ), + actuators={ + "openarm_arm": ImplicitActuatorCfg( + joint_names_expr=[ + "openarm_left_joint[1-7]", + "openarm_right_joint[1-7]", + ], + velocity_limit_sim={ + "openarm_left_joint[1-2]": 2.175, + "openarm_right_joint[1-2]": 2.175, + "openarm_left_joint[3-4]": 2.175, + "openarm_right_joint[3-4]": 2.175, + "openarm_left_joint[5-7]": 2.61, + "openarm_right_joint[5-7]": 2.61, + }, + effort_limit_sim={ + "openarm_left_joint[1-2]": 40.0, + "openarm_right_joint[1-2]": 40.0, + "openarm_left_joint[3-4]": 27.0, + "openarm_right_joint[3-4]": 27.0, + "openarm_left_joint[5-7]": 7.0, + "openarm_right_joint[5-7]": 7.0, + }, + stiffness=80.0, + damping=4.0, + ), + "openarm_gripper": ImplicitActuatorCfg( + joint_names_expr=[ + "openarm_left_finger_joint.*", + "openarm_right_finger_joint.*", + ], + velocity_limit_sim=0.2, + effort_limit_sim=333.33, + stiffness=2e3, + damping=1e2, + ), + }, + soft_joint_pos_limit_factor=1.0, +) +"""Configuration of OpenArm Bimanual robot.""" + +OPENARM_UNI_CFG = ArticulationCfg( + spawn=sim_utils.UsdFileCfg( + usd_path=f"{OPENARM_ROOT_DIR}/usds/openarm_unimanual/openarm_unimanual.usd", + rigid_props=sim_utils.RigidBodyPropertiesCfg( + disable_gravity=False, + max_depenetration_velocity=5.0, + ), + articulation_props=sim_utils.ArticulationRootPropertiesCfg( + enabled_self_collisions=False, + solver_position_iteration_count=8, + solver_velocity_iteration_count=0, + ), + ), + init_state=ArticulationCfg.InitialStateCfg( + joint_pos={ + "openarm_joint1": 1.57, + "openarm_joint2": 0.0, + "openarm_joint3": -1.57, + "openarm_joint4": 1.57, + "openarm_joint5": 0.0, + "openarm_joint6": 0.0, + "openarm_joint7": 0.0, + "openarm_finger_joint.*": 0.044, + }, + ), + actuators={ + "openarm_arm": ImplicitActuatorCfg( + joint_names_expr=["openarm_joint[1-7]"], + velocity_limit_sim={ + "openarm_joint[1-2]": 2.175, + "openarm_joint[3-4]": 2.175, + "openarm_joint[5-7]": 2.61, + }, + effort_limit_sim={ + "openarm_joint[1-2]": 40.0, + "openarm_joint[3-4]": 27.0, + "openarm_joint[5-7]": 7.0, + }, + stiffness=80.0, + damping=4.0, + ), + "openarm_gripper": ImplicitActuatorCfg( + joint_names_expr=["openarm_finger_joint.*"], + velocity_limit_sim=0.2, + effort_limit_sim=333.33, + stiffness=2e3, + damping=1e2, + ), + }, + soft_joint_pos_limit_factor=1.0, +) +"""Configuration of OpenArm Unimanual robot.""" + +OPENARM_BI_HIGH_PD_CFG = OPENARM_BI_CFG.copy() +OPENARM_BI_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True +OPENARM_BI_HIGH_PD_CFG.actuators["openarm_arm"].stiffness = 400.0 +OPENARM_BI_HIGH_PD_CFG.actuators["openarm_arm"].damping = 80.0 +OPENARM_BI_HIGH_PD_CFG.actuators["openarm_gripper"].stiffness = 2e3 +OPENARM_BI_HIGH_PD_CFG.actuators["openarm_gripper"].damping = 1e2 +"""Configuration of OpenArm Bimanual robot with stiffer PD control. + +This configuration is useful for task-space control using differential IK. +""" + +OPENARM_UNI_HIGH_PD_CFG = OPENARM_UNI_CFG.copy() +OPENARM_UNI_HIGH_PD_CFG.spawn.rigid_props.disable_gravity = True +OPENARM_UNI_HIGH_PD_CFG.actuators["openarm_arm"].stiffness = 400.0 +OPENARM_UNI_HIGH_PD_CFG.actuators["openarm_arm"].damping = 80.0 +"""Configuration of OpenArm Unimanual robot with stiffer PD control. + +This configuration is useful for task-space control using differential IK. +""" From a980b11ab870b318813dd6942b988172702d77d5 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Tue, 25 Nov 2025 06:34:10 +0000 Subject: [PATCH 02/32] updated a license --- .../isaaclab_assets/robots/openarm.py | 15 +++------------ 1 file changed, 3 insertions(+), 12 deletions(-) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index e805ae7ab89..3c4870e9b4f 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -1,16 +1,7 @@ -# Copyright 2025 Enactic, Inc. +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. # -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. +# SPDX-License-Identifier: BSD-3-Clause """Configuration of OpenArm robots. From ac2161b1e1f87f6de4e99dd287a75b71b40aa6e8 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Tue, 25 Nov 2025 09:58:32 +0000 Subject: [PATCH 03/32] added reach task with openarm bimanual --- .../reach/config/openarm/__init__.py | 36 ++ .../reach/config/openarm/agents/__init__.py | 4 + .../openarm/agents/rl_games_ppo_cfg.yaml | 83 +++++ .../config/openarm/agents/rsl_rl_ppo_cfg.py | 43 +++ .../config/openarm/agents/skrl_ppo_cfg.yaml | 85 +++++ .../reach/config/openarm/joint_pos_env_cfg.py | 90 +++++ .../reach/reach_openarm_bi_env_cfg.py | 351 ++++++++++++++++++ 7 files changed, 692 insertions(+) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rl_games_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rsl_rl_ppo_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/skrl_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py new file mode 100644 index 00000000000..9ac6be5a340 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py @@ -0,0 +1,36 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import gymnasium as gym + +from . import agents + +## +# Register Gym environments. +## + +gym.register( + id="Isaac-Reach-OpenArm-Bi-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmReachEnvCfg", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmReachPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Reach-OpenArm-Bi-Play-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmReachEnvCfg_PLAY", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmReachPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/__init__.py new file mode 100644 index 00000000000..2e924fbf1b1 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rl_games_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rl_games_ppo_cfg.yaml new file mode 100644 index 00000000000..01a594e9687 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rl_games_ppo_cfg.yaml @@ -0,0 +1,83 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +params: + seed: 42 + + # environment wrapper clipping + env: + clip_observations: 100.0 + clip_actions: 100.0 + + algo: + name: a2c_continuous + + model: + name: continuous_a2c_logstd + + network: + name: actor_critic + separate: False + space: + continuous: + mu_activation: None + sigma_activation: None + + mu_init: + name: default + sigma_init: + name: const_initializer + val: 0 + fixed_sigma: True + mlp: + units: [64, 64] + activation: elu + d2rl: False + + initializer: + name: default + regularizer: + name: None + + load_checkpoint: False # flag which sets whether to load the checkpoint + load_path: '' # path to the checkpoint to load + + config: + name: openarm_bi_reach + env_name: rlgpu + device: 'cuda:0' + device_name: 'cuda:0' + multi_gpu: False + ppo: True + mixed_precision: False + normalize_input: True + normalize_value: True + value_bootstrap: True + num_actors: -1 + reward_shaper: + scale_value: 1.0 + normalize_advantage: True + gamma: 0.99 + tau: 0.95 + learning_rate: 1e-3 + lr_schedule: adaptive + schedule_type: legacy + kl_threshold: 0.01 + score_to_win: 10000 + max_epochs: 1000 + save_best_after: 200 + save_frequency: 100 + print_stats: True + grad_norm: 1.0 + entropy_coef: 0.01 + truncate_grads: True + e_clip: 0.2 + horizon_length: 24 + minibatch_size: 24576 + mini_epochs: 5 + critic_coef: 2 + clip_value: True + clip_actions: False + bounds_loss_coef: 0.0001 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rsl_rl_ppo_cfg.py new file mode 100644 index 00000000000..658f4f9f525 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rsl_rl_ppo_cfg.py @@ -0,0 +1,43 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab_rl.rsl_rl import ( + RslRlOnPolicyRunnerCfg, + RslRlPpoActorCriticCfg, + RslRlPpoAlgorithmCfg, +) + +from isaaclab.utils import configclass + + +@configclass +class OpenArmReachPPORunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 24 + max_iterations = 550 + save_interval = 50 + experiment_name = "openarm_bi_reach" + run_name = "" + resume = False + empirical_normalization = False + policy = RslRlPpoActorCriticCfg( + init_noise_std=1.0, + actor_hidden_dims=[64, 64], + critic_hidden_dims=[64, 64], + activation="elu", + ) + algorithm = RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.001, + num_learning_epochs=8, + num_mini_batches=4, + learning_rate=1.0e-2, + 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/manipulation/reach/config/openarm/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/skrl_ppo_cfg.yaml new file mode 100644 index 00000000000..c037a4b4ce0 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/skrl_ppo_cfg.yaml @@ -0,0 +1,85 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +seed: 42 + + +# Models are instantiated using skrl's model instantiator utility +# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html +models: + separate: False + policy: # see gaussian_model parameters + class: GaussianMixin + clip_actions: False + clip_log_std: True + min_log_std: -20.0 + max_log_std: 2.0 + initial_log_std: 0.0 + network: + - name: net + input: STATES + layers: [64, 64] + activations: elu + output: ACTIONS + value: # see deterministic_model parameters + class: DeterministicMixin + clip_actions: False + network: + - name: net + input: STATES + layers: [64, 64] + activations: elu + output: ONE + + +# Rollout memory +# https://skrl.readthedocs.io/en/latest/api/memories/random.html +memory: + class: RandomMemory + memory_size: -1 # automatically determined (same as agent:rollouts) + + +# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) +# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html +agent: + class: PPO + rollouts: 24 + learning_epochs: 5 + mini_batches: 4 + discount_factor: 0.99 + lambda: 0.95 + learning_rate: 1.0e-03 + learning_rate_scheduler: KLAdaptiveLR + learning_rate_scheduler_kwargs: + kl_threshold: 0.01 + state_preprocessor: RunningStandardScaler + state_preprocessor_kwargs: null + value_preprocessor: RunningStandardScaler + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 + value_clip: 0.2 + clip_predicted_values: True + entropy_loss_scale: 0.01 + value_loss_scale: 1.0 + kl_threshold: 0.0 + rewards_shaper_scale: 1.0 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "openarm_bi_reach" + experiment_name: "" + write_interval: auto + checkpoint_interval: auto + + +# Sequential trainer +# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html +trainer: + class: SequentialTrainer + timesteps: 24000 + environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py new file mode 100644 index 00000000000..039eef33557 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py @@ -0,0 +1,90 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import math + +from isaaclab.utils import configclass + +import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp +from isaaclab_tasks.isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_bi_env_cfg import ( + ReachEnvCfg, +) + +## +# Pre-defined configs +## +from openarm_isaac_lab.source.openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_BI_HIGH_PD_CFG + +## +# Environment configuration +## + + +@configclass +class OpenArmReachEnvCfg(ReachEnvCfg): + + def __post_init__(self): + # post init of parent + super().__post_init__() + + # switch robot to OpenArm + self.scene.robot = OPENARM_BI_HIGH_PD_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + + # override rewards + self.rewards.left_end_effector_position_tracking.params["asset_cfg"].body_names = ["openarm_left_hand"] + self.rewards.left_end_effector_position_tracking_fine_grained.params["asset_cfg"].body_names = ["openarm_left_hand"] + self.rewards.left_end_effector_orientation_tracking.params["asset_cfg"].body_names = ["openarm_left_hand"] + + self.rewards.right_end_effector_position_tracking.params["asset_cfg"].body_names = ["openarm_right_hand"] + self.rewards.right_end_effector_position_tracking_fine_grained.params["asset_cfg"].body_names = ["openarm_right_hand"] + self.rewards.right_end_effector_orientation_tracking.params["asset_cfg"].body_names = ["openarm_right_hand"] + + # override actions + self.actions.left_arm_action = mdp.JointPositionActionCfg( + asset_name="robot", + joint_names=[ + "openarm_left_joint1", + "openarm_left_joint2", + "openarm_left_joint3", + "openarm_left_joint4", + "openarm_left_joint5", + "openarm_left_joint6", + "openarm_left_joint7", + ], + scale=0.5, + use_default_offset=True, + ) + + self.actions.right_arm_action = mdp.JointPositionActionCfg( + asset_name="robot", + joint_names=[ + "openarm_right_joint1", + "openarm_right_joint2", + "openarm_right_joint3", + "openarm_right_joint4", + "openarm_right_joint5", + "openarm_right_joint6", + "openarm_right_joint7", + ], + scale=0.5, + use_default_offset=True, + ) + + # override command generator body + # end-effector is along z-direction + self.commands.left_ee_pose.body_name = "openarm_left_hand" + self.commands.right_ee_pose.body_name = "openarm_right_hand" + + +@configclass +class OpenArmReachEnvCfg_PLAY(OpenArmReachEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + # make a smaller scene for play + self.scene.num_envs = 50 + self.scene.env_spacing = 2.5 + # disable randomization for play + self.observations.policy.enable_corruption = False diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py new file mode 100644 index 00000000000..5e6ad87d6e8 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py @@ -0,0 +1,351 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from dataclasses import MISSING + +import isaaclab.sim as sim_utils +from isaaclab.actuators import ImplicitActuatorCfg +from isaaclab.assets.articulation import ArticulationCfg +from isaaclab.assets import ArticulationCfg, AssetBaseCfg +from isaaclab.envs import ManagerBasedRLEnvCfg +from isaaclab.managers import ActionTermCfg as ActionTerm +from isaaclab.managers import CurriculumTermCfg as CurrTerm +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.scene import InteractiveSceneCfg +from isaaclab.utils import configclass +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR +from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise + +import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp + +import math + +## +# Scene definition +## + + +@configclass +class ReachSceneCfg(InteractiveSceneCfg): + """Configuration for the scene with a robotic arm.""" + + # world + ground = AssetBaseCfg( + prim_path="/World/ground", + spawn=sim_utils.GroundPlaneCfg(), + init_state=AssetBaseCfg.InitialStateCfg(pos=(0.0, 0.0, 0)), + ) + + # robots + robot: ArticulationCfg = MISSING + + # lights + light = AssetBaseCfg( + prim_path="/World/light", + spawn=sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=2500.0), + ) + + +## +# MDP settings +## + + +@configclass +class CommandsCfg: + """Command terms for the MDP.""" + + left_ee_pose = mdp.UniformPoseCommandCfg( + asset_name="robot", + body_name=MISSING, + resampling_time_range=(4.0, 4.0), + debug_vis=True, + ranges=mdp.UniformPoseCommandCfg.Ranges( + pos_x=(0.15, 0.3), + pos_y=(0.15, 0.25), + pos_z=(0.3, 0.5), + roll=(-math.pi / 6, math.pi / 6), + pitch=(3 * math.pi / 2, 3 * math.pi / 2), + yaw=(8 * math.pi / 9, 10 * math.pi / 9), + ), + ) + + right_ee_pose = mdp.UniformPoseCommandCfg( + asset_name="robot", + body_name=MISSING, + resampling_time_range=(4.0, 4.0), + debug_vis=True, + ranges=mdp.UniformPoseCommandCfg.Ranges( + pos_x=(0.15, 0.3), + pos_y=(-0.25, -0.15), + pos_z=(0.3, 0.5), + roll=(-math.pi / 6, math.pi / 6), + pitch=(3 * math.pi / 2, 3 * math.pi / 2), + yaw=(8 * math.pi / 9, 10 * math.pi / 9), + ), + ) + + +@configclass +class ActionsCfg: + """Action specifications for the MDP.""" + + left_arm_action: ActionTerm = MISSING + right_arm_action: ActionTerm = MISSING + + +@configclass +class ObservationsCfg: + """Observation specifications for the MDP.""" + + @configclass + class PolicyCfg(ObsGroup): + """Observations for policy group.""" + + # observation terms (order preserved) + left_joint_pos = ObsTerm( + func=mdp.joint_pos_rel, + params={ + "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_left_joint1", + "openarm_left_joint2", + "openarm_left_joint3", + "openarm_left_joint4", + "openarm_left_joint5", + "openarm_left_joint6", + "openarm_left_joint7", + ]) + }, + noise=Unoise(n_min=-0.01, n_max=0.01), + ) + + right_joint_pos = ObsTerm( + func=mdp.joint_pos_rel, + params={ + "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_right_joint1", + "openarm_right_joint2", + "openarm_right_joint3", + "openarm_right_joint4", + "openarm_right_joint5", + "openarm_right_joint6", + "openarm_right_joint7" + ]) + }, + noise=Unoise(n_min=-0.01, n_max=0.01), + ) + + left_joint_vel = ObsTerm( + func=mdp.joint_vel_rel, + params={ + "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_left_joint1", + "openarm_left_joint2", + "openarm_left_joint3", + "openarm_left_joint4", + "openarm_left_joint5", + "openarm_left_joint6", + "openarm_left_joint7", + ]) + }, + noise=Unoise(n_min=-0.01, n_max=0.01), + ) + right_joint_vel = ObsTerm( + func=mdp.joint_vel_rel, + params={ + "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_right_joint1", + "openarm_right_joint2", + "openarm_right_joint3", + "openarm_right_joint4", + "openarm_right_joint5", + "openarm_right_joint6", + "openarm_right_joint7" + ]) + }, + noise=Unoise(n_min=-0.01, n_max=0.01), + ) + left_pose_command = ObsTerm( + func=mdp.generated_commands, params={"command_name": "left_ee_pose"} + ) + right_pose_command = ObsTerm( + func=mdp.generated_commands, params={"command_name": "right_ee_pose"} + ) + left_actions = ObsTerm(func=mdp.last_action, + params={ + "action_name": "left_arm_action"}) + right_actions = ObsTerm(func=mdp.last_action, + params={ + "action_name": "right_arm_action"}) + + def __post_init__(self): + self.enable_corruption = True + self.concatenate_terms = True + + # observation groups + policy: PolicyCfg = PolicyCfg() + + +@configclass +class EventCfg: + """Configuration for events.""" + + reset_robot_joints = EventTerm( + func=mdp.reset_joints_by_scale, + mode="reset", + params={ + "position_range": (0.5, 1.5), + "velocity_range": (0.0, 0.0), + }, + ) + + +@configclass +class RewardsCfg: + """Reward terms for the MDP.""" + + # task terms + left_end_effector_position_tracking = RewTerm( + func=mdp.position_command_error, + weight=-0.2, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "command_name": "left_ee_pose", + }, + ) + + right_end_effector_position_tracking = RewTerm( + func=mdp.position_command_error, + weight=-0.25, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "command_name": "right_ee_pose", + }, + ) + + left_end_effector_position_tracking_fine_grained = RewTerm( + func=mdp.position_command_error_tanh, + weight=0.1, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "std": 0.1, + "command_name": "left_ee_pose", + }, + ) + + right_end_effector_position_tracking_fine_grained = RewTerm( + func=mdp.position_command_error_tanh, + weight=0.2, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "std": 0.1, + "command_name": "right_ee_pose", + }, + ) + + left_end_effector_orientation_tracking = RewTerm( + func=mdp.orientation_command_error, + weight=-0.1, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "command_name": "left_ee_pose", + }, + ) + + right_end_effector_orientation_tracking = RewTerm( + func=mdp.orientation_command_error, + weight=-0.1, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "command_name": "right_ee_pose", + }, + ) + + # action penalty + action_rate = RewTerm(func=mdp.action_rate_l2, weight=-0.0001) + left_joint_vel = RewTerm( + func=mdp.joint_vel_l2, + weight=-0.0001, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_left_joint1", + "openarm_left_joint2", + "openarm_left_joint3", + "openarm_left_joint4", + "openarm_left_joint5", + "openarm_left_joint6", + "openarm_left_joint7", + ])}, + ) + right_joint_vel = RewTerm( + func=mdp.joint_vel_l2, + weight=-0.0001, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_right_joint1", + "openarm_right_joint2", + "openarm_right_joint3", + "openarm_right_joint4", + "openarm_right_joint5", + "openarm_right_joint6", + "openarm_right_joint7" + ])}, + ) + + +@configclass +class TerminationsCfg: + """Termination terms for the MDP.""" + + time_out = DoneTerm(func=mdp.time_out, time_out=True) + + +@configclass +class CurriculumCfg: + """Curriculum terms for the MDP.""" + + action_rate = CurrTerm( + func=mdp.modify_reward_weight, + params={"term_name": "action_rate", "weight": -0.005, "num_steps": 4500}, + ) + + left_joint_vel = CurrTerm( + func=mdp.modify_reward_weight, + params={"term_name": "left_joint_vel", "weight": -0.001, "num_steps": 4500}, + ) + + right_joint_vel = CurrTerm( + func=mdp.modify_reward_weight, + params={"term_name": "right_joint_vel", "weight": -0.001, "num_steps": 4500}, + ) + + +## +# Environment configuration +## + + +@configclass +class ReachEnvCfg(ManagerBasedRLEnvCfg): + """Configuration for the reach end-effector pose tracking environment.""" + + # Scene settings + scene: ReachSceneCfg = ReachSceneCfg(num_envs=4096, env_spacing=2.5) + # Basic settings + observations: ObservationsCfg = ObservationsCfg() + actions: ActionsCfg = ActionsCfg() + commands: CommandsCfg = CommandsCfg() + # MDP settings + rewards: RewardsCfg = RewardsCfg() + terminations: TerminationsCfg = TerminationsCfg() + events: EventCfg = EventCfg() + curriculum: CurriculumCfg = CurriculumCfg() + + def __post_init__(self): + """Post initialization.""" + # general settings + self.decimation = 2 + self.sim.render_interval = self.decimation + self.episode_length_s = 24.0 + self.viewer.eye = (3.5, 3.5, 3.5) + # simulation settings + self.sim.dt = 1.0 / 60.0 From 158faa21124ade5bede5062608cfe039e8635171 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Tue, 25 Nov 2025 19:43:28 +0900 Subject: [PATCH 04/32] updated reach task with openarm bimanual --- source/isaaclab_assets/isaaclab_assets/robots/openarm.py | 4 +++- .../manipulation/reach/config/openarm/joint_pos_env_cfg.py | 6 ++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index 3c4870e9b4f..c7b9753eead 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -13,13 +13,15 @@ * :obj:`OPENARM_UNI_HIGH_PD_CFG`: OpenArm robot with one arm and stiffer PD control. Reference: https://github.com/enactic/openarm_isaac_lab + +Please `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab` to use these configurations. """ import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg -from openarm_isaac_lab.source.openarm.openarm.tasks.manager_based.openarm_manipulation import ( +from openarm.openarm.tasks.manager_based.openarm_manipulation import ( OPENARM_ROOT_DIR, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py index 039eef33557..d66535aa989 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py @@ -3,19 +3,17 @@ # # SPDX-License-Identifier: BSD-3-Clause -import math - from isaaclab.utils import configclass import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -from isaaclab_tasks.isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_bi_env_cfg import ( +from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_bi_env_cfg import ( ReachEnvCfg, ) ## # Pre-defined configs ## -from openarm_isaac_lab.source.openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_BI_HIGH_PD_CFG +from openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_BI_HIGH_PD_CFG ## # Environment configuration From 182ac164a746d366f8dab9c57a9b676216d08a3f Mon Sep 17 00:00:00 2001 From: JinnnK Date: Tue, 25 Nov 2025 19:55:39 +0900 Subject: [PATCH 05/32] added lift a cube task with openarm unimanual --- .../lift/config/openarm/__init__.py | 42 +++ .../lift/config/openarm/agents/__init__.py | 4 + .../openarm/agents/rl_games_ppo_cfg.yaml | 85 ++++++ .../config/openarm/agents/rsl_rl_ppo_cfg.py | 42 +++ .../config/openarm/agents/skrl_ppo_cfg.yaml | 85 ++++++ .../lift/config/openarm/joint_pos_env_cfg.py | 104 +++++++ .../lift/lift_openarm_uni_env_cfg.py | 265 ++++++++++++++++++ .../reach/config/openarm/__init__.py | 4 + .../reach/config/openarm/joint_pos_env_cfg.py | 2 +- 9 files changed, 632 insertions(+), 1 deletion(-) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rl_games_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_uni_env_cfg.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py new file mode 100644 index 00000000000..b9c4c89479e --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py @@ -0,0 +1,42 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import gymnasium as gym + +from . import agents + +## +# Register Gym environments. +## + +## +# Joint Position Control +## + +gym.register( + id="Isaac-Lift-Cube-OpenArm-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCubeLiftEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmLiftCubePPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml", + }, + disable_env_checker=True, +) + +gym.register( + id="Isaac-Lift-Cube-OpenArm-Play-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCubeLiftEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmLiftCubePPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml", + }, + disable_env_checker=True, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/__init__.py new file mode 100644 index 00000000000..2e924fbf1b1 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rl_games_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rl_games_ppo_cfg.yaml new file mode 100644 index 00000000000..70548b9d299 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rl_games_ppo_cfg.yaml @@ -0,0 +1,85 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +params: + seed: 42 + + # environment wrapper clipping + env: + clip_observations: 100.0 + clip_actions: 100.0 + + algo: + name: a2c_continuous + + model: + name: continuous_a2c_logstd + + network: + name: actor_critic + separate: False + space: + continuous: + mu_activation: None + sigma_activation: None + + mu_init: + name: default + sigma_init: + name: const_initializer + val: 0 + fixed_sigma: True + mlp: + units: [256, 128, 64] + activation: elu + d2rl: False + + initializer: + name: default + regularizer: + name: None + + load_checkpoint: False # flag which sets whether to load the checkpoint + load_path: '' # path to the checkpoint to load + + config: + name: openarm_lift + env_name: rlgpu + device: 'cuda:0' + device_name: 'cuda:0' + multi_gpu: False + ppo: True + mixed_precision: False + normalize_input: True + normalize_value: True + value_bootstrap: False + num_actors: -1 + reward_shaper: + scale_value: 0.01 + normalize_advantage: True + gamma: 0.99 + tau: 0.95 + learning_rate: 1e-4 + lr_schedule: adaptive + schedule_type: legacy + kl_threshold: 0.01 + score_to_win: 100000000 + max_epochs: 1500 + save_best_after: 100 + save_frequency: 50 + print_stats: True + grad_norm: 1.0 + entropy_coef: 0.001 + truncate_grads: True + e_clip: 0.2 + horizon_length: 24 + minibatch_size: 24576 + mini_epochs: 8 + critic_coef: 4 + clip_value: True + clip_actions: False + seq_len: 4 + bounds_loss_coef: 0.0001 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py new file mode 100644 index 00000000000..cb94987a450 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py @@ -0,0 +1,42 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +from isaaclab.utils import configclass + +from isaaclab_rl.rsl_rl import ( + RslRlOnPolicyRunnerCfg, + RslRlPpoActorCriticCfg, + RslRlPpoAlgorithmCfg, +) + + +@configclass +class OpenArmLiftCubePPORunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 24 + max_iterations = 2000 + save_interval = 50 + experiment_name = "openarm_lift" + empirical_normalization = False + policy = RslRlPpoActorCriticCfg( + init_noise_std=1.0, + actor_hidden_dims=[256, 128, 64], + critic_hidden_dims=[256, 128, 64], + activation="elu", + ) + algorithm = RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.006, + num_learning_epochs=5, + num_mini_batches=4, + learning_rate=1.0e-4, + schedule="adaptive", + gamma=0.98, + lam=0.95, + desired_kl=0.01, + max_grad_norm=1.0, + ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml new file mode 100644 index 00000000000..4f0b7ecd3a0 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml @@ -0,0 +1,85 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +seed: 42 + + +# Models are instantiated using skrl's model instantiator utility +# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html +models: + separate: False + policy: # see gaussian_model parameters + class: GaussianMixin + clip_actions: False + clip_log_std: True + min_log_std: -20.0 + max_log_std: 2.0 + initial_log_std: 0.0 + network: + - name: net + input: STATES + layers: [256, 128, 64] + activations: elu + output: ACTIONS + value: # see deterministic_model parameters + class: DeterministicMixin + clip_actions: False + network: + - name: net + input: STATES + layers: [256, 128, 64] + activations: elu + output: ONE + + +# Rollout memory +# https://skrl.readthedocs.io/en/latest/api/memories/random.html +memory: + class: RandomMemory + memory_size: -1 # automatically determined (same as agent:rollouts) + + +# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) +# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html +agent: + class: PPO + rollouts: 24 + learning_epochs: 8 + mini_batches: 4 + discount_factor: 0.99 + lambda: 0.95 + learning_rate: 1.0e-04 + learning_rate_scheduler: KLAdaptiveLR + learning_rate_scheduler_kwargs: + kl_threshold: 0.01 + state_preprocessor: RunningStandardScaler + state_preprocessor_kwargs: null + value_preprocessor: RunningStandardScaler + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 + value_clip: 0.2 + clip_predicted_values: True + entropy_loss_scale: 0.001 + value_loss_scale: 2.0 + kl_threshold: 0.0 + rewards_shaper_scale: 0.01 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "openarm_lift" + experiment_name: "" + write_interval: auto + checkpoint_interval: auto + + +# Sequential trainer +# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html +trainer: + class: SequentialTrainer + timesteps: 36000 + environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py new file mode 100644 index 00000000000..858fc4ec273 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py @@ -0,0 +1,104 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +from isaaclab.assets import RigidObjectCfg +from isaaclab.sensors import FrameTransformerCfg +from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg +from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg +from isaaclab.utils import configclass +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR + +from isaaclab_tasks.manager_based.manipulation.lift import mdp +from isaaclab_tasks.manager_based.manipulation.lift.lift_openarm_uni_env_cfg import ( + LiftEnvCfg, +) + +import math + +## +# Pre-defined configs +## +from isaaclab.markers.config import FRAME_MARKER_CFG # isort: skip +from source.openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_UNI_CFG + + +@configclass +class OpenArmCubeLiftEnvCfg(LiftEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + + # Set OpenArm as robot + self.scene.robot = OPENARM_UNI_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + + # Set actions for the specific robot type (OpenArm) + self.actions.arm_action = mdp.JointPositionActionCfg( + asset_name="robot", + joint_names=[ + "openarm_joint.*", + ], + scale=0.5, + use_default_offset=True, # False + ) + + self.actions.gripper_action = mdp.BinaryJointPositionActionCfg( + asset_name="robot", + joint_names=["openarm_finger_joint.*"], + open_command_expr={"openarm_finger_joint.*": 0.044}, + close_command_expr={"openarm_finger_joint.*": 0.0}, + ) + + # Set the body name for the end effector + self.commands.object_pose.body_name = "openarm_hand" + self.commands.object_pose.ranges.pitch = (math.pi / 2, math.pi / 2) + + # Set Cube as object + self.scene.object = RigidObjectCfg( + prim_path="{ENV_REGEX_NS}/Object", + init_state=RigidObjectCfg.InitialStateCfg( + pos=[0.4, 0, 0.055], rot=[1, 0, 0, 0] + ), + spawn=UsdFileCfg( + usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", + scale=(0.8, 0.8, 0.8), + rigid_props=RigidBodyPropertiesCfg( + solver_position_iteration_count=16, + solver_velocity_iteration_count=1, + max_angular_velocity=1000.0, + max_linear_velocity=1000.0, + max_depenetration_velocity=5.0, + disable_gravity=False, + ), + ), + ) + + # Listens to the required transforms + marker_cfg = FRAME_MARKER_CFG.copy() + marker_cfg.markers["frame"].scale = (0.1, 0.1, 0.1) + marker_cfg.prim_path = "/Visuals/FrameTransformer" + self.scene.ee_frame = FrameTransformerCfg( + prim_path="{ENV_REGEX_NS}/Robot/openarm_link0", + debug_vis=False, + visualizer_cfg=marker_cfg, + target_frames=[ + FrameTransformerCfg.FrameCfg( + prim_path="{ENV_REGEX_NS}/Robot/openarm_ee_tcp", + name="end_effector", + ), + ], + ) + + +@configclass +class OpenArmCubeLiftEnvCfg_PLAY(OpenArmCubeLiftEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + # make a smaller scene for play + self.scene.num_envs = 50 + self.scene.env_spacing = 2.5 + # disable randomization for play + self.observations.policy.enable_corruption = False diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_uni_env_cfg.py new file mode 100644 index 00000000000..613f8bfdf7a --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_uni_env_cfg.py @@ -0,0 +1,265 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +from dataclasses import MISSING + +import isaaclab.sim as sim_utils +from isaaclab.assets import ( + ArticulationCfg, + AssetBaseCfg, + DeformableObjectCfg, + RigidObjectCfg, +) +from isaaclab.envs import ManagerBasedRLEnvCfg +from isaaclab.managers import CurriculumTermCfg as CurrTerm +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.scene import InteractiveSceneCfg +from isaaclab.sensors.frame_transformer.frame_transformer_cfg import FrameTransformerCfg +from isaaclab.sim.spawners.from_files.from_files_cfg import GroundPlaneCfg, UsdFileCfg +from isaaclab.utils import configclass +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR + +from . import mdp + +## +# Scene definition +## + + +@configclass +class ObjectTableSceneCfg(InteractiveSceneCfg): + """Configuration for the lift scene with a robot and a object. + This is the abstract base implementation, the exact scene is defined in the derived classes + which need to set the target object, robot and end-effector frames + """ + + # robots: will be populated by agent env cfg + robot: ArticulationCfg = MISSING + # end-effector sensor: will be populated by agent env cfg + ee_frame: FrameTransformerCfg = MISSING + # target object: will be populated by agent env cfg + object: RigidObjectCfg | DeformableObjectCfg = MISSING + + # Table + table = AssetBaseCfg( + prim_path="{ENV_REGEX_NS}/Table", + init_state=AssetBaseCfg.InitialStateCfg( + pos=[0.5, 0, 0], rot=[0.707, 0, 0, 0.707] + ), + spawn=UsdFileCfg( + usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd" + ), + ) + + # plane + plane = AssetBaseCfg( + prim_path="/World/GroundPlane", + init_state=AssetBaseCfg.InitialStateCfg(pos=[0, 0, -1.05]), + spawn=GroundPlaneCfg(), + ) + + # lights + light = AssetBaseCfg( + prim_path="/World/light", + spawn=sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=3000.0), + ) + + +## +# MDP settings +## + + +@configclass +class CommandsCfg: + """Command terms for the MDP.""" + + object_pose = mdp.UniformPoseCommandCfg( + asset_name="robot", + body_name=MISSING, # will be set by agent env cfg + resampling_time_range=(5.0, 5.0), + debug_vis=True, + ranges=mdp.UniformPoseCommandCfg.Ranges( + pos_x=(0.2, 0.4), + pos_y=(-0.2, 0.2), + pos_z=(0.15, 0.4), + roll=(0.0, 0.0), + pitch=(0.0, 0.0), + yaw=(0.0, 0.0), + ), + ) + + +@configclass +class ActionsCfg: + """Action specifications for the MDP.""" + + # will be set by agent env cfg + arm_action: ( + mdp.JointPositionActionCfg | mdp.DifferentialInverseKinematicsActionCfg + ) = MISSING + gripper_action: mdp.BinaryJointPositionActionCfg = MISSING + + +@configclass +class ObservationsCfg: + """Observation specifications for the MDP.""" + + @configclass + class PolicyCfg(ObsGroup): + """Observations for policy group.""" + + joint_pos = ObsTerm( + func=mdp.joint_pos_rel, + params={ + "asset_cfg": SceneEntityCfg( + "robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"] + ) + }, + ) + joint_vel = ObsTerm( + func=mdp.joint_vel_rel, + params={ + "asset_cfg": SceneEntityCfg( + "robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"] + ) + }, + ) + object_position = ObsTerm(func=mdp.object_position_in_robot_root_frame) + target_object_position = ObsTerm( + func=mdp.generated_commands, params={"command_name": "object_pose"} + ) + actions = ObsTerm(func=mdp.last_action) + + def __post_init__(self): + self.enable_corruption = True + self.concatenate_terms = True + + # observation groups + policy: PolicyCfg = PolicyCfg() + + +@configclass +class EventCfg: + """Configuration for events.""" + + reset_all = EventTerm(func=mdp.reset_scene_to_default, mode="reset") + + reset_object_position = EventTerm( + func=mdp.reset_root_state_uniform, + mode="reset", + params={ + "pose_range": {"x": (-0.1, 0.1), "y": (-0.25, 0.25), "z": (0.0, 0.0)}, + "velocity_range": {}, + "asset_cfg": SceneEntityCfg("object", body_names="Object"), + }, + ) + + +@configclass +class RewardsCfg: + """Reward terms for the MDP.""" + + reaching_object = RewTerm( + func=mdp.object_ee_distance, params={"std": 0.1}, weight=1.1 + ) + + lifting_object = RewTerm( + func=mdp.object_is_lifted, params={"minimal_height": 0.04}, weight=15.0 + ) + + object_goal_tracking = RewTerm( + func=mdp.object_goal_distance, + params={"std": 0.3, "minimal_height": 0.04, "command_name": "object_pose"}, + weight=16.0, + ) + + object_goal_tracking_fine_grained = RewTerm( + func=mdp.object_goal_distance, + params={"std": 0.05, "minimal_height": 0.04, "command_name": "object_pose"}, + weight=5.0, + ) + + # action penalty + action_rate = RewTerm(func=mdp.action_rate_l2, weight=-1e-4) + + joint_vel = RewTerm( + func=mdp.joint_vel_l2, + weight=-1e-4, + params={ + "asset_cfg": SceneEntityCfg( + "robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"] + ) + }, + ) + + +@configclass +class TerminationsCfg: + """Termination terms for the MDP.""" + + time_out = DoneTerm(func=mdp.time_out, time_out=True) + + object_dropping = DoneTerm( + func=mdp.root_height_below_minimum, + params={"minimum_height": -0.05, "asset_cfg": SceneEntityCfg("object")}, + ) + + +@configclass +class CurriculumCfg: + """Curriculum terms for the MDP.""" + + action_rate = CurrTerm( + func=mdp.modify_reward_weight, + params={"term_name": "action_rate", "weight": -1e-1, "num_steps": 10000}, + ) + + joint_vel = CurrTerm( + func=mdp.modify_reward_weight, + params={"term_name": "joint_vel", "weight": -1e-1, "num_steps": 10000}, + ) + + +## +# Environment configuration +## + + +@configclass +class LiftEnvCfg(ManagerBasedRLEnvCfg): + """Configuration for the lifting environment.""" + + # Scene settings + scene: ObjectTableSceneCfg = ObjectTableSceneCfg(num_envs=4096, env_spacing=2.5) + # Basic settings + observations: ObservationsCfg = ObservationsCfg() + actions: ActionsCfg = ActionsCfg() + commands: CommandsCfg = CommandsCfg() + # MDP settings + rewards: RewardsCfg = RewardsCfg() + terminations: TerminationsCfg = TerminationsCfg() + events: EventCfg = EventCfg() + curriculum: CurriculumCfg = CurriculumCfg() + + def __post_init__(self): + """Post initialization.""" + # general settings + self.decimation = 2 + self.episode_length_s = 5.0 + # simulation settings + self.sim.dt = 0.01 # 100Hz + self.sim.render_interval = self.decimation + + self.sim.physx.bounce_threshold_velocity = 0.01 + self.sim.physx.gpu_found_lost_aggregate_pairs_capacity = 1024 * 1024 * 4 + self.sim.physx.gpu_total_aggregate_pairs_capacity = 16 * 1024 + self.sim.physx.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py index 9ac6be5a340..2de6f9a6777 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py @@ -11,6 +11,10 @@ # Register Gym environments. ## +## +# Joint Position Control +## + gym.register( id="Isaac-Reach-OpenArm-Bi-v0", entry_point="isaaclab.envs:ManagerBasedRLEnv", diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py index d66535aa989..f4f90769468 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py @@ -13,7 +13,7 @@ ## # Pre-defined configs ## -from openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_BI_HIGH_PD_CFG +from source.openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_BI_HIGH_PD_CFG ## # Environment configuration From 00a8aaffb5d731c05d7223b02092b4e0ce8136c6 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Tue, 25 Nov 2025 20:44:23 +0900 Subject: [PATCH 06/32] added reach and cabinet task with openarm unimanual --- .../isaaclab_assets/robots/openarm.py | 8 +- .../cabinet/cabinet_openarm_env_cfg.py | 277 ++++++++++++++++++ .../cabinet/config/openarm/__init__.py | 40 +++ .../config/openarm/agents/__init__.py | 0 .../openarm/agents/rl_games_ppo_cfg.yaml | 81 +++++ .../config/openarm/agents/rsl_rl_ppo_cfg.py | 37 +++ .../config/openarm/agents/skrl_ppo_cfg.yaml | 85 ++++++ .../config/openarm/joint_pos_env_cfg.py | 93 ++++++ .../lift/config/openarm/joint_pos_env_cfg.py | 4 +- ...uni_env_cfg.py => lift_openarm_env_cfg.py} | 0 .../config/openarm/{ => bimanual}/__init__.py | 0 .../openarm/bimanual/agents/__init__.py | 4 + .../agents/rl_games_ppo_cfg.yaml | 0 .../{ => bimanual}/agents/rsl_rl_ppo_cfg.py | 0 .../{ => bimanual}/agents/skrl_ppo_cfg.yaml | 0 .../{ => bimanual}/joint_pos_env_cfg.py | 2 +- .../config/openarm/unimanual/__init__.py | 33 +++ .../openarm/unimanual/agents/__init__.py | 4 + .../unimanual/agents/rl_games_ppo_cfg.yaml | 84 ++++++ .../unimanual/agents/rsl_rl_ppo_cfg.py | 40 +++ .../unimanual/agents/skrl_ppo_cfg.yaml | 85 ++++++ .../openarm/unimanual/joint_pos_env_cfg.py | 77 +++++ .../reach/reach_openarm_uni_env_cfg.py | 273 +++++++++++++++++ 23 files changed, 1220 insertions(+), 7 deletions(-) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/{reach => cabinet}/config/openarm/agents/__init__.py (100%) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rl_games_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rsl_rl_ppo_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/{lift_openarm_uni_env_cfg.py => lift_openarm_env_cfg.py} (100%) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/{ => bimanual}/__init__.py (100%) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/__init__.py rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/{ => bimanual}/agents/rl_games_ppo_cfg.yaml (100%) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/{ => bimanual}/agents/rsl_rl_ppo_cfg.py (100%) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/{ => bimanual}/agents/skrl_ppo_cfg.yaml (100%) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/{ => bimanual}/joint_pos_env_cfg.py (96%) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/__init__.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rl_games_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/skrl_ppo_cfg.yaml create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index c7b9753eead..3a37c57f409 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -14,14 +14,14 @@ Reference: https://github.com/enactic/openarm_isaac_lab -Please `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab` to use these configurations. +Please `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab/source` to use these configurations. """ import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg -from openarm.openarm.tasks.manager_based.openarm_manipulation import ( +from source.openarm.openarm.tasks.manager_based.openarm_manipulation import ( OPENARM_ROOT_DIR, ) @@ -54,8 +54,8 @@ "openarm_right_joint5": 0.0, "openarm_right_joint6": 0.0, "openarm_right_joint7": 0.0, - "openarm_left_finger_joint.*": 0.044, - "openarm_right_finger_joint.*": 0.044, + "openarm_left_finger_joint.*": 0.0, + "openarm_right_finger_joint.*": 0.0, }, ), actuators={ diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py new file mode 100644 index 00000000000..953535d9280 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py @@ -0,0 +1,277 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from dataclasses import MISSING + +import isaaclab.sim as sim_utils +from isaaclab.actuators.actuator_cfg import ImplicitActuatorCfg +from isaaclab.assets import ArticulationCfg, AssetBaseCfg +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.scene import InteractiveSceneCfg +from isaaclab.sensors import FrameTransformerCfg +from isaaclab.sensors.frame_transformer import OffsetCfg +from isaaclab.utils import configclass +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR + +## +# Pre-defined configs +## +from isaaclab.markers.config import FRAME_MARKER_CFG # isort: skip + +FRAME_MARKER_SMALL_CFG = FRAME_MARKER_CFG.copy() +FRAME_MARKER_SMALL_CFG.markers["frame"].scale = (0.10, 0.10, 0.10) + +from . import mdp + +## +# Scene definition +## + + +@configclass +class CabinetSceneCfg(InteractiveSceneCfg): + """Configuration for the cabinet scene with a robot and a cabinet. + + This is the abstract base implementation, the exact scene is defined in the derived classes + which need to set the robot and end-effector frames + """ + + # robots, Will be populated by agent env cfg + robot: ArticulationCfg = MISSING + # End-effector, Will be populated by agent env cfg + ee_frame: FrameTransformerCfg = MISSING + + cabinet = ArticulationCfg( + prim_path="{ENV_REGEX_NS}/Cabinet", + spawn=sim_utils.UsdFileCfg( + usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Sektion_Cabinet/sektion_cabinet_instanceable.usd", + activate_contact_sensors=False, + scale=(0.75, 0.75, 0.75), + ), + init_state=ArticulationCfg.InitialStateCfg( + pos=(0.7, 0, 0.3), + rot=(0.0, 0.0, 0.0, 1.0), + joint_pos={ + "door_left_joint": 0.0, + "door_right_joint": 0.0, + "drawer_bottom_joint": 0.0, + "drawer_top_joint": 0.0, + }, + ), + actuators={ + "drawers": ImplicitActuatorCfg( + joint_names_expr=["drawer_top_joint", "drawer_bottom_joint"], + effort_limit=87.0, + velocity_limit=100.0, + stiffness=10.0, + damping=1.0, + ), + "doors": ImplicitActuatorCfg( + joint_names_expr=["door_left_joint", "door_right_joint"], + effort_limit=87.0, + velocity_limit=100.0, + stiffness=10.0, + damping=2.5, + ), + }, + ) + + # Frame definitions for the cabinet. + cabinet_frame = FrameTransformerCfg( + prim_path="{ENV_REGEX_NS}/Cabinet/sektion", + debug_vis=True, + visualizer_cfg=FRAME_MARKER_SMALL_CFG.replace(prim_path="/Visuals/CabinetFrameTransformer"), + target_frames=[ + FrameTransformerCfg.FrameCfg( + prim_path="{ENV_REGEX_NS}/Cabinet/drawer_handle_bottom", + name="drawer_handle_bottom", + offset=OffsetCfg( + pos=(0.222, 0.0, 0.005), + rot=(0.5, 0.5, -0.5, -0.5), # align with end-effector frame + ), + ), + ], + ) + + # plane + plane = AssetBaseCfg( + prim_path="/World/GroundPlane", + init_state=AssetBaseCfg.InitialStateCfg(), + spawn=sim_utils.GroundPlaneCfg(), + collision_group=-1, + ) + + # lights + light = AssetBaseCfg( + prim_path="/World/light", + spawn=sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=3000.0), + ) + + +## +# MDP settings +## + + +@configclass +class ActionsCfg: + """Action specifications for the MDP.""" + + arm_action: mdp.JointPositionActionCfg = MISSING + gripper_action: mdp.BinaryJointPositionActionCfg = MISSING + + +@configclass +class ObservationsCfg: + """Observation specifications for the MDP.""" + + @configclass + class PolicyCfg(ObsGroup): + """Observations for policy group.""" + + joint_pos = ObsTerm(func=mdp.joint_pos_rel) + joint_vel = ObsTerm(func=mdp.joint_vel_rel) + cabinet_joint_pos = ObsTerm( + func=mdp.joint_pos_rel, + params={"asset_cfg": SceneEntityCfg("cabinet", joint_names=["drawer_bottom_joint"])}, + ) + cabinet_joint_vel = ObsTerm( + func=mdp.joint_vel_rel, + params={"asset_cfg": SceneEntityCfg("cabinet", joint_names=["drawer_bottom_joint"])}, + ) + rel_ee_drawer_distance = ObsTerm(func=mdp.rel_ee_drawer_distance) + + actions = ObsTerm(func=mdp.last_action) + + def __post_init__(self): + self.enable_corruption = True + self.concatenate_terms = True + + # observation groups + policy: PolicyCfg = PolicyCfg() + + +@configclass +class EventCfg: + """Configuration for events.""" + + robot_physics_material = EventTerm( + func=mdp.randomize_rigid_body_material, + mode="startup", + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=".*"), + "static_friction_range": (0.8, 1.25), + "dynamic_friction_range": (0.8, 1.25), + "restitution_range": (0.0, 0.0), + "num_buckets": 16, + }, + ) + + cabinet_physics_material = EventTerm( + func=mdp.randomize_rigid_body_material, + mode="startup", + params={ + "asset_cfg": SceneEntityCfg("cabinet", body_names="drawer_handle_bottom"), + "static_friction_range": (2.0, 2.25), + "dynamic_friction_range": (2.25, 2.5), + "restitution_range": (0.0, 0.0), + "num_buckets": 16, + }, + ) + + reset_all = EventTerm(func=mdp.reset_scene_to_default, mode="reset") + + reset_robot_joints = EventTerm( + func=mdp.reset_joints_by_offset, + mode="reset", + params={ + "position_range": (-0.1, 0.1), + "velocity_range": (0.0, 0.0), + }, + ) + + +@configclass +class RewardsCfg: + """Reward terms for the MDP.""" + + # 1. Approach the handle + approach_ee_handle = RewTerm(func=mdp.approach_ee_handle, weight=2.0, params={"threshold": 0.2}) + align_ee_handle = RewTerm(func=mdp.align_ee_handle, weight=0.5) + + # 2. Grasp the handle + approach_gripper_handle = RewTerm(func=mdp.align_grasp_around_handle, weight=5.0, params={"offset": MISSING}) + align_grasp_around_handle = RewTerm(func=mdp.align_grasp_around_handle, weight=0.125) + grasp_handle = RewTerm( + func=mdp.grasp_handle, + weight=0.5, + params={ + "threshold": 0.03, + "open_joint_pos": MISSING, + "asset_cfg": SceneEntityCfg("robot", joint_names=MISSING), + }, + ) + + # 3. Open the drawer + open_drawer_bonus = RewTerm( + func=mdp.open_drawer_bonus, + weight=7.5, + params={"asset_cfg": SceneEntityCfg("cabinet", joint_names=["drawer_bottom_joint"])}, + ) + multi_stage_open_drawer = RewTerm( + func=mdp.multi_stage_open_drawer, + weight=1.0, + params={"asset_cfg": SceneEntityCfg("cabinet", joint_names=["drawer_bottom_joint"])}, + ) + + # 4. Penalize actions for cosmetic reasons + action_rate_l2 = RewTerm(func=mdp.action_rate_l2, weight=-1e-2) + joint_vel = RewTerm(func=mdp.joint_vel_l2, weight=-0.0001) + + +@configclass +class TerminationsCfg: + """Termination terms for the MDP.""" + + time_out = DoneTerm(func=mdp.time_out, time_out=True) + + +## +# Environment configuration +## + + +@configclass +class CabinetEnvCfg(ManagerBasedRLEnvCfg): + """Configuration for the cabinet environment.""" + + # Scene settings + scene: CabinetSceneCfg = CabinetSceneCfg(num_envs=4096, env_spacing=2.0) + # Basic settings + observations: ObservationsCfg = ObservationsCfg() + actions: ActionsCfg = ActionsCfg() + # MDP settings + rewards: RewardsCfg = RewardsCfg() + terminations: TerminationsCfg = TerminationsCfg() + events: EventCfg = EventCfg() + + def __post_init__(self): + """Post initialization.""" + # general settings + self.decimation = 1 + self.episode_length_s = 8.0 + self.viewer.eye = (-2.0, 2.0, 2.0) + self.viewer.lookat = (0.8, 0.0, 0.5) + # simulation settings + self.sim.dt = 1 / 60 # 60Hz + self.sim.render_interval = self.decimation + self.sim.physx.bounce_threshold_velocity = 0.01 + self.sim.physx.friction_correlation_distance = 0.00625 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py new file mode 100644 index 00000000000..e6d5a0c31cc --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py @@ -0,0 +1,40 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +import gymnasium as gym + +from . import agents + +## +# Register Gym environments. +## + +## +# Joint Position Control +## + +gym.register( + id="Isaac-Open-Drawer-OpenArm-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCabinetEnvCfg", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmCabinetPPORunnerCfg", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + }, + disable_env_checker=True, +) + +gym.register( + id="Isaac-Open-Drawer-OpenArm-Play-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCabinetEnvCfg_PLAY", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmCabinetPPORunnerCfg", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + }, + disable_env_checker=True, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/__init__.py similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/__init__.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/__init__.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rl_games_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rl_games_ppo_cfg.yaml new file mode 100644 index 00000000000..85b8a40d5be --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rl_games_ppo_cfg.yaml @@ -0,0 +1,81 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +params: + seed: 42 + + # environment wrapper clipping + env: + clip_observations: 5.0 + clip_actions: 1.0 + + algo: + name: a2c_continuous + + model: + name: continuous_a2c_logstd + + network: + name: actor_critic + separate: False + + space: + continuous: + mu_activation: None + sigma_activation: None + mu_init: + name: default + sigma_init: + name: const_initializer + val: 0 + fixed_sigma: True + mlp: + units: [256, 128, 64] + activation: elu + d2rl: False + + initializer: + name: default + regularizer: + name: None + + load_checkpoint: False + load_path: '' + + config: + name: openarm_open_drawer + env_name: rlgpu + device: 'cuda:0' + device_name: 'cuda:0' + multi_gpu: False + ppo: True + mixed_precision: False + normalize_input: False + normalize_value: False + num_actors: -1 # configured from the script (based on num_envs) + reward_shaper: + scale_value: 1 + normalize_advantage: False + gamma: 0.99 + tau: 0.95 + learning_rate: 5e-4 + lr_schedule: adaptive + kl_threshold: 0.008 + score_to_win: 200 + max_epochs: 400 + save_best_after: 50 + save_frequency: 50 + print_stats: True + grad_norm: 1.0 + entropy_coef: 0.001 + truncate_grads: True + e_clip: 0.2 + horizon_length: 96 + minibatch_size: 4096 + mini_epochs: 5 + critic_coef: 4 + clip_value: True + seq_length: 4 + bounds_loss_coef: 0.0001 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rsl_rl_ppo_cfg.py new file mode 100644 index 00000000000..b6d7a5ce6d5 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/rsl_rl_ppo_cfg.py @@ -0,0 +1,37 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab.utils import configclass + +from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg + + +@configclass +class OpenArmCabinetPPORunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 96 + max_iterations = 600 + save_interval = 50 + experiment_name = "openarm_open_drawer" + empirical_normalization = False + policy = RslRlPpoActorCriticCfg( + init_noise_std=1.0, + actor_hidden_dims=[256, 128, 64], + critic_hidden_dims=[256, 128, 64], + activation="elu", + ) + algorithm = RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=1e-3, + num_learning_epochs=5, + num_mini_batches=4, + learning_rate=5.0e-4, + schedule="adaptive", + gamma=0.99, + lam=0.95, + desired_kl=0.02, + max_grad_norm=1.0, + ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml new file mode 100644 index 00000000000..7af74961593 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml @@ -0,0 +1,85 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +seed: 42 + + +# Models are instantiated using skrl's model instantiator utility +# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html +models: + separate: False + policy: # see gaussian_model parameters + class: GaussianMixin + clip_actions: False + clip_log_std: True + min_log_std: -20.0 + max_log_std: 2.0 + initial_log_std: 0.0 + network: + - name: net + input: STATES + layers: [256, 128, 64] + activations: elu + output: ACTIONS + value: # see deterministic_model parameters + class: DeterministicMixin + clip_actions: False + network: + - name: net + input: STATES + layers: [256, 128, 64] + activations: elu + output: ONE + + +# Rollout memory +# https://skrl.readthedocs.io/en/latest/api/memories/random.html +memory: + class: RandomMemory + memory_size: -1 # automatically determined (same as agent:rollouts) + + +# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) +# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html +agent: + class: PPO + rollouts: 96 + learning_epochs: 5 + mini_batches: 96 + discount_factor: 0.99 + lambda: 0.95 + learning_rate: 5.0e-04 + learning_rate_scheduler: KLAdaptiveLR + learning_rate_scheduler_kwargs: + kl_threshold: 0.008 + state_preprocessor: null + state_preprocessor_kwargs: null + value_preprocessor: null + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 + value_clip: 0.2 + clip_predicted_values: True + entropy_loss_scale: 0.001 + value_loss_scale: 2.0 + kl_threshold: 0.0 + rewards_shaper_scale: 1 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "openarm_open_drawer" + experiment_name: "" + write_interval: auto + checkpoint_interval: auto + + +# Sequential trainer +# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html +trainer: + class: SequentialTrainer + timesteps: 38400 + environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py new file mode 100644 index 00000000000..a7832a5cd8f --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py @@ -0,0 +1,93 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab.sensors import FrameTransformerCfg +from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg +from isaaclab.utils import configclass + +from isaaclab_tasks.manager_based.manipulation.cabinet import mdp + +from isaaclab_tasks.manager_based.manipulation.cabinet.cabinet_openarm_env_cfg import ( # isort: skip + FRAME_MARKER_SMALL_CFG, + CabinetEnvCfg, +) + +## +# Pre-defined configs +## +from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG + + +@configclass +class OpenArmCabinetEnvCfg(CabinetEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + + # Set OpenArm as robot + self.scene.robot = OPENARM_UNI_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot") + + # Set Actions for the specific robot type (OpenArm) + self.actions.arm_action = mdp.JointPositionActionCfg( + asset_name="robot", + joint_names=["openarm_joint.*"], + scale=1.0, + use_default_offset=True, + ) + self.actions.gripper_action = mdp.BinaryJointPositionActionCfg( + asset_name="robot", + joint_names=["openarm_finger_joint.*"], + open_command_expr={"openarm_finger_joint.*": 0.044}, + close_command_expr={"openarm_finger_joint.*": 0.0}, + ) + + # Listens to the required transforms + # IMPORTANT: The order of the frames in the list is important. The first frame is the tool center point (TCP) + # the other frames are the fingers + self.scene.ee_frame = FrameTransformerCfg( + prim_path="{ENV_REGEX_NS}/Robot/openarm_link0", + visualizer_cfg=FRAME_MARKER_SMALL_CFG.replace(prim_path="/Visuals/EndEffectorFrameTransformer"), + debug_vis=False, + target_frames=[ + FrameTransformerCfg.FrameCfg( + prim_path="{ENV_REGEX_NS}/Robot/openarm_ee_tcp", + name="ee_tcp", + offset=OffsetCfg( + pos=(0.0, 0.0, -0.003), + ), + ), + FrameTransformerCfg.FrameCfg( + prim_path="{ENV_REGEX_NS}/Robot/openarm_left_finger", + name="tool_leftfinger", + offset=OffsetCfg( + pos=(0.0, -0.005, 0.075), + ), + ), + FrameTransformerCfg.FrameCfg( + prim_path="{ENV_REGEX_NS}/Robot/openarm_right_finger", + name="tool_rightfinger", + offset=OffsetCfg( + pos=(0.0, 0.005, 0.075), + ), + ), + ], + ) + + # override rewards + self.rewards.approach_gripper_handle.params["offset"] = 0.04 + self.rewards.grasp_handle.params["open_joint_pos"] = 0.044 + self.rewards.grasp_handle.params["asset_cfg"].joint_names = ["openarm_finger_joint.*"] + + +@configclass +class OpenArmCabinetEnvCfg_PLAY(OpenArmCabinetEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + # make a smaller scene for play + self.scene.num_envs = 50 + self.scene.env_spacing = 2.5 + # disable randomization for play + self.observations.policy.enable_corruption = False diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py index 858fc4ec273..25c2447a7a9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py @@ -12,7 +12,7 @@ from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab_tasks.manager_based.manipulation.lift import mdp -from isaaclab_tasks.manager_based.manipulation.lift.lift_openarm_uni_env_cfg import ( +from isaaclab_tasks.manager_based.manipulation.lift.lift_openarm_env_cfg import ( LiftEnvCfg, ) @@ -22,7 +22,7 @@ # Pre-defined configs ## from isaaclab.markers.config import FRAME_MARKER_CFG # isort: skip -from source.openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_UNI_CFG +from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG @configclass diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_uni_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/__init__.py similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/__init__.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/__init__.py new file mode 100644 index 00000000000..2e924fbf1b1 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rl_games_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rl_games_ppo_cfg.yaml similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rl_games_ppo_cfg.yaml rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rl_games_ppo_cfg.yaml diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rsl_rl_ppo_cfg.py similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/rsl_rl_ppo_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rsl_rl_ppo_cfg.py diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/skrl_ppo_cfg.yaml similarity index 100% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/agents/skrl_ppo_cfg.yaml rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/skrl_ppo_cfg.yaml diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py similarity index 96% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py index f4f90769468..6ae7e1ee76e 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py @@ -13,7 +13,7 @@ ## # Pre-defined configs ## -from source.openarm.openarm.tasks.manager_based.openarm_manipulation.assets.openarm import OPENARM_BI_HIGH_PD_CFG +from isaaclab_assets.robots.openarm import OPENARM_BI_HIGH_PD_CFG ## # Environment configuration diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py new file mode 100644 index 00000000000..32998d7910b --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py @@ -0,0 +1,33 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +import gymnasium as gym + +from . import agents + +gym.register( + id="Isaac-Reach-OpenArm-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmReachEnvCfg", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmReachPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + }, +) + +gym.register( + id="Isaac-Reach-OpenArm-Play-v0", + entry_point="isaaclab.envs:ManagerBasedRLEnv", + disable_env_checker=True, + kwargs={ + "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmReachEnvCfg_PLAY", + "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", + "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmReachPPORunnerCfg", + "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", + }, +) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/__init__.py new file mode 100644 index 00000000000..2e924fbf1b1 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rl_games_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rl_games_ppo_cfg.yaml new file mode 100644 index 00000000000..749310c3e02 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rl_games_ppo_cfg.yaml @@ -0,0 +1,84 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +params: + seed: 42 + + # environment wrapper clipping + env: + clip_observations: 100.0 + clip_actions: 100.0 + + algo: + name: a2c_continuous + + model: + name: continuous_a2c_logstd + + network: + name: actor_critic + separate: False + space: + continuous: + mu_activation: None + sigma_activation: None + + mu_init: + name: default + sigma_init: + name: const_initializer + val: 0 + fixed_sigma: True + mlp: + units: [64, 64] + activation: elu + d2rl: False + + initializer: + name: default + regularizer: + name: None + + load_checkpoint: False # flag which sets whether to load the checkpoint + load_path: '' # path to the checkpoint to load + + config: + name: openarm_reach + env_name: rlgpu + device: 'cuda:0' + device_name: 'cuda:0' + multi_gpu: False + ppo: True + mixed_precision: False + normalize_input: True + normalize_value: True + value_bootstrap: True + num_actors: -1 + reward_shaper: + scale_value: 1.0 + normalize_advantage: True + gamma: 0.99 + tau: 0.95 + learning_rate: 1e-3 + lr_schedule: adaptive + schedule_type: legacy + kl_threshold: 0.01 + score_to_win: 10000 + max_epochs: 1000 + save_best_after: 200 + save_frequency: 100 + print_stats: True + grad_norm: 1.0 + entropy_coef: 0.01 + truncate_grads: True + e_clip: 0.2 + horizon_length: 24 + minibatch_size: 24576 + mini_epochs: 5 + critic_coef: 2 + clip_value: True + clip_actions: False + bounds_loss_coef: 0.0001 diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py new file mode 100644 index 00000000000..4a1e9f3cbac --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py @@ -0,0 +1,40 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + + +from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg + +from isaaclab.utils import configclass + + +@configclass +class OpenArmReachPPORunnerCfg(RslRlOnPolicyRunnerCfg): + num_steps_per_env = 24 + max_iterations = 1000 + save_interval = 50 + experiment_name = "openarm_reach" + run_name = "" + resume = False + empirical_normalization = True + policy = RslRlPpoActorCriticCfg( + init_noise_std=1.0, + actor_hidden_dims=[64, 64], + critic_hidden_dims=[64, 64], + activation="elu", + ) + algorithm = RslRlPpoAlgorithmCfg( + value_loss_coef=1.0, + use_clipped_value_loss=True, + clip_param=0.2, + entropy_coef=0.001, + num_learning_epochs=8, + num_mini_batches=4, + learning_rate=1.0e-2, + 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/manipulation/reach/config/openarm/unimanual/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/skrl_ppo_cfg.yaml new file mode 100644 index 00000000000..5cebf2eba2d --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/skrl_ppo_cfg.yaml @@ -0,0 +1,85 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +seed: 42 + + +# Models are instantiated using skrl's model instantiator utility +# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html +models: + separate: False + policy: # see gaussian_model parameters + class: GaussianMixin + clip_actions: False + clip_log_std: True + min_log_std: -20.0 + max_log_std: 2.0 + initial_log_std: 0.0 + network: + - name: net + input: STATES + layers: [64, 64] + activations: elu + output: ACTIONS + value: # see deterministic_model parameters + class: DeterministicMixin + clip_actions: False + network: + - name: net + input: STATES + layers: [64, 64] + activations: elu + output: ONE + + +# Rollout memory +# https://skrl.readthedocs.io/en/latest/api/memories/random.html +memory: + class: RandomMemory + memory_size: -1 # automatically determined (same as agent:rollouts) + + +# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) +# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html +agent: + class: PPO + rollouts: 24 + learning_epochs: 5 + mini_batches: 4 + discount_factor: 0.99 + lambda: 0.95 + learning_rate: 1.0e-03 + learning_rate_scheduler: KLAdaptiveLR + learning_rate_scheduler_kwargs: + kl_threshold: 0.01 + state_preprocessor: RunningStandardScaler + state_preprocessor_kwargs: null + value_preprocessor: RunningStandardScaler + value_preprocessor_kwargs: null + random_timesteps: 0 + learning_starts: 0 + grad_norm_clip: 1.0 + ratio_clip: 0.2 + value_clip: 0.2 + clip_predicted_values: True + entropy_loss_scale: 0.01 + value_loss_scale: 1.0 + kl_threshold: 0.0 + rewards_shaper_scale: 1.0 + time_limit_bootstrap: False + # logging and checkpoint + experiment: + directory: "openarm_reach" + experiment_name: "" + write_interval: auto + checkpoint_interval: auto + + +# Sequential trainer +# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html +trainer: + class: SequentialTrainer + timesteps: 24000 + environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py new file mode 100644 index 00000000000..961cd059312 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py @@ -0,0 +1,77 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause + +from isaaclab.utils import configclass + +import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp +from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_uni_env_cfg import ( + ReachEnvCfg, +) + +## +# Pre-defined configs +## +from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG +from isaaclab.assets.articulation import ArticulationCfg + +## +# Environment configuration +## + + +@configclass +class OpenArmReachEnvCfg(ReachEnvCfg): + + def __post_init__(self): + # post init of parent + super().__post_init__() + + # switch robot to OpenArm + self.scene.robot = OPENARM_UNI_CFG.replace( + prim_path="{ENV_REGEX_NS}/Robot", + init_state=ArticulationCfg.InitialStateCfg( + joint_pos={ + "openarm_joint1": 1.57, + "openarm_joint2": 0.0, + "openarm_joint3": -1.57, + "openarm_joint4": 1.57, + "openarm_joint5": 0.0, + "openarm_joint6": 0.0, + "openarm_joint7": 0.0, + "openarm_finger_joint.*": 0.0, + }, # Close the gripper + ), + ) + + # override rewards + self.rewards.end_effector_position_tracking.params["asset_cfg"].body_names = ["openarm_hand"] + self.rewards.end_effector_position_tracking_fine_grained.params["asset_cfg"].body_names = ["openarm_hand"] + self.rewards.end_effector_orientation_tracking.params["asset_cfg"].body_names = ["openarm_hand"] + + # override actions + self.actions.arm_action = mdp.JointPositionActionCfg( + asset_name="robot", + joint_names=[ + "openarm_joint.*", + ], + scale=0.5, + use_default_offset=True, + ) + + # override command generator body + # end-effector is along z-direction + self.commands.ee_pose.body_name = "openarm_hand" + + +@configclass +class OpenArmReachEnvCfg_PLAY(OpenArmReachEnvCfg): + def __post_init__(self): + # post init of parent + super().__post_init__() + # make a smaller scene for play + self.scene.num_envs = 50 + self.scene.env_spacing = 2.5 + # disable randomization for play + self.observations.policy.enable_corruption = False diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py new file mode 100644 index 00000000000..e4fe67cee4b --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py @@ -0,0 +1,273 @@ +# Copyright 2025 Enactic, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import MISSING + +import isaaclab.sim as sim_utils +from isaaclab.actuators import ImplicitActuatorCfg +from isaaclab.assets.articulation import ArticulationCfg +from isaaclab.assets import ArticulationCfg, AssetBaseCfg +from isaaclab.envs import ManagerBasedRLEnvCfg +from isaaclab.managers import ActionTermCfg as ActionTerm +from isaaclab.managers import CurriculumTermCfg as CurrTerm +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.scene import InteractiveSceneCfg +from isaaclab.utils import configclass +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR +from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise + +from . import mdp + +import math + +## +# Scene definition +## + + +@configclass +class ReachSceneCfg(InteractiveSceneCfg): + """Configuration for the scene with a robotic arm.""" + + # world + ground = AssetBaseCfg( + prim_path="/World/ground", + spawn=sim_utils.GroundPlaneCfg(), + init_state=AssetBaseCfg.InitialStateCfg(pos=(0.0, 0.0, -1.05)), + ) + + table = AssetBaseCfg( + prim_path="{ENV_REGEX_NS}/Table", + spawn=sim_utils.UsdFileCfg( + usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd", + ), + init_state=AssetBaseCfg.InitialStateCfg( + pos=(0.55, 0.0, 0.0), rot=(0.70711, 0.0, 0.0, 0.70711) + ), + ) + + # robots + robot: ArticulationCfg = MISSING + + # lights + light = AssetBaseCfg( + prim_path="/World/light", + spawn=sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=2500.0), + ) + + +## +# MDP settings +## + + +@configclass +class CommandsCfg: + """Command terms for the MDP.""" + + ee_pose = mdp.UniformPoseCommandCfg( + asset_name="robot", + body_name=MISSING, + resampling_time_range=(4.0, 4.0), + debug_vis=True, + ranges=mdp.UniformPoseCommandCfg.Ranges( + pos_x=(0.25, 0.35), + pos_y=(-0.2, 0.2), + pos_z=(0.3, 0.4), + roll=(-math.pi / 6, math.pi / 6), + pitch=(math.pi / 2, math.pi / 2), + yaw=(-math.pi / 9, math.pi / 9), + ), + ) + + +@configclass +class ActionsCfg: + """Action specifications for the MDP.""" + + arm_action: ActionTerm = MISSING + gripper_action: ActionTerm | None = None + + +@configclass +class ObservationsCfg: + """Observation specifications for the MDP.""" + + @configclass + class PolicyCfg(ObsGroup): + """Observations for policy group.""" + + # observation terms (order preserved) + joint_pos = ObsTerm( + func=mdp.joint_pos_rel, + params={ + "asset_cfg": SceneEntityCfg("robot", joint_names=[ + "openarm_joint1", + "openarm_joint2", + "openarm_joint3", + "openarm_joint4", + "openarm_joint5", + "openarm_joint6", + "openarm_joint7", + ]) + }, + noise=Unoise(n_min=-0.01, n_max=0.01), + ) + joint_vel = ObsTerm( + func=mdp.joint_vel_rel, + params={ + "asset_cfg": SceneEntityCfg("robot", joint_names=[ + "openarm_joint1", + "openarm_joint2", + "openarm_joint3", + "openarm_joint4", + "openarm_joint5", + "openarm_joint6", + "openarm_joint7", + ]) + }, + noise=Unoise(n_min=-0.01, n_max=0.01), + ) + pose_command = ObsTerm( + func=mdp.generated_commands, params={"command_name": "ee_pose"} + ) + actions = ObsTerm(func=mdp.last_action) + + def __post_init__(self): + self.enable_corruption = True + self.concatenate_terms = True + + # observation groups + policy: PolicyCfg = PolicyCfg() + + +@configclass +class EventCfg: + """Configuration for events.""" + + reset_robot_joints = EventTerm( + func=mdp.reset_joints_by_scale, + mode="reset", + params={ + "position_range": (0.5, 1.5), + "velocity_range": (0.0, 0.0), + }, + ) + + +@configclass +class RewardsCfg: + """Reward terms for the MDP.""" + + # task terms + end_effector_position_tracking = RewTerm( + func=mdp.position_command_error, + weight=-0.2, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "command_name": "ee_pose", + }, + ) + end_effector_position_tracking_fine_grained = RewTerm( + func=mdp.position_command_error_tanh, + weight=0.1, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "std": 0.1, + "command_name": "ee_pose", + }, + ) + end_effector_orientation_tracking = RewTerm( + func=mdp.orientation_command_error, + weight=-0.1, + params={ + "asset_cfg": SceneEntityCfg("robot", body_names=MISSING), + "command_name": "ee_pose", + }, + ) + + # action penalty + action_rate = RewTerm(func=mdp.action_rate_l2, weight=-0.0001) + joint_vel = RewTerm( + func=mdp.joint_vel_l2, + weight=-0.0001, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=[ + "openarm_joint1", + "openarm_joint2", + "openarm_joint3", + "openarm_joint4", + "openarm_joint5", + "openarm_joint6", + "openarm_joint7", + ])}, + ) + + +@configclass +class TerminationsCfg: + """Termination terms for the MDP.""" + + time_out = DoneTerm(func=mdp.time_out, time_out=True) + + +@configclass +class CurriculumCfg: + """Curriculum terms for the MDP.""" + + action_rate = CurrTerm( + func=mdp.modify_reward_weight, + params={"term_name": "action_rate", "weight": -0.005, "num_steps": 4500}, + ) + + joint_vel = CurrTerm( + func=mdp.modify_reward_weight, + params={"term_name": "joint_vel", "weight": -0.001, "num_steps": 4500}, + ) + + +## +# Environment configuration +## + + +@configclass +class ReachEnvCfg(ManagerBasedRLEnvCfg): + """Configuration for the reach end-effector pose tracking environment.""" + + # Scene settings + scene: ReachSceneCfg = ReachSceneCfg(num_envs=4096, env_spacing=2.5) + # Basic settings + observations: ObservationsCfg = ObservationsCfg() + actions: ActionsCfg = ActionsCfg() + commands: CommandsCfg = CommandsCfg() + # MDP settings + rewards: RewardsCfg = RewardsCfg() + terminations: TerminationsCfg = TerminationsCfg() + events: EventCfg = EventCfg() + curriculum: CurriculumCfg = CurriculumCfg() + + def __post_init__(self): + """Post initialization.""" + # general settings + self.decimation = 2 + self.sim.render_interval = self.decimation + self.episode_length_s = 12.0 + self.viewer.eye = (3.5, 3.5, 3.5) + # simulation settings + self.sim.dt = 1.0 / 60.0 From dd63da62b19e78221b581913d42e7a556d6345f8 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 10:56:05 +0900 Subject: [PATCH 07/32] Fixed bug --- .../manipulation/cabinet/cabinet_openarm_env_cfg.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py index 953535d9280..740b95a586f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py @@ -208,7 +208,7 @@ class RewardsCfg: align_ee_handle = RewTerm(func=mdp.align_ee_handle, weight=0.5) # 2. Grasp the handle - approach_gripper_handle = RewTerm(func=mdp.align_grasp_around_handle, weight=5.0, params={"offset": MISSING}) + approach_gripper_handle = RewTerm(func=mdp.approach_gripper_handle, weight=5.0, params={"offset": MISSING}) align_grasp_around_handle = RewTerm(func=mdp.align_grasp_around_handle, weight=0.125) grasp_handle = RewTerm( func=mdp.grasp_handle, From b647491fb9bd57e7e4ecd52fbd1c8d63acf8938d Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 11:53:55 +0900 Subject: [PATCH 08/32] Fixed bugs --- source/isaaclab_assets/isaaclab_assets/robots/openarm.py | 2 +- .../manipulation/reach/config/openarm/__init__.py | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) create mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index 3a37c57f409..acbafc3c4a6 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -14,7 +14,7 @@ Reference: https://github.com/enactic/openarm_isaac_lab -Please `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab/source` to use these configurations. +Please `git clone https://github.com/enactic/openarm_isaac_lab` and `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab` to use these configurations. """ import isaaclab.sim as sim_utils diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py new file mode 100644 index 00000000000..2e924fbf1b1 --- /dev/null +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: BSD-3-Clause From 94d6aabe23103e0df608d744530f51ccd8c97518 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 12:45:11 +0900 Subject: [PATCH 09/32] Updated changelog --- source/isaaclab_assets/docs/CHANGELOG.rst | 8 ++++++++ source/isaaclab_tasks/docs/CHANGELOG.rst | 19 +++++++++++++++++++ 2 files changed, 27 insertions(+) diff --git a/source/isaaclab_assets/docs/CHANGELOG.rst b/source/isaaclab_assets/docs/CHANGELOG.rst index b6582e77e8a..3456213b3e8 100644 --- a/source/isaaclab_assets/docs/CHANGELOG.rst +++ b/source/isaaclab_assets/docs/CHANGELOG.rst @@ -1,6 +1,14 @@ Changelog --------- +0.2.4 (2025-11-26) +~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Configuration for OpenArm robots used for manipulation tasks. + 0.2.3 (2025-08-11) ~~~~~~~~~~~~~~~~~~ diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 518c3a02541..7da42aaea24 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -1,6 +1,25 @@ Changelog --------- +0.11.10 (2025-11-26) +~~~~~~~~~~~~~~~~~~~ + +Added +^^^^^ + +* Added reaching task environments for OpenArm unimanual robot: + * :class:`OpenArmReachEnvCfg`; Gym ID ``Isaac-Reach-OpenArm-v0``. + * :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``OpenArmReachEnvCfg_PLAY``. +* Added lifting a cube task environments for OpenArm unimanual robot: + * :class:`OpenArmCubeLiftEnvCfg`; Gym ID ``Isaac-Lift-Cube-OpenArm-v0``. + * :class:`OpenArmCubeLiftEnvCfg_PLAY`; Gym ID ``Isaac-Lift-Cube-OpenArm-Play-v0``. +* Added opening a drawer task environments for OpenArm unimanual robot: + * :class:`OpenArmCabinetEnvCfg`; Gym ID ``Isaac-Open-Drawer-OpenArm-v0``. + * :class:`OpenArmCabinetEnvCfg_PLAY`; Gym ID ``Isaac-Open-Drawer-OpenArm-Play-v0``. +* Added reaching task environments for OpenArm bimanual robot: + * :class:`OpenArmReachEnvCfg`; Gym ID ``Isaac-Reach-OpenArm-Bi-v0``. + * :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``Isaac-Reach-OpenArm-Bi-Play-v0``. + 0.11.9 (2025-11-10) ~~~~~~~~~~~~~~~~~~~ From 66e17433bdadd4f95cfdced839ad8085c640ec94 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 12:46:39 +0900 Subject: [PATCH 10/32] updated init --- .../reach/config/openarm/unimanual/__init__.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py index 32998d7910b..149847c9828 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/__init__.py @@ -3,11 +3,18 @@ # # SPDX-License-Identifier: BSD-3-Clause - import gymnasium as gym from . import agents +## +# Register Gym environments. +## + +## +# Joint Position Control +## + gym.register( id="Isaac-Reach-OpenArm-v0", entry_point="isaaclab.envs:ManagerBasedRLEnv", From 0d51e76484d421ccce0dc4711021848d493020b2 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 12:50:43 +0900 Subject: [PATCH 11/32] updated license --- .../reach/reach_openarm_uni_env_cfg.py | 17 ++++------------- 1 file changed, 4 insertions(+), 13 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py index e4fe67cee4b..638ef821161 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py @@ -1,16 +1,7 @@ -# Copyright 2025 Enactic, Inc. +# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). +# All rights reserved. # -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. +# SPDX-License-Identifier: BSD-3-Clause from dataclasses import MISSING @@ -32,7 +23,7 @@ from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise -from . import mdp +import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp import math From 8c45882da5b72a2688ebe107203f5040143940ac Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 13:18:28 +0900 Subject: [PATCH 12/32] updated contributors --- CONTRIBUTORS.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CONTRIBUTORS.md b/CONTRIBUTORS.md index 9a7f43604fa..27ee9dc344b 100644 --- a/CONTRIBUTORS.md +++ b/CONTRIBUTORS.md @@ -85,6 +85,7 @@ Guidelines for modifications: * Jinghuan Shang * Jingzhou Liu * Jinqi Wei +* Jinyeob Kim * Johnson Sun * Kaixi Bao * Kris Wilson From a9ab009c40ca905f7b801baef093ec1db93be152 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 13:20:28 +0900 Subject: [PATCH 13/32] updated extension.toml --- source/isaaclab_assets/config/extension.toml | 2 +- source/isaaclab_tasks/config/extension.toml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/source/isaaclab_assets/config/extension.toml b/source/isaaclab_assets/config/extension.toml index dac5494087e..3f682d93335 100644 --- a/source/isaaclab_assets/config/extension.toml +++ b/source/isaaclab_assets/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "0.2.3" +version = "0.2.4" # Description title = "Isaac Lab Assets" diff --git a/source/isaaclab_tasks/config/extension.toml b/source/isaaclab_tasks/config/extension.toml index ef079ce9112..5d1e4c5ef27 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.11.9" +version = "0.11.10" # Description title = "Isaac Lab Environments" From 7681c6b4c3cd0032f91cdd6d23b76f0935970b96 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 14:18:12 +0900 Subject: [PATCH 14/32] updated environments.rst and added image files --- .../tasks/manipulation/openarm_bi_reach.jpg | Bin 0 -> 39488 bytes .../tasks/manipulation/openarm_uni_lift.jpg | Bin 0 -> 40923 bytes .../manipulation/openarm_uni_open_drawer.jpg | Bin 0 -> 41076 bytes .../tasks/manipulation/openarm_uni_reach.jpg | Bin 0 -> 40019 bytes docs/source/overview/environments.rst | 16 ++++++++++++++++ 5 files changed, 16 insertions(+) create mode 100644 docs/source/_static/tasks/manipulation/openarm_bi_reach.jpg create mode 100644 docs/source/_static/tasks/manipulation/openarm_uni_lift.jpg create mode 100644 docs/source/_static/tasks/manipulation/openarm_uni_open_drawer.jpg create mode 100644 docs/source/_static/tasks/manipulation/openarm_uni_reach.jpg diff --git a/docs/source/_static/tasks/manipulation/openarm_bi_reach.jpg b/docs/source/_static/tasks/manipulation/openarm_bi_reach.jpg new file mode 100644 index 0000000000000000000000000000000000000000..12e6620027d6d301c2b17203fd9fc10f981976b3 GIT binary patch literal 39488 zcmc$_byQp3^EVm_Bos@aP@IH93#Eku#fqm;tVnQ*l;UoM;2tPeqy>sYTHM{;Tio4> zySu)5p6`9v{pa34-tX_Obth|`b#l&@*|TT%`ONIu_mlUF0En!lj3fXH3jn~v`~dee z0C52JgMa9sD>jC3fH?mU9uSBNe29mS{}AutLwrIoAwB^y!NZ3{Bt*nu2!sTJPe}TR z6!Hjj5BaANtbb}^JF{bDLyX${Bz~lt^fcMECx=v{rxn65c^*qNC2XMTMn`R zUkTo6Kox=4#(GMjA*Q<4>9-`L4;&e>!oCM6shk>Pk61lm?q~JNN4r`3cyIl4L%16| zaNTncP)7*!Hout_Jv9cg83uh=QuSEsuCpjJkX$?um*&I!|A=sWYs7HqLjF}hqQV!> zYm~-gi!f?#okL-?8LD+#PiH)PYs{i%z@D8co(bL7Z?WI$yG|Z41EUG4vyTSz=kmIW zZEt%{!KVcTJ1l3GM|X8qPc_(HI+(sSkQzjdBmNJS@c+5E_5S`&ah<^A7X}A~`DxVq zE!FG|OR+UsaO!bYw9RXG2MyxiKgf0q65e~jOt0F3$~J6D z6)73W%~hue5$den6W-wABs6IwY~AAwO=#+{&Pk}Co%2+hnntCoZf>V-8DS$`j5}(z zQ~J)QKomhIJu$Dn=-ho5ZR)HS2z1uQ)2WF>*yQ}ASm2|pI4s-?>S=mJnZxs+FGO1I z0glvi4Ln9%bA5KCF7uP1;uaR3?1p`F9%xDA$&dy%;ji8 z=i?@-_UFoZ8at{k4bJCX4D+atGG@i8l%os_DzD^<7}$IBF`{i+iT!P{nHrF?vy3NW zW0BU*rVHIUn>ELRBW#DCPhn~upYbn+)>654b#`-CmqX%pq`SzwP3BkYb>=1R1^b%w ztd+>1ZJK$J4d)0e*ly7O#3)28j{*mF+wCoClwu3gzWikp*dO;*Zz61~OTZhcM0hMj zoU{b!6MMd7_o?1G*-qI5LLZLa{1#9fP@K%kmKTVVwtW`w=fCy z2Y?af*Xii}$~Rs39h)k|%jMMta_U(M<=mtCq_o4r8ty!_gKnvBV<{V6$f>WW-Q-%G_s!B<_Q_m3H$|{orz#g^!2Os z?HQ93y)f0X0{N2}%Q3&MLx77FY)N|6|5ezolJ?}MMdl@b9xEaw;a7KsNbxZ$?8_kdI2QVg%kCqo<{`VTHO z?BJ`JC}A&uMX;lt&L|tGq?zB7MGz|K61urQi-Vt#cx`R^%>}fH@MInl?h7r=&|)vL zU4NM;%~M#=dO*L}N7E0V+(4}sF%r5R{rK2RHf6V0+4k5xQ}KDGNN!r(rsO@~QB^-r zu7O4sWkx4#NPRkrS{LCbO-Mv7#u!aJN>4W&_}+O+gTzZ4X{x<2h;n#~G8$qxW7Bsp zkK@t@#ppWLMa+tR708RQejgik3_&5kI8McLT=}kL*wA-sI1g^(2`8rMvCvr7OOCG( z=o$xWR|~}GQeV=|@Y8>CkM#0$bWXM^+taA%Du62H+imSVFCNfPwGkrrcZQ%!(XjuT zW|sJ(i?<09ulgS(S1^y+GmB9_6nzWsCQi6AF9=$89@q3#(rU2SFZi(1qph^Z&U99* zFdOL-GtTH7G|E$C!>Z=Gb}aJu4>0I;V-Sn`W?e{PkMt-+A2d!c@4`+#O!3Zn(&TfR z)>Ta53$-5=?@W0siaJzY%P&~w#7!eS$)h;r1esSuUsePfP-r+>B`i))*qG;E+S@O& z0Ui||pjN*^AqDq<@VTc8$~olEwI}}Ct-PBn_rw#)>i)3R=yrst?I*YHC~0SZQBmGj z{WHIQt0j)+V4y;d9!u*2(9&@(8)382IjX&Kt(A#gn6$Ot6tsB^Kvmdt(+%?bo4v(B zk8DlS>O504XW_y2hb4(u;4V?a4pU+`2naiSI`OPmn@EHUZ35T)X+*;In=aM?v6ky+ zje8Z@f<=lAu-U;QpW=;!>2jq!OT%FN)q4O7GF;zC$}Bzx6z2+^JKz%>iXv*yu6BP1 zzYB>#@7eTeP>7j_)5CZeOP&3psdvgel>PB#OtsXkO7={54-&vsO#`kf;GD5pL$ai^ zy=k%fdqDJC0^`)u6h?&7&#%LVb7dBO14%*f{?ckIwe$t{uCN?Ddtpv<5PTP44&zQw~O zT6=i6%c-<57j7m>U%>fDFMO%NoISRoUu4)Aq}1!lu2h!2E!Skzy$_`On0|nLo|YOh zjLI3^l;Rip>C%)rsQAbFan~R!uH{O)(p!qLevIHei+aZ{NU9U#^dsN;W_r^!6oMSrL6T=S^x^z*bBJkS zJ^3ev#v)q9W{L&>$R`Qc!8PmNP~?21m%aQ0OeagG#z+ivle!YNx0Zz6I92R6Wxab;~-qP{ zs0x2|3BH9bxDf{qc?npo&(^nIF1K6LH2qCLjo)N(;dW%n)tF{9ec27ezm+7k`gB@g zXP*rfgcvZu560DxeES;6mnr9jO0)(?8tWalN2)VAX*JiSI3!n@QgVJ8UJ(=8#b(83P{rI8eQX5`a0M$apZgaz`$`Xb4AX%S=8)jkc>;9Wc)hLK%8ii z97sBd{aCWQV?sw$0-7M_gFNi&}8dQkK%sKF-CrL`(mI zyZ`0__Gy|v4%7KNN3%l1iu^cD!9Uj_8%F%4x->A4G0C0``hzO)^(-xm=FBJ?AGHt) zgesdxWntFGwbC=kzA3Hbjz*n6%1R2!9lKeT()yft6;g&MJmNF-cvf6t(z0?xpKOtR ztZ;uUloScyrI)9?-d+gafY+Gh_bnaLOb4Ta>nx_)eMx6J$TW-Rwj zKP_JYOlAcO-;MpF^m%^-;Upc;s3P{13y%})~w}eKaP#^BwX;< z9xc*%YA||8@Z+^I8*BMc_C>G|JCe(tnpWYrD1{AcLPmPLFCKR!28JteLEO5c6rRnz zy!4o;#qB3RzV8~(+`k8qLD6*dqx^c`&Sm()WVC{`O@>+`WA%<7MPfiHmuxeQ=agL~ zTR!hHfYZgd$GxfXO#*3iCreK|je)NVH(nAO1G(^q0F>hp_4s`_-D^e(;xYv@K22xr z*(-9XN37-Ls9rMYD@S*m8-ngvxIKHEYadePL*1vR7t62F=>2)bgmv{%WFP;bEsfoc zAYoaZk9SDsmLne|)xm)F7THQAzRUup1)n>pNR3GmS@AN0pZ3)pgq;$;)XHHQ`f zczpjoy5y(5{PO8yT&By;qs6QziR&6%T~+t%@JR-9aYf&mAL{b&=EyHX=bu)WopB_&%tF?s!qEeiu~n4s|lumi2P>RRobG4JY&6 zZ^5Dik6wAJ@h*;W`T?DLz%L@9Z~i(b-op)r3PX_hwy~ z_t{Y-Hp3p+y$5J5%=?YBA1oPSaP}Q}Qv+}*z|uXFVz4Gl4c+q6&Mp<=+sa4nPaVyQ zkJNJVL$#Lyb@>%z<`vpCe^+&~4maUgk1H8o+ynHprZXc{kH%W;>Z=BgY0r&)L)~Yk z$nqRqJ)6bz-X%`Sk$Q~+xrtST{>VX-<{&55(PcI`_Jm&3YZYyK$+C&&6EAVmc!LiG z26&{>^<0HkwBTn*j(Tx$^`%IKbKr>cE476!h{sHbwsLXDD~>CktF;*oPsnXGN=M>a zA2@}rpG(9VV|2hJBVdM+=53UhyjAx-fbe7}xwx{7z6k!Kng_r4bZ0kJ*jQ8a>AuhW z;MDamh*#8q4IW{zjbwgD-`HBtjV|iGn)sO94@&9NbZW$pl=HT#ISb6}0r8F(4_sjv zq8YSV-vk`HxpiH-`Nk<6JKQb5kaWqk+Ys-%Oop{YB0OFUYkY6?_~T4o`1w}!%fX_I ze)^L#?ca|b4(V6u;jaG6{77*O4#%sja^cWc4o&c~Ln$l}ci7B7*V2zw({Un9Ux&uQ zuG4-C{)VRaf45<~LiC-Fe%_O>=3(o3xYSffXqSTTu0o2pWWS>La1EO4N`Wp6aT9F& z5NO;R`y~)~(73fW7gNaEf1^hG@by&HXQJa;x{a`l0$Swl<5da+^?h=dd0NuRiOfZ# zH${s}IP{;;}egS z$Z$;zz`r_6zO^a(Lzq*xz)3fGpDPFo<4fL7TeD?ZTFikKF;2H?%Tk=AW|sZuE0aiu zhPkb9wW%ku`SK+6SRk-|jJZaGC!Y!q_al;d6h`40zvh_;@U~mej`QVpSlFRxsI6Fu zQjGgGH1!lNVx=m~hj{7U@y$HurJYESca7>dy7_~u0GO!JhYs;c(LvW|=S;m5IrNdi z`j1cbzG#r^bSbgZ@&NumF)my~ZMx59{NR+ss?nxuw&E0eT0SE^wV++P6q+yucoTsG zHG^07c+wjYCNZ+CST*^g1oS73X{_%7&jwLGo2Ea70*CL2)O%hpp3J#*D_CbTNCS1W zt5LMCsJ{su#MAv2#eRJc5c_b>x_l859o*gdyAWlN+$;aNTErNG`BS>iC27i(KQ zMAY%#q{KkRz7+2vkZ}(k-bqf<3(hzvwFYB8%558}F%IYLqH5Sx5xR*n>D9{xZ4;sM zk3XJzzU#}8^|9?xwi~4sWkK~`M|#Cv@*#|Qmw*A1_^O+nNm$c=xCq_(;CufAuU>@Y z9$--<-Pgj!`{8%x=~5vBQiY_j8A+Hqk8e8t@g6V)zx*?F9{tg5V{5CRf%R8IfOExZ z!Is~aqTQeX7H(k}e*&D*)gLPMNkloBYOTk@6w>HLWVcJ(-N$2&J*R{U@^(daC7@#K z>;7EyJ+e2CFrMjlYx}}r<7LVZjR(<0AAC(rx{_$Fzqq*$%u?e8Hm9<)=Ib{daU)M~kUha0Bw0?(tG}%Io2nFE7FjC@5mp2>N7Cw16YK8(XA z^h(i*85v*frao0$p}qaWvM$%@G~n%Kb~C-09nSC9XU#5w;%(L(S5_44PBdffhnI7B z!Z$jI44S;VZ*FgT)H@5AlZv$zOp@hkzS(Q&)u*+4W`f+n{QZrZuBP}EUeKrlR$U$F zd0wSY%SE}CjOe`G0gK?mwP3ATXUPCd*GT6f>p5}nIN#$jUG?-s;V^Ql%w{aPa!e?? zS=B4&f3V2knB4=+i=_AZybu>DAcYcSqi$73ASZf*0Pb)P=skCj^iXuUV}3M^GWfU_ zZy6+vZpAKQPfjajC7EAB?JAzhoygAKuCnZ020hrOMFpz0Qw|TVjn)?u;j?jxj1}b} zNV1W)A-dh@}NgG&2=AHFvj~&LZ8^ zK`U9q=kL!>Uwgf8E553>&$V{Ro3D(jo&-_kx>`V-gc??aS7~B7Ej05u2w8K|X&K^@ z-;7G}!{@YDMpl^?DL+?4CO@6bpcC!@jeFvpNC-Udo|9z$7&9*HO>R#R@>vsaI_e>+ zc@F8z^c^)k2!VLn+yg4TnQPadoOq@_SFt}PR9Gj-J>Y&&!Jt&O`)dUnqsl2Ki4v&g ztB9L#UdH1gX7JROtwN><5_A)}YkdD(#0?d{q+Q#WsCE0ppO*{dtnR4b`@Vq{;bIsp z9Jz!#kNM9w#sA9{>vm;-FVor%6iG5`2gG z!*WzoY|l``TjhM%ateX38XL*EQE1km{~&_dY?Y{B;re zg(sA^BOMiG`A_3mjp~%{U)`XZ-s9kGKW_pWD&HuJfq(j8I4UWjG3s7e293hK0|HXA z25X0A*3-6Nue&?{EZ+m7EF!KjeS%`bf?YoSsi?yQi7+h)c6a~D@?Ys5xd-rz{35t{ zX(f8sS8&JSDS^GJXAY=(I)?dzP>cM+A7I^PZhpg6rs#?3>qUKDKHN9T68cYzpFHxd zd|@ly)83unY#*U~tNzA-@rcWzQ;6x!i~OK(|6v@+c2r!(j{3fh^)FLd-Hq*(C%olO zmzd^W9Tb!-3~mkm%LATA-VUQ&^1njC?r!|;=Sh_J4?mR97cXFjgZ~*|k?pFyrGw;I z)vvH$Jv0InMV>lhJoRLgIuZvq2A~jdJN=K>1?SRK*U-Mn0I$;J$4y1fO3fQO=dqM~ z-%;qgzX$aHE7?+%9BnMZ zdpsf=MRBP)&0!v8@o3-zGhU2JIO<~6Jjr3cY=P4HwgomlQ|laIiSp>dEK zT^1=KiT6F%;{xM%hd~K+;;vP$r3Eb$)6tt#YCg*`zJRNu+jOX*tMJLb_0XAg&JVp< zJtu8X_3B)9Y^-IXVSYseu)K&`Iq;G_>jE0 zG`CQrZ!5YRHO{IVwc9vZ<0aD;?9FAYD56Fiq;W)>5hML|3P?nVcb_Q_Om?RMi96S3D7c_LYM7dJ7Dd21r z$*QS|E`7lG;W0+`;F#o~g=gyb07{Wx*!2Z3wU~@**YAowB_3U9eMl}A!Q|7|RUT`^wt|1h*| z{%`Aqq5(1fL4RUyt591o!R`UDd4#xS>OTTgSv3wMIzo0`V8#xL3GlV0_*v0}F<9T5 zm&JD5~CE_ zNu7tVznY5*5Oi?i!Nq-oN1dK9Q$n9Mwv&3=utm7B2FAv%P6z$zlpq??1Vw%V<4{o- z+UCx=J4#UN*1V&I1HMBHU<3L1_&QR#JZDc{`pk9ty!#;Ty@B6F9JNoF8 zJhT&K_8L{S8;M3AEj-tmQ)F>`7p7BLZSCG|U6w{oy8ca+gC(LL?y~;Je*c}hS~k52 z!g|&SJyup;)BcJ@^TUv*WoSZJhHN5E&Az?Qpr8y4cB{652|E)<94UaK`b6-n)sh9> z+A6c5l%9o4@X5`PF#y@5jF69nk=YN=_`k{My%4_)AY4d6WQDSJJ!}|9(Ev|p-Sz}F z_IQ?!yzpUWUwfFM4?Ih~+QEh8bsk+A(*=6tLrH3n2C?WAm*_iC(yAEn1+uVDv>a7c z^Ropc-yMBXQWrE0y_Ob6u>`ekRhzjjpWx7ak8yr2#S33S*x)`>H%C5U-s2VNAC;Uu zw2!xfPyVXVJpZ!K*no@dBb~>O9-y#9e9VkWANIII*PdYvb9!oY*bPV%3TC#P<6t(&*{QEibElzS>0PKp42Sq>1^%3+<_^-M@YC)8gR@BHfi?;S4;BFn9r5 z2X8;X)0=<#K;}^~{M#s%02!qpFW?%&U;QQh7c3r!iXM;Qb;Y9uSn87 zH}Xw&VeU!*$I&3+-)Yh_y4R48T)M4r2A~984?ZE0s1_W%19xGSA8!Zmg+=M7sI1R~ z^0J0wwj^SfUA#~W!s?%;&wUU?8ghX=wXm*y^JgEyeh=CmnsI>P$9Tk+CIaKpeT0EB|p;6 z+NYr3Ub<5m=+&KMTh*(UivXvA=PykMSD;U1XkYD9pGi2ZZS!g zI%*E{yGH0{H9({UdhbRz^+I zW+pul*5R{UvP6s^csguWOEi<(5xn#&QxJU3nu$UrFp z`$M=$>OpKgJK=C#;J2&~Srh5|q!6)#VVO+N-!F1in56CSV1*OXU`JW$M3JzGN^HY;5S4`7UJ>% zk7s`rQ-T4Vsm*JL|7`Y!o}3#9pg z1Y3Y_=kuiU=Sk-E0mGS~B81{69JKG*4z*0!D(-RQu2yF`4kfam{ZiSFD&Cw6;y~r_ zV!f@6x2mOY(fN^-+E(1% zNi_Xadw*SoNW&A9$rjk$Zx~|!<6AZSj3Tm9#ki3oVqNRxNkN~9rgnWq`KM(M`t!#F zOXskwauFQ^W85X24IX$D_E%1Htl%feXX`e$9W7RaF#>w+_GzL^)2=FL)N-dyp6>im4dg`7zWIdP2 zP6;hR^1&}tP`eh@$TGNWyz4lwm5{iRG4N#e5e!YmI&lwbdue*r&w5IlHD5H@9hnzK-VND8#Fq)a3 z5%s_0z~kaml@1&-Y%~I?mSi)Grpg^N45Q?R%S8?9U||=Sq!4vw%YhCZW%hk%Fh(L! z+n^Dv#<`9LwDh?@HSPqPp!wumd<#-xlZRq->V@t+@JJ+M4$kLj5KwB$fEOP1m58<6 zcis;_2H*>7?gnWidPioGVC|~dPT-$FU1Mgj);Am{GI(b6Z+7~2RW|)=PY(#T&qz4J zc(f$#vQ2tVj3{%`mPBOGk3z-FS5CnFBZ|I~d(pN5$ew$PXJ_l!%1EJJ0O*bAe5cM; z(GtQi;A|)tOP2o$h*od*qYF&#!2u~G8mcv>y=D-N-6EtZ=9MGo0tcitV}1rg^M zb8stCn`U!e33)v@7_4z)|ckk>W=#@6=(O8T8y5~H6FHuN_xk6<10+@>1iu?-vja{iENFqA9U@ zZ&|qPVPa1_5QNESDK{b(X73D;T5nt6BNw5ZvJLn;mCQY$htK|;J#`p9Yl35j%3L{; z6hwk{^)Nuro3&!8I|oLYt8m)_;?`c+i3XycJrP0}Xy@-Qun>Q;`|jO~BBckW$`VVC zkg2OY#x7K zd_6H!Gm}D{58BLxc$g~;XNVK&i(r8mtYi1t0S;!hLXgi+HP7yrSB6=H)BfbK n zA6WWK#Oeu6;aiigC-?!d9rDdkd-+nJPOe>dCtcoxiuWNz)mhsIQSu`o@mUFHSStQ3 zNsGJn+uf1|czt%Q6Le2UQ_+GX|( zg)Fo6V_33rvWEDEK&rWA%N0UnMymm>QfG7~Dt?#ENoj0>TB^1n=}v5msB@%#Rhi$a zb>+eIc@o{OlFihZ3a-F4%q{P+e4K(fq3*3|B)+q|2Rzt>3J`ATj@#2ZvTb?27Q4bM zMmt;5c}7~^AT5!2c$B&RK7B!-mhgZX<2?8Z_NCkRn(h|lQs;lO!O&JnFa67WY%fc# zP-GEdK2}~=HC#cVA{>qbO$HL>sA3!*!rE^1o`(qnSJq#O0BqGt^ma=}prUMcgN5Po zA-h9@q6<7IL+rb@h6HtV@y^>iljIl!urU`(Wij+@Q`yIKxf%zI%2uJ(;2V{i=PYt> z^bv8Sv2@=(Jnr`d{sO)NHgI_6nt*+ z$)U?g2PXri!0tS?p1jVaI#R{5Aho~|QuB#icfcZa%dhs*H;LO$3-PADrfbum+RHl# zqBTvYf#f~7#pCU$=m}kr@9I*e0yfMjF;Du1vjsro(BVtiJM3dXcm|rjpgm=UYNWEd z+Rj?gl++18MvMA<#soliJf0p|yAHGiJFQPb=oGO_IrKhW?k?of>596ir`k!-MX09p z+wE}8PwXf3Gv7s}U;iZUoSoC18|S02@znCa$*Qit+2GS;Cvgs2I*U_F(`21fv*xW$ z3$iqg7xI|{j%0yZt|kMhr{2~b^bqn6?PR?x&lSip<&F0FxQW5**p5TeB66D)JOE8@+WL;c0%du_anUk2w4#rcQC)PU z`l!)*F$B*W;AZBDYtB*0`%$+{K6qg=E)?lPoXuiR!-2MoG|c1jaU3lkV50O}7Wp}c zLo1FLrBmUi>Y(rMmcw9>N+nv&xdrfS{4En*mka|){!gTRU4g4m>Ii)2&8IixuNdk^ zF%YEpaV?J#49#yrvkwnNt%T!HKCTWT6lsTq__S%t62|G3<-o>%e%$IWvz(zAaYrsa z$|Z(o-hJg%h!bG!$ku=JxuRp4e!83}kH2<$^!>**yZv@eImsi`@=Is5&h7W&YaKNV}T^pZp)DZyhsDI`z3gO_;<>7BIlGWSs zXPVUzt@UWhrwbp*f{ivT(~>HNY>=%E9Y1Joiw<(^u`GgL&G}66J0`FF+ zczZ>J<{S7>-RUI@BB=tnI-(Gp@d(C>got?HG5T-`V%`|~CxQ=lL53y2U@g}_ zgvU~4$Hh|Z4zX0OZQpHI&QX26=kgV5K%{O!F~Y-^GkW7Dc5{s$_>0d2x3+qgD7V)o z+_Z%-yoqlID>?ShlR{5gi4A!v_rcW6RIlcU1Qal&@&_mY4UQxs|_x*Y^gkD?|MHJ0-MJ&r+jwmpaBF|4qj>NXxcI5+C9Q^La!hr^_v=XAJ*#L+l{7<%l+uF<>}1YX z5l=58@^kg*yEZH6rEL05E5vZUs{XZX84I|@XV^1MmB#JYQc;oeMs;d!whTPTunn0n zDg&VQxs5Nm`2G5HS$5Ie73X3|lzy&p7boOffj!P{yU)1lgLft^`|tv5V|OHiYa)10 z05J6w^lY{S32(6B4AGk6+p`!;2y6-a?iUj8G+nc^+am+8Y-to->)i z>)8LzhF^wm?^0?$Xqi>DNNFuYYqj5*>yiciDx47kwIJ9Q@Z#|LPWX<`UJ-g3Xmx<6Zl9~hwo)*A7snmxB378=3QGHl4p++SxBUf) zv`dQEU3tZE&g|Og>!x3K2_-MjV~?EQP0nrSX*NO2jV-rg^joLn*{ur@NP8aYPUkTE z1VL|U*Wq=_UX6h=ck@A{ihPm&X;SAETG1pVEvsJmsy3_PcQ${fKnpz!i~Y)hXEwtt zoU7$|-)+28%$}Ct)ks=9@d;Q*vFI4x(y=R0?QDU{T~plDiYn@Oy}=^1%mQ6?9~K1f z!uFm#U(qHG^Bh=ECCR-F?BbKVIxl(ZzjW6BC zQ>%}|b6Gy+Z^1_0&SS4d;nfY2HK(ll&XuP*-wEyTGR1`ZoO{XWAhEw`4V7qivK#B9 zrcB%ig$=;@AYZutfe2^G{0e21s%0nRVI*9+oHAF!dKFxr6);+s*SzQ5!>Qzh;B_dgBDzm${0VG{>`ut(O z54I9FQyZC{RAv><6y5{42zY{qi#gAKGmWx`Gi1(}VuwllA{3X=KP#G})Up(7;lW_n zar7ZO-28NOphE)|u77~iF>qd@zHTh3d-s-J#F0A1Sst@p!7?oBDZiQyYvu#H`Z}mb z-;VOTw-TA^OXi6ea9XlPmB}|7HuU>b^W@v(KVijQqGO!rhX16%@q>~y6{28tB4wQm zjy{^_53S*JNzxn+xfa-g6~AHIi7<5^R}k#C$Yw1;78n#wby@#FXw8>#KhjvXbE)KI zmU7~Np?L76A5lwl-UtR0{TN@~vrzlXJXK4mt#2qlykiiW7Q?Ln%fwXeA zlt4wVdje?KkGDZR_@{bztS9gGJ}jD=r+%$0bD1>rmOD0@+Pd5@k*zk3F)4M{cg+zU z#kG&ad9!%82Mrp)r>; zzSLlNVxDmi@4J9JTj*`Um@?Ilq2W3UZx#PMn|fT8$x~}viF<&W4KD9ZE5g1IO~2%E z<-_dil(i;y%;hEDK`Kg#CO~*9IY^yE?1_2CJs|3%x-lZDOvk=42|7d5=pu{W*NwAq zJ#MDrBU>&-cucMGB_7s)OS0>pM9$$yv+sz9K@OzZ+rKk&31) z=>)Oh@9W}XVY6gIdmk;EW#($s4e;aiO)? zP3WxO<d*v<<56_;jF>2$;yfyQ?UQ!M7>*zAGYcVn zus}D2GqhNW5wn*TN$rf@bmf;6w9iigc@2a0ddR}wQ&f){isde131fUX>vcW;4AHL$ zaf=B&KF74fNO3E;FH-6xQjf=MaCUhAG}3U*I#qoyB9Ih+TbMs=?D-)ax9D+-gW^df zCh79@RFKf}QAwU-D|>->5enbi;3-_`p z<3`4dHQ z_&y%k9=8wQy2ZJabPV*-Kc|B(Us}v(YPSn)sU>LrRSuKwBig3XKrG?`8K=qUqpkmV zoSt-5AtjJ`?~Ue^_XA?{aax@8aT|sv%$hkxpW8oo%?LR4bydM51tehBI47af~@^ltt*s~=?QAVYS!ER?l%`Nz?Y93bRMw>*X%CW zAricjXEbxg_9t;T3h8vL$EYcu;Z%BR3Ek7s+69nL(dVT`vB^GcL-l!Jt~3wo3vwRtuA(o9LH z@m0|E91C}zo&g_yfp$oe=;vp`Z4xw}r~Q4#8xgeKY049det48irggvED%44$QclPlyR|C3LSZur@$ zIiwG9{;kEzK#&lLtWZ5xb)K%9^%GB9Az6fob(bB{VIpZ>jXBY@>Q=o!T%`atT_vn) zskRn0Z0S$?nS21rd@KUSf%0*@jMfTg3wZ7FtbS6zN7mu9*_RTRc!m_bRaA9oIcJ)7 zmYLH24EGr~o@rWep^L6PlvVBvirSe)ByH2ZyC}{3*$wuKX}(uWEpL0blSnp`aK=61NLtM z=08_$X4r$uo+b;v7zxH7)iz^ABDZ-HtIbt&I(3$oq{AtJglA0jAHKT2Jh=z>Pph_< zr1%xt(dNazKV&`FvOP8Dj#bYV&uHd;RM{Qjx#9e{KrhWQFM&{4k|#JM%#Mq;#|@sc zSF(Rgir(?m4zCA#kW(huPO3bSG5{EhfjX+qsr?}(i_(^XB{+X`=cYG=QI1qdADDHh?@R+4CLFp3-*&aC{?IVXghK2tLL6w>2Z7&MxO*(16;8<=xP&gGnu|jC569G= zX|>Vg;x2l1_|s3q3Fry!sP^$*X=r#A%tH_kH7~eT|HSPI*-yF`PRSQqZlGFq!1}vG z+%A|z#29dN#hIuSm5D`~q2F+Ua+=*=i~j85-(;y-G-#(fyL5W2B=$MvI{CJEp1OO= z5pX45g!)L;k@ihy%sqgFBp0mM%>LW(eM68i4U1uC_ih+Nq5cy%Da4Z@!f>}=v8vZ; zl8sO#xubzsASUlgyaP?^IsiZ_9ZjpK`WMn=;p$I?RMR0W{*5sj=Gupue|O*!>bG!x z7KY4Snlb+4VFVE$)kRsB874##LH$F(y_Ha0_fhLcN;`!62q?&a8`9iG5OFSx_f7?E z{-`kkc-KYQ$+7V`78$otJz9Q&`bBiuRj{u}{Mu(QPjIa2BJidaTm!UiwIjH2A`eX< z796fO1z)zKj$tz&S9NTT>W4cl4`SYeay@@DYpCqz z@ZSTF*uKqe80kY0(_cr%S#ZOdSE^HSh^eE5h_PD{1Ro{r1gnf7yv1{wu4V`$^HJ<^ zL!Se9@{7bRsD5?+@0DSxUXxDVWZ)hr zrtZ$svpiT^+?)`RG8d!JU{8(k@Z!Q_XJ__T_b$i8uWO4$3N*~;Q6Qc1XGG4|_=GtV z`O8FkN?o6@Lx?|40D5B`-L|50wTJG8>#i!V=kWNR^#I!9yMouKtB|frrB)G^bJ%k% zU#XI;cRq|QPO7njuC-Riy~At4pI?O5_qwb-IohsQUdpE;dc}}7$qg^#bH<&okot4I z&2nNk&D`6P!|u#(Zi&ZO{DLApZznhW%Pv9hR5R2y@$u1aH-IEIOHazudSy;^+dFH6 z?F6N?rr>|y2%H@gHs+X`jnC;%yjK6w|JQzR7LzM&8&|-oQx*RT_YCS_D~UPIQcfgm zT;QOy$I$8|h`yrfCdl|Io<-O+bS$6L30XDp#+4xLd4dc&Jra99wsko+i00 zV;NVd=|>OS%MHGOvADnOdy|5`$1zf-M{0HGyVTOhgFcqCU`=({8H@lk)pE8!#g6l$vb1&u2MyQ@g8^gqj0UoVVPowF z3HuRbV8L47whu$|ewV95Lu27dE9j1@Sm=yk3rM+FE#>B8S<2><7-5+OM>=fQTFy|k z~9@z zH#qq;v~Jul-1#Go*!PTp-qW7~*I;JatSv-;>WVkUa> zud^!ocZC^FoC6%=Q8{NeD4~+?W`^fF3Y`b_>~S2HOR=whDoECHC9YivHpgOSUnNbWpFauzx#{`*`&2PCw+sSnHM= zZ2+tPXr_*Wk8m&DhVb$)IYkaFWBf@;=kDrCNRQ=&R!x;-7*}^aLpx`e)IYflxoM>a zl;q1Si962@=Cr~*RoLknKsYmrKO(fse3K=jNhV^s@T#-noVA4S<~}=Oyf`)dg;=Enoj;sV>wlaHhuufcM#bPuZb6_F{a_ zD#8u}=OKiN&JLhuJYP zD#wJ*f~GSn6pE#MMqz(*)#}mjEdT@8)C)16EsbLW)R5Hi05YCkbSK z1gYQUSPzndTzD0`e^0K%E$U(w2f4dAQj{m$&+=evwN<`D=ElJ1mCam3hu$y?pB`?t z`N0o*<~x|z3YPz$(~|cOq^w&BB`FtoIcY^OIZ_DG&!CplMdGKQu-4bHaBU!q-0k^b zmqLh*buslhJ7JousZx9MgZyaP2KMk0lXCUO#8R z(<=X#x{-!!e*t)>za&n*^6|SN-SiEb3?BDbgwehvIwZhenDD2(A*cQ-*?bQe#i3a2 z0*Kr0Jls9@@v-~mrOp_L>bLX<`{8lzD71$)^I_p$Fh#@!PZIHMcLs4{B41as&F80o zK?c8FiQ;>BrdHRND=T+vmzQ$nTk{gAy96aSMW2FlW-dAPHRQHCZSz4Cgaq){SF%JS zLNRuG5J}sDJBX)In#|q%I9JzC{p1<7-rUd+EJxm~qRj3(MS~wLdkK37YLHYNJr_ocU zT--b-NH^+mDLQ{pHNtI-_LAy~>(PT1uJHPc6@zqWZT8;LBtJv4W%5OZq{)ed2oh=i_@lPkB@=mR#oh|IK7?#SvS}r9xtKt>DOLz z%ipyh(L{lUw z{%1@n@-6KyyR^&9&Kx34$V}?}DV^ZmJ4}fqt!8hk_Z>CZ716SbEFmI@v1zbhL1@!P zJN!_88;D^dtj{arqMHpUy_3(T{A_I0s!KhhPAbAi{@E(ZCGHCFI;{EiQANSMQRQcjzyie+9_uuKon zlt>c#@X3dEzx}zA^6&oV*X?TCjbu$RZQ9J=kDn%IyfRo`npa@`Nc2C1hFYzD92cZ0 z%zUZtgKvsOxK&9m;BvV`mqhI@yzD&w_{UjcNPHBp#D?#2q{=C&NEh!Lb1#o33+GHM z(C)l>Z+}N(Q*3m7e#2=TDlJ$ga`uAPbw7vA)6adlHC;lr5`^~+Sz;9B`sm+r3Hm>{ zfsCr`BHuqa`}!lO`f`I6IfbyUeb*I(;U^m$M_0E^lzE$ z#QbdI;5tO~OyoUq&8+HT(8}&+zWqf95|)2p%h7Erda4KcR}vcdB@sw&^23vUt4;S8 zeI1n8rAH|Qbt|Ez-<`j^p@sEOc14b`jaMM)ly3wUr+eq-VQ18T?Ie@A>pGDK^qq!) z;*)Rxd-E%a@()ttgE^T{V2K;NrtgV&VSkk)NdMeo`=X}oQkRubO*$?2Sz3U93CF~& zwC|ldgR?%AH{VT))%^XEXbD_R?@E(BStb16GsS%xzw$nNXN|6_YcF9y>WVP?%^?!< z{WCLrr^%tAHnpY!t0{7Sm(?5Q@@EKa%y4y)hdF8`!_!plA!G$gk~zulSFCG>f=C`= zsZ3CDj$t`o@DHVy5qJ!CSz^#=X;|5nMBHz3&sqo0)Dbj)g)6hP-9++}zKkp7MG`a4 zE+CDm!+D$XNOJwke8D{vF?I4?m&$N~$O^URjb@r5zoS>I@&s1g{N>igz0GnbFJQXd zhN8{YOA=2@_JvfGTxXw3jcTql)5~}tURd7yNJpVBf?Ib}SGO!owS34+$*Z)zLCi1p zcBrFHk%L6{V0siOw8dB3?NONQg@J)z>qVBQ#3w*!$zN%e74qM3iuh;wuUn1GsgWYm zm0_|AHxFMF_Qn=4nY~5`NqP7Z$1qV{>RhlZ*e&+`X@+$ER+ut)ym|PIMR~i|*z+fq z*QK12O3z;Qfl(T)QFB)Zt+n-6kjHgyt^i4QmiUlY>z?h|a5)W+TL@}|xrIHB7JjyO zUi`ReA=jU~pByKz%s($N`IeP`sW1b{Z+(I-HDrfmc>04aN225YI#gwfh7DKNm_!H? z7Y$H^2pRLQFVG#3a0*;8!mh zuxkV(H~#0wT|B83nNc6!iNgk6+mNgpu0_b{8FORBIB$_QNSC-~E%)&;3(ZccRt7`{ z)>FEFWSu7bprbw=!}ClpZ1Ypz%^vDd<^FJEWA!c4u$1ta(3{z_hCwuzUzw*V*R@T) zR@k!hXmGQcO1nY7Ans|BDtotPjmZ>#;i$uSz4SwYqc&v7_N!-wm`)DN+tjU9m#pVp zm0jEMj;a~WQ@d@Zb);M3qY3jagPEc#1J{U$ZX{Be<*`$H>hB&LJ6mseYOnUhHbGOk zG2nwh!P?(9L6XC3Vrm%NAbm}6qx91oYBTQad>X2Pe>LlCKRkz!8omKsjgig0ffPo= z69~uagJc`waOtz-t6!nbBAg#7u!KT_P>}sd~@y>(GSH|pq!2i2_B)#fROuS2IHAlr^-OBWF z#m4*}%!!$=(_v-YuWC&$ozqnvr9MjGE&1`ZL2O*3(md4Rd2n(;hCKUYGkm%noG&8g zgf{~EeB^D4E7zH69!!ohwYoh^Cyd$iw#!xypDqJmrU|tOW5o$a!ue~waK&tSd@>f$ zs02McipWF8LWvT#%vdDbyprM@WA>c+$zs4P#HZbWz?LP}@F>|aHCV*t(wk1RTc-kT z#U3^jvB9G!tGG(6sr}_GucgLt*-`gRFT7Jj9G(asa~vm2Jnkku*IT*Y8gf0Q$-2zH zBV<8xh_<@~9?vXI;o8zqPOp>r%-l?+d#7lZIoqz>ej6Id`FoPAG?GqRd2>W5AxPoO z@_4@GyY!&lz!nfKxqKO0VU*u+>`h5wD53*tt_bv7N}X`MUw!OY+xv&-F)@7^4R+zL ziMl}k@K}dACRY`o z!YDQ%bRP2757cW$=;;r<6m&X$-*rg-wTheou07wE&yGTdS2Gw6Tf$cXI_P1R@{<-u4mNjF$dacD` za$H!ze6G>k_n2*zr^ka=g*@64_oZwd9JBXFD#bDWCP(|4H3sSr%7<=+=B- zU(qRUcfKx?2e(7eJI05^+X&0+KWY^ z_OMBGVP>$d&SCs7KprhfQRh07vy%1#t>=()1V_iY{K7{KIv)|E6EWN)HO$K38dc&Z zK+noCJ0fEY+ak*4*w94z3)7}(Y6X1OR5a4|?FPU(%>|$cBfG$V?=E1M>;eNPlBAJ_ zE{vT|7H8{A0+p77p9OwASG_Tb#P?k%xIR_6$-93Z!|;Fn{Q&moBmYNBvE6y)mJc4@ zVU9IJ5&J$g>TPX@{K5)GSy9%r(qmSICzz5h9yh&WVRzF9aW0;PpZU}Q`a6xW_d|v< zSOX#U(|-P@OGcdAWz({K(~;2W?J7a3ihw@D_doiEZ0bNt zTfB>#hoLIg)HOivzoeoR8>|8U@L2nL-)%UaCa89z>g9nMD4GH4Lv>BwX5tM+6#qe# zUhb?KGbPS{{w;1e5{qRG{Bm~lHcUe)wv9@-&y9KRN<&zqVsq{Bmp&{QaWCE2W#{tT#Gzm)%}wO&v#4XMR?i$#J$d-e#!2o` z*hrOc4$ImDY4?4T=jazxrhxaCe(8Tda}BI}eDUe$5x;S#QJt`x1-R#G3w_U?D3?iy zOSBe`)V5!BP<_m>F7<;#YLf6gL72zk3-g1W`0YO}Pkpp$u~Pb#2Jy_#i%K*dg&zAw zu6LA$-*#IY=ITD@8!POT)A-xIrs?c^(T46EQ~VW|2iqnx^94iJ+&rS1QmHqUS5j!} z%?52)+k0Be$Nj!9j>Pi*%%|fgE?F-aarB*=hD65YOc%#uU6VicozPW(ioFusJ=}Nv zAH)WG`mUW=WK!1OZs1{Cvdk4XPuXp0cJ6mR+=!&qzpcQ?OZ{lAj?d>uCc2-tihYD- z^BDB{A38MRzlCq$HwqeT6^(JGM@AII8gd)J;*zm%{c9yI1BC=qbZ6693zx2R%;h=N zVM#ZSXjLrc_)3b(%L5B!TWri!^ICH?~`uV{5}2tuidxJOdy zsFQ7jNbWeM{)iFu-4o--ociD`H`SjPRkfb|v`X}bH{z3jhxGPnruP6;Zzx_MRu3<`~ z6T22)hmwGNkhsw#`VqNV3H0qZZpmHyyXe7r#7*SZt3UQqdivLtSwkk<=92G_r%rgE znj6QzNotSnO^m7oew{cR(u;q5c`=UWY9Aml&NUf3^|8H7xjVQx{r!h%Pe`!2ek$!_ zRqw+Im%53lii(_1KF9MF9=@OR;@>^0sVI1pSXG_U4X*R&+$ps3n!gZm*Hq5K=fP52_s_+OY6`|k zUi1E4AoAo~h1zy#Ve?-b&h6(Fg;Jis3j|n|4COyYhTx_Q;hiWmALn_gpK->We@;2P zy}afV>&+(hrX28K;?f^Ntni$HqIuOz!))-q8L78d@GPZXiPOKb{O9z{C|t0i@@lwr+ze?s>>I$7Jn(XAJ28R=%&FSthe+Zq>1YeVNfeBuHev2MpdLYf3&LR z`cm3uG+C?z-`Ze_=SLcmTpdq0lSocel&`DmL{^L(^G<;m2U39BGLvn-`%kJfK`hr5 zrJ>e?P)ee5p~-6RPy~IDfG8WWkLMR##(J9B6`vLv=L-X-0xh$G!w|Fho$CP_O1JM| zgES|L(7oTeb6^&aOOtSRyM&x3r^6HB^ihp~vc^pVLIpEi#)3lvm9MfxzD`&}RaWhNuH>G5fAC$RF z;2vfilDz|tQ9g}$h=xm6%&_yFRh!s{eR0se%TtcHz}q1?Bq+%<{5(Ux>nu+CTKQkK zP(AHQkIwypq_T>$0BJh(c0D$bzWPVwK9UlW_c8g%#|!e_cUTw4e&j?Nj}={@IkG3u z;c5NnhRzhCVtG3lp+Jg6ET)Qa3V=P)4=}A|-|XdWdQp0GFw&ddSOC|>(;spBqnI!-mGaDM)g>+&qRTG&5?dun5Srjblmh+6xCjN7?0aGcB1FYU@M= zb1KOy&~rBCo%lMnraKG8t%4WPr{izGDpp&AOyi#zOP(Ncdo9ou&Wru-#)L4w6I2v) zUE%u-62g=l{%26)C!0LGT6r5<$(v!x6gFe|bpu+{Ce6&exu;G~Ih=9ju_BVVR9N3K zJN;NL@~j?~3+G63CWteUmi+Q?me=GvcIj{K&BkJhA-Q%Rf-u%xz4br)U94s^8X}w2 zQMyUTjyGp4?~Pab_fJ6Xz+RL%x#0%Ff7V)6K2Fk+-EfE`m_mGZ8g|$evqlAJS1@w^ zs3Rr1c#ftBe2c5Dbr5Pi$up<>q`jt?BmjBUMMlXwYc5fDh?!XJVKtN*OE#1F#2CE+ zAgr5`uv#7F1`ERF@^F76*=!DHlVU~Q1=2Ou$%N#CK|n&SSdLkNXY2uEyHG`5a?(l- z4+Cl3o9+4o4{F zy*k3&IiqK-=&t85HZOl|f8KsCpLOS0WT!|MaJ_@%!Y*UnkRGLdRCkkmXv?y%ytnT( zCe*>hacQ(oqBD&(h}yZ2|L*v5XwULP?}f#QJJ4%(w*G9L!;#3llANBoGT56b=lbE>o5eAm8o2@@!c?nbX;sB+ zu9!gf&~+f8*h7qDYG^(pAh85{e0@8<_Gx~p%^weKq`!L5eoz69SU0xyI8yN32)U)1 zKBwV0Rg(fSD5HFoc2t|Sk1&(|Ppb>_l;k!>F^0`e&`vcL<-|eW>f|yIJluE)Re#$f z9Dt5R;=8r9u$G{L;=-~ETL=~FOqhW*TsPD~3Vl62OT&IM*N;QYgRnJsN6%il@7hmQ znx@O6R5AN$tIuu(6|I0HYD?$8O9hgEcvttgFDn(d{{sO+mZQz_0Iu6yt5mzTYW}sz zr07AzM!3lNpCgkO57?-N934>BDUJE2$Em;_mWqKJ`S(+r+MO#&XYZ4BZ(ag0qIAv0 zOBW3v6Ofn=R7U)?PHl|iI$tt= zDjH!HV?u6v*$Oudb2?~zf%F*rxLrzK?aU|-)Kje$b2Hi>Qaz88*?gcG_SLS!Kk(Z| zPvN5AGi%Nc2k9}5+P|U)-Ll)$K%w6I#_hrd_PK`m!{nAj%Vo;68gG`+dAcDjh$FD? z%>B5CzgdJMZ9BXYr_O@{%h5sTZ4cSJ-J@R^2Av?P%d({SmF4zl3d}vq{0C8~m=5CH?$P<(YX}h!#Wvj1`8O9x2HfxD(mb#1f!~Emt1X3oh*PD( z?y%U+s-H{INmppsJNHBXr{(M(_-X(5>@~9Ztwa!OTsyGNx^Tc2v+W^`e|(f>$WFqD zMyvX*fj1XTJawqpx7Km%EkJMIDmtUn^)~sS8^+Udxy)}Zl$yTG98KZtPK54=?KK>@Bn>%rRvTIpht)iJW{hUH;8k8SUR@bl|9o1|B!^%a31 zW0TFaPv2od=r1dyPmxSrCK9b5jcxvXL6f49@%YJ$8-GMUA_8!?)pvFNL6{`>bzLkx z8rz`H$^vjM(RlHr{~%=qNtbBDekJ76G$ruQSL|g^$CRE-_POzay_*9p(=YG2H#x6J zwvsvQ???u0l-dTeZYh6>P&_w>GVt#^Jm+-WLt;1auf~v-{$-BN>&ISqewyQ`$TP1f zjqv6OZX1M%naU$M??oDi41e5|w%An+iN8B>YCp~2w0iE{yCUyExq#x|m!aRjc9rX8 zTvzGs`#~lT-BR`2$aUx+aPe;P5=76f_P$dzbe_W(>+wLpy;&L7SvvJsGi$@Q>AtZ3 z-eotF$BbesYb-&nuT*zG_#10wrQ!4oP&dMmwR-#X2_G@jd&$)o&+U2mZA??F3zQ&0@GE zP(Uo8{rT53M_UgqSE)B~bRC|oak)b-WkYXF}&@6-Pp#cYGDjKlOQ*cJ!0eMe|*={|G!3xQDeTIaFFXC}B- ze#Y>v>EyqSLx|kk&+k8WI|g9KMPg6*nk|Wt+?A(KGww$Z5;VK?JktI_a-0sUm^qI< zvJM$7Dep6R&hDCtxrJx^vLUgD_NypLG$X$~Lx_&6@0fRODSmqf*B(~y;0oK_dj|QM zIQTgu*(u|f5jAlmoAFvROz&tW*3)s&^2zNV)@_-*ljG_&J2wp@qIF2NjNNmRm73wd zho}-8*b1*-4s6N!jR$6&95RupTTd3_1jkJ zhD+TiNDurfb!pg`*jlsTdZpFRJv_Je^27Qw#P_f2X-J9Y-1nKhji1$byOj3+9sx|k z`tfTi&ZdhN9P7K;Zlhf%73<3hD%$fJX|hr+$d~2B@1IX?s(fnv`xL!W=PPwgs>Sfh z|87ydtkT>4HxIB1>*p488wV$w5?tvW81FU?T5poOTAiozZCvwsu02U#quv}Zk z*>8Ma^5{h?wpQJUK!{=V1C;q#RX8BJfD3F9uW8zb@FJ+KL}j( zQV8!*b?{8GXW8X59yEm{Q%C(-Zavvqo0P7Wpv?+LTmCkw;4Yib*ylF0C41)KqPgf9 ze}a?kiKd$3;S0u6jf$<^1dZyWm)gde>pH7nF&!&k1h3y)9=|1g&vPW0 zuBVjDcgt$lOub3DAusl-R-t=CQHS~JBbhTyKRt7lrjUlpO*i4{HaWYlmsZmLz7~(4 zAYoTXDoLOWfH}PA2G&G5t9@8j4{>o27l_J%9&#_?iq^am;8no{1&`6YB&2! zr)J3i9(Z~;+cH|o$$RQMkCmF^O47{X6K1z(;)Lg~u&wWdq5W3##<2Pzj&Y2nm&7%= z5~Ld?JIj*u!d@NMlJrtlN*;mCSE2aKN6b)aZnS4iA8e48Gy2xO3;xG$@Q`&M4dS;V zZriu1F7ietf>WVx4V|$g+aKO4arReUerAjsHqL+MI5YCx#`zn|s^C6qD7bra$l~bB zw~#KOWo13vX{;Q#E*LzFk+ibm%-9_mfjb0eLRTH!r8S{DxG3)U9*S>eel1*SoJ9G0 zYoJ&z2`A6)c*V~M<%sE;pk@?p0x80T;VyR}lijCC5u{NFkRqzHBOsj6rg&)-!O}^k zNgf%CT&Fk{4A8ao+;^OBGGJngv$TT6Ws%w*$A z=PekuI=IWz->yB?D&T$Negt{Ue=#(XbiK>{&rv4hQ`r7L$j?l%&uxo)J{u(%N58uw&)orp|G;2`fM1Le{Sg0gH-8)eYjL&#Axs4^~&d;R$#fl5p?F?6Vt^ zjdLLh-mKyj zVO}$N8Zsql!OoViy-qb$LL)G*pE>aS=D@sqa&)2hudGx}*_|)-xC^|&PJP#o{*;84c&}5fAqh6d7px2AobbLmiRtmd?SUh+XVAmZ@641^AAJ zr0>9E=TnPQ6w53GxC@zGbcnGJwf36^70X#@1|~1CSVbobSPn1);pL;@H+z6HiT-l< z4t_pkxPWf6u`oSDna0P`#`n_S4&pQcdSJ2*m7Kb124|!~b7JpgA2Yk^}yf z4N--l<>wwPrnBl@ze3PCb;Yn(7=P;@q<##TOxz3s#)7I3NtF;Oxx*nI32uWay%6AZ!sb5ST2lbqoza9YH|f?||6qTvH{zKqUiE!* z!nODk(`1u1p+~Cx?OGNg zDZdXAE@Wk1QVq+xnyu_)i-6>CpgYOtt6t!@>AT6E;{J9ZV zE9MYM6}XU!UuT1*pm!!ATB53O<`a`he03j=r1fMNMR=4>;%tn0ioEorSebi+aAX89 zAgIJ(DPoE?G0L=)7tKMO&$0<1oKV=y-e&9r6M@I`=&m0y0{4ytE1f^q^6_PFqsgb_ zFLlqZYOh}7Sk+F^cV@|t?N_cY)4iGO#<6j-Ft3(n6Ieh5w7jLU)SmwK)J z^BpJr{VR2Tj8~Y(m2)G5XzL1nL;`$!qaOj!@sjKi@X-KZ%vEZJtg(Q|dL}mOtHFo} z2$(Kwe1x->V&1(j=GVmydQ6RazpC`5uaCRqK%(ZuFpPjw%4KUW{k!?K7usJO2Gp%p zoH=q)=BjroCL#ISaZ_}pzWH(Z?`|zki2g-}(cLx^#Y zC_%i!0a&VH96akI%uSqW8NuY6c@GIm+FPJSy2O2U6%@A^yT?#a;NvlBeW6h(Zt3j0 zcbS>PcmA(&=Wc(cl=+ywuE^j=KK}Oc9G3m7S!vS9bGwF&zT%3Or)64z%iKu=mjbk%l;cn@r)$O z4?jin7jR=0GYp~QFil-emgO7?s-bKMhQL3`>?pQWZ9D+*HfZZCD+iJo{35_ke zZ9pWy<77`JOL%NFTZ@7TYs^PD6&;Jad^C04=1b6=p#_i8+r3(ygKFS427H1Jr$RbG zfrI^3F<$RI`wI;s6|;PNm#D_%b4bakRqYRnsTHgz#(b{p(=h^RUoX^HWYCWBm?SM57d zWgOIJ9B~CQx`$}SI$6i4SJ*2f4-CJDJHKgE%xF5h@c3q%f~7hiPgeCl=7_t$BJ^$K zh~NvPeOe(M(e4$C-sGb;pC-EA~#$heRO~eXP%1n8OpP1Zt$*u ziwx*(6k7V#|2$-X18<(=lV3aD@nWA;x4JRaH46I*4DS4$k4n^vv8&5kPzT1P&MkK2 zI+$t*nwD$uPQ(-t2@*^u^aUrVQo$>Y2(f_BW3doS9AwA(E<`-72O(>o$$x7Qtt$Xk zrDm~RgAb>oj_;yWR7r|w>pmhN$u0=RG=kh#)izPgyA-NO#GbwN3GXY8H_t*5^mI3= zJABqYToF%5@XlhbCzpS9NS;OMSRpF4gWUe#h4Kmm;Xn{6Ej~Qoq@M&P)IKUd*q-vk zzv|XZ3c0SsH1+;9Xs_4#s#q+o6s`Eg`+w%=AH-Oo`88J2ew`?5zYd69eG9m9(E%A8 z9AD7c9Lr}ugjLYaM2m}N3UpJnnHhRt8zGFVHa0fna2OQ3E`n<3A{3+voj`Y+pzhlgMpIVPj zy9v$3Z)%)#8b>YPgS~x(bKWhFm>Gb8k`kZPTbExMTDo+geTFW?Ya9+M=>Ds2dS|B(nRF3NOGyQ60l-HfY&6_xpJUmu# z^f#y7>B~v>xdYsMg7;p?ljP@M) z30&ej&+vA>ahz@1(If-0s{Qk$()Nk*_M$&M+V@I0x)*ew8b0s~{W>NGO*_W^q5YIX zGzXtx3bPiL5T@ZGb>EE8U7P%da{~IyJx-skn;kjn-VV!OW*ZM!m6fmVhC52j+yxV4U2@OVjBVSze%fBelI(c*2WbC1!Mbhyy z+qgj<*WyL?(+!LFCV;;LGo*|o5=)Lk|1CBnEjTQ^?L2OLTSSf!B;Tdy+}=8h=7^Ub zOCmo;ZI<#0niw@qyY8z-bMbKm;ab(UU(pTkqv4`_3k-4;&p13zAJ!ymd4=b|hZtbg zI4E)9e{(7k7pNgpOCP`8AjbnJp)gvt@hJ{`0@|2)w|n+H1F>=J#*MnJby5{*j@L2M zDSv0%_hO_;3&)CXv?IKoiXILTkjRneCuB<4~yj(;rgm>D0|Txm@;` z!v;CR^gVLP&nrBN-}3O_oqfk#_hHSI9RIm3pXk#U};zH(ES^Mzt^Wd-O z)`4Ms9sh(+l8wN3p(S@#om3?n@tvaq_RG2TFajQT1yJJYd3PKSPN2wdbZCi4Mao*b zfCtcgGVPu{eZ8EIdtW?LX~XwanaY|1@1#B0(x)-jwz*C~h0ABCoQ}7H7bcQ(?kFc- z@cDEl)Y>pg`Uvir!16J{7v7=AEk^sq&)l=S==l6&r*yy}?Czx5=lSyq4$hQm?CI(= zqJN7?uG6&ea@RVQU!?M5B}hFHjB3=#gMcyA* zYG}%|o!SIVVJB@(heZ03(XOg33Y;}P_&EFuev&+>_rr%u9uc<-)TbY*Ak{_mYyk8M zyMXyEfZHM72K=~uzAIdGlc1`R%ZC047qnVjA_2|?(2lG4%F-WRl1At;JK3?wOo8*o zGg`?lgWR4SJ(<|^CA^&rP@4j;A8_!3RRNWW|Z>biudpr;}2DXg6&ux*UL=I7fGirg4+mK7ij$4v%zfK6)IpN5yvkOd)=WM5Yh-=Q_ z4y(ZVYK8RZ@7l}p`tjtLiRQ3^!a(uTr^S8$8=I6bOT5zW!*kEgIM$N8f$FRe$U}E zN}o4Sr5v^MO5N4_!n{*!mZNHr2|K?jHexUoGj@T-qf8asyKOC=|AK^YV0H&*W3P>k zOxp$OZqhC=4rXLeSxJI`o&=FnwGZW@5c?b96Wr<*TaLB8t9`l zJ;+OajY|7hLazn=co_jNTL$Yc$3r+D+r26fS$bMGP;stMt7wY35g9J;$h!8t?7zON zx(vY`+|q0>^nKmCE%knrgp8IV({p{1hp#5pkLR}b*DU2=9+M+4EDnU)nCq8vv$wF_ ztt{3BSr5qYAUG-wL~}fiViZpkjy<`x3`QJQnqf>bZxhE?DjS#MhUPvV32PihDADo& zIXr)5EdE(*5OE$<)M2=NC7y&Yle8KV1%y-VXR+Kya{NtPX9{{I{9>Ar5?-EDR5EO1 zi85|_1UOT$*3a&Ebsej<46sXV7A%!-h)9I*|HS7Fog%0x!N{fDNr$x# z27Aaet>~Wt>!vdxbUUt$8V99S7oAj&J%@c~ZjBlCPtEmZigh%ct_2d)8g_t(ym;>y zoL#GH;5`GVceAgr1Kj3%%0wU{5%XQ337&~Fe@Ra(5RX*zz5ZHYlQ(+$wgIj-E~ zG0yGvU_~0qaBVo4mA^Dlx{J|S%_LWjYzo*ZfdQ;O6Hm#xhR9M;dx|FTs%G-+CuPEcmn~|fEdDlZNZ)J2hn2s0?4z@gzO*(F0w`Hj`I{eX7z7@|QB`|h zfwcX1?2TlAGe$K=4vtZgdIiVuDpPkb3v6?}#(Yt?-95mEQ8 z7}K0x8{cwu8Qz96t%eV|l5A(O8Vq$5Vkl}*59`ju89D<;bYxAb16(nD)Oc@f%)4?t z*@Uu6CF_C#v|6KNhv?4kI-u39%E6Tl;zgA7+csPgiQA3rKz|bZGG5Vpo0v7j?jJ~( z!}r|RvgVJ(F9km7kBS?`xXrY)D$Kqg*EE>>aiKqS!Ye9dRNDEBb90%bVoSQUhG2oE zmbMZqB@GarFi-_WU8_KbeSyc%dYfE+W#Hy4Oj=aWGzeUN1;*6^8-_tydlV2K z^*>zOS4^D}iC>L0F~BxSMHwyuvnP0V$aS$#3G$u17w<-;$_>yZzyy}G98M!s6zScB zk_cZX@}w05usur5J9hLaBBO>GyC%ofdX#z%&PvMz9!1i#fW)kHtc^JscBg7Jq5<>} ziDWMJjVP7{qB%D6Q*2yk^0PT4!U#w3#NSwRemB8Gm?qKEqGCPsB)Ru2HGl< z9M;Am8AiZ|;EXt~C>l{8`WDHFl8F>>u#rhvqZKt}8b-QExEi7rV1Y7caKNtgF_Q!J z2DM@~Vlgt>Oxj&{CfgTF#vmHrql+iwT-b@bpsMzxO(H{`s8|aL%K*o7O3DJNSRaDL zd0b_}U^X#$swNQehesXT+~PxJb43$bN%9DGt8Bcm#X#hZ6gG5kC`Hw<6ff(fns6IE*lqiMgZS0Rcj7RUW{4a zMdy?MBO>eqqd^aO+B8jTo1zB8eK2=bp?ns2CuECEo?IFN!Ae4B0a`yGOyLYRtUIo7 z83K}r$!H1|4gJ^;SK=qAoXn5|--;K=<8Xw0HpXh<~@h{6i+>DLevCPV|U5Wz2M(8v-c7EDwK1CRiQzaG;F(!!hIAFcu(Cc_}PyBSNImoX`paOeR|&X<*G5QNsf1aNi_k!+UvXxPJB z#m9dz)5Q_+P$LO#rf@3BN?W&$!`hY0k#%YYMu%2DL$J~+ixIn30IU%%@Wx&T-*p!h zy22mGF~y$ZajC?^4#*PixjMw83EXHBscv1fSa%5p{cgzb;rhEsiC{@^vU0q*LwwhP zRArKjBjrGwLSGd@DJnZz%Yf0@e_;(`o3!F)-^h^~ z0=Ph+s9Tl#kP;#dc~cALQFIrq)U`lLRud3^2d%UQnU#Ub-+5p?uzN%_pElks#RoO7 z7|f#9$=)J4%fL4&65t{(mLWN7fiF&pQ4q##aU+u4QDXbdjt0hiXke-Z^yV_Pc7YpH z4Bg%!anivQ!@xHz=l(|oMl1ouVlst|3~z9q*#qllLN>9a&_~;Vd&U$AmY`@4JjCjR z;n}3wAAw|Kt={Bi#7EvHh^!OIXv6c;2629d&CPxsJl6JVKm~b*G&>(>-6(WmfeWAR zLDHf^LY6I%*i4X#{{ktQhEid%#@&S@(`h)9rf_@pPY_C5GzvC!F*Zy49?2EfijO3RZo?}3r7uVh~;!3`Fq$xW*`RY z!0DPHl2+s2Wdd0|legms9%&pD3)#ln9G)BQ29f7|{3; z(iA3+@1oaV(qXm`cNeHuRiP+&vQsf$r<`Ftl}&M zHH~K@*#HE&&Z+lsCKBUjhfzA=IYHyQ+Pb|>#QPH@9A%8Svgc&&Os*TeDVwN#w5kO$ zNc$Y|X62ky!8%yK=J>2o78D2u+jh_zXaXOU>BB6kkh`741uA-$bZN|UnmX{30NED> z&J+c|KvyLVqCtxyUARq6hYaGo{6j#{pVosoIfg~!H)CXNs40)|%vM0VjZ?ZZ3pA{T zKT6R9BnTuRM(jO2hPeU!kND?jggl|mOvl9T0uk{tR4Q~5p@cMwIT15OancnK5D{nQ zO@WtQb*o6$^n65o0!_V{3g|71-AGsm48f^S<&Q>@=ieI+X-40Bz9N8o zHCrLwd%B0WK4*FTKcmo*W$M86;MtVBoN|8ZMDLMh3W?<2hJH?khBbLlQG0eIQc00* zXa!Ichy}qjzAl5!Ka@?DK}Rc9L6gY($`_;7j~Kz2!CQ$88BGxP|CM^~ON>Go5#9=( zZ@f>DH_ZXLRca5+SU{^w9pcVpc7RJcZxq5`O*}dL7U8$m#MxB}@AHc3h!hYpmt&Hn z200Tz5J1kV8QMs}B`WcQ{%{ZP3ly#dzD`|HrA5ZNXeI04y?k}zzp~Bi*L~{ZUJ3D@ zES`s;fmQ!+XI2*bG2f4)|JX+R8y<8B|5OOs{U8th2iX+*{0}0-Jtn%4F|2WURba=D z?GDc8Ys>{!#fC74|B_3k+)pE}mV$2vS9&xXqqtiGS5LLrN3P9S-}vB5nb$A)2Px%w z9C$?Z?st>FV5+KC)2#_pmO=b!v7XWJ=?~Z@Ycf1f+&T3(_uCz==6DC&zJOado;I%r zhR)UI%p&;?6O9b`_8!!Z4y;{x1WN@L|Jq2ykBUTB+zA^ z2nGMj3^0e>C{}?7gcGv{nJ@HUR)u+8>Rh_3SpWLepg z$)-LE$?4!7fEiJ^x)np%HhEdJk(Niw^=?ku*L=ADLBbnK!ZzgChYEfi;KAlcLpsUO zJMQ$wCN3$5`y2|-Ot)32XP$(ibWX`9zZCEIPqg%t4loTZsr8=ztYN5lGvfDb_>V8t9=b?YnT#r=MNM_VSt!q2}Xy zdJ34@QvCjtqAZ=Udd@e|o%I&h)8KVortTh~jih2k@r6CU?Y#sv+WxPyA!EcQM0 z&l2xpv7y3hb7}c+W1lXeTn{>;b(v}&_J18+c|26__aDrRk!?iT&9ze@L&+G-$j--B z-*%#uD58ceg_%*dFf_7-$?`!(p+2^3VbEfWY(vEqL-s+9==b#d?|I#OpXZ)?&bjxV zlfaYPgp zs1DEdMpL0BF)ljq!<$_&97FL-t_3`arePYV;94MjP+g!2O|VJe(`QV;bw}(){zVPJ z6xnM;Z-Fv6gXzfmfS?QIUP4;-8cN0^2IJ+RmWCIM-C+z{Hko<0KnO>PwnGUzOYz$c zr@ZC)kT{giml=f3ei?$DVZEW6DG?+hOIGTTKx!Cc;Rt0zhR6-=cx&#t_H~j z;&-ncBpfrf_|2)}WSrZ&SbX2b2 z#13>~w`8uoV+Bv$)yO_kt>Zm^tZ|}i@23k?(~G($bd2^d_skEW`rp1gWB$M@1>ebt zWj$ODS?T0J3)OsMbVUaZf#vkik(Jw1R4%5wHfme_jiP~W?H|}uqhP`07^d2lMx0V^ z_?gUA_%4(^2YYwmpVjHY{bYlmZLb9V5wCo&9L@f^gfib(@6fufz|l1LLVjFc-4Wnh z`I?IB4E)_ktq|QgF^d%&oM%xo2N_}uXxo|QR|r93mGC4$a+U!9NnTO6GQ6)l2-r*3 zmGvUE+$^GqL;)<&0LBpbcMIYdG?bE=X}$r|ea7MU%#z*TSaoZw8sd$Hd_u}%MzLfZ~ zA40oI#OqRCG_Yu8-=%dwmX(^u?~<2)$Qf+9y<6Z}h3%H8bCB)vHTnOdMWwgWqz+5l zcogqU(HL!u%*LY)mv>n(UevQ(Zq*j;`;|1jA+EV%Pei2m2O+7QmC8h~V63mX2m3Cb z`K2MoHFQIb?;^>2m)^%ZWoPPQ4>y0&_Jp}0YiSS=hG$N13HFk0mArxlryckQFGi0OA;T@ zGPl6z2>pS*aa3qntT5jK9Verq@%o`3&-RZszMOMlTqfNkF6EoL`jO*q=K@AgkM!YP(w>1(lNw>`IeX8nmPU);0~R5-8e<-_BT zkFw(U6Sv2Uq)wf4#3iyfr6^%{TMlZyRui~%6E^_#>iFq%Oga#N{+dHMuVgE2zaF+$ z-_WB7J#x<15VL4YKWrqwuD8s0N~^L0NzYdcQQIdhpBt$TROiz7|FwKd-0p^rvU067 zx6-t~pCm+IX=bJF6W*WZ2o{IBPO)Sa9R>t5S+n68TWNdnZ#bU^2Z6%>O6u8m=&e+? z9$_)*9ze=rN&OUGb4$vv^!In}?ywUI-pnr8O@4!Tp`PxTBplCgUHXdxRdd?6^BR2i zHiBmUUx`2~4r;*)ZVdKT;so`$k<*I)#!jhbur5i(VDmty#MvE!>JNHhizdO-SitK{ zen>Zo7)^@8?svQoX)G8&BBE`~u zBPj0THdxqLx%RRUN$hMF+}YikwfpZXsy_yIyk|vT0ag{6cK4gg0W`QRKaVfDlKrov zgXewK`?yyNN2n(HY3&K zUGIoI)rA=!Fk{y%-RDM%k8-Yl$sl}t6irn0$7Jb7zmpYA_p>8S@$_gm>)dG5R$L(W zJY>S-d4LItY_v_M+ot*e80jte-tH!W#ngN~(n!u$t9){wik}BM-A_K*CBM#X{Qq4VqQ`Fgrt~$L+Va;>IR&nFP~l|@v%pn z?}tO7a{4OjfLbD=bnUmN6XY9Yz6T;c#g-q2{)LQpL?#Pcsi6|4n68mymEWt zBg>6uTq2!ibbYfJGB|Mn9`^C~C2ev0$~#d>O}E`rk=Huz<=p^Xrqv|}-XDMOj(7g7uFP@LGnh$P8q(&=UWwYixXrN*Kb^SRaQkPms-A=X4V2OK zyit2=rSz$>KQQ?yj=GA-aH9BTeIB>q(Qx9N74TKS6F%K*zHen^itcT2Sr4uISxMW9 zTP>|(HQp{74CX$Z`uKaHZH%69GeAe>I;Om?JO?8+W_yyiyUR*web8mKTvbWYeJS{3Y1NgJ2u335}bY;QbirXL!eV8t( z0{jW+`0p?8#2qS=Ua#zMi!R&@(M4vwGPl!~^D&xg`(%`|FrkepZItxteZ#}P+k41v zUi<5bj&I{DxXhq@Usv}>RS%xXV80yNO_g>NOcNC=$ckWe%g2u*4ln#57HJ*R4fKU4 zwf~^%87ao;mjra*5_y1|KS(`(_P@hKU${%oA;RWi?h!xz3dx0%wWm3f=j9EIFX|)L0lhw)dk4)YKR-9NxAw@G zmiWE0v+gTB@Z(&P9%g!d@jx|-O!YdLd0}pNHyYqos`T}wO?xZZ25Cv@6v;_C`9tmNKQPm$ zU;@=>8rJ$cO!9rPs%lP<|LcW*ppe|^y>dC7^ON-0;*l<(B$!EiOW8J=thKj!+@kXi zD|y;$ojYl6SmQR?thJinX>}EF-v`ChGaXt@85a?sd(SV~6Gv;LabeRytwhEX*BYW4 zwPgX}xrp&b&e4G%o?UA-A&$i=_s0|cXHrt6icEDnx&~I(rs(mU%LdQRHR0V73_=d} zn~@fmPHXe!RAx$qtOBi7;hj$sKyrXind&j)%$XC% z8!P&`XW`XvgQ#$kCZ)ENt)b@mY|4F)_j6+}9XF1nut$o4t<}1YADy*ob)(EP&f?k&tbY_0$;^{g+n{fiiSKA*GIcN+vVG7mm& ziZ8!bHaTYYW$NWQ=Hcpd+j74kN5;>?S!zPWCyGTdN^G~>CJ2`IkP&c-7xJ8?k{7Ht z>5Pkq!DziuM^hYD40i{$Ta`eeJ_cQkyZS%^jIX2)38zkIVLzWHdNX3yP!Lwb3+d(} zoB)3#Qd{>H&KZe5bkLc?2l*Ofc%c>AA8LJ!m!?X+M7LX#c}BA-k^{!K>!>bTW+tP~`$JLLSx z&u$RaV$k)r`Y6P9oU%Run+pB+5`XaWC||FJ=Nwhq#CHg(zD%`P_{Pm^nVnLgk*>1J z{x{^nnPeI6c0Bwv`d5Nz;_8R-LjmfcCXt}6MkBJPLOcT0MGRyV`Tzd<_W-Rh-Zk)R z`;ui;yZL50b|DK_p*`a`)gI7O7~ZozZ_CRm+&6qL9Xo!kO*~xUX$r_cuCkEN;)uj`mfzU%maze)IQH z@GoILjd0+99k}xVdR0U=Fp7~4vQ zj`n;j+zy{3tA?SlVyT+mVy1>fp_n}-0ai#$PAO62a11&VvWGLPDAbJ>Msc4fLsCn@ zwS)&Tx-(I5>RT5V_|yJT5{o&K}9cJ=fYP;{O-M}++k~O z?P*&ZsJh(LMCtnK6-;>5)fut0S&CoW+4f=T1z@5vol`Dc0a$+hFuwh`iZf$55X$u| z?|4p!GIA%8M6AF1caKKbkvSJ1oYbD8t51ZPx9EGrWC;BTfm9-$kMTWP{&kG_$x|q} z(1UK+5&B+I42t@1m!334@xz1ECupk{M4ommy1Y9NV7?}~v< z%Rw>S3Vp5zDK&|eu-%prqcx7`9YDr08j|`T>)7K`XmUH+lPv|Ac*`&z^?BGTvmgS& zTn&0O_){TWhH{Co6oJ$Xq*Sx%C>>K(q9h+uXJ&zDv-r>6O!)jH z`2$kWTcCECU?L?G!hjvxU=+hmQeaepnpa3oHlzJ_zMrUE&X$Y+lWTZ;(MErlpbT?u zQGc6v!l$wqPFso_Uw-tal;>R7{J?qS-wIPr#hs+}h_y$}c*kBSft8QIl1qh>X8$g^^L%>u)!p^6@c>D2tNvkP5Qo zK{!9EekCC!#zN>An?dipJaLO?0s9_pLS82m`*SSslTq eD(}QWEQTE+q!sBuf&QM5JaDlRAy3Er8T~(4&dUG* literal 0 HcmV?d00001 diff --git a/docs/source/_static/tasks/manipulation/openarm_uni_lift.jpg b/docs/source/_static/tasks/manipulation/openarm_uni_lift.jpg new file mode 100644 index 0000000000000000000000000000000000000000..b7bb7c3cecf953e583fb954bee151a1d76535966 GIT binary patch literal 40923 zcmb5VcQjl7A3vT5N$gR3rbQ{GHnCH+SM1tVRP7O?RuM|8cI_ImgVIWE>Rr^Xy=vDU zwW_v`@Adhf?>WDJf0yGVxhHvDue@H*=VRS}-~N3E(P*h@s)4{@5C{zXfd0*aR6r1- z>*M+_1UQJH#McKL3MGM(!pX=;;iRNw6x0-Ci^H<-)9gl9Na-v2LaQ9h-kqOTJXOwAWjg72uuRLzTW?L zfQcZ)Bv2TflngkpMFRpxCL$pshLDgzNr<2jFzEU`E%YXgP84Nu!w!DSJAz&;nc==+ zK@BOlO8Y2}xY1)DEF*79;WCpwvxMXW%;B4{pTK9a1H%9VLH<93{lBq*v$C|nCj-x+ zAaW?||6U82mIxwBOmY(nqeB^Z-=M#B-_R~1xuB+K&Vm-lb!R4+fzCsx%p3&DFHXoT{A zJZ8hy;a94r5Oy`_(bYgCu}fXQ_DIu z$Kj^#X$<0|W%$vEDfQFlur7R08`J1?IF`h&fTao!88iE%fVOLzD|rd|`12^gK=rYn zIy%B>hL{vN17b&u92CL^_aiV|H$gTb)T2aw3LV6OH6QDhql5o}jKRGeXkiBmnKNDp z%mKv15eu~mP9>iRP>zTnu{N;qkY*wFHTLJ?_<2)7{G4cJWv39L$eZqj1z|!x8S9-V!S(D_{gg-39d@cWT{zs%3bu_`h$QU|DO`X`e}Mtfd}RwKDKFGr5lx z*s-sQX*JQICJr5Opu#Wj?cr>WJGY($nB#3D^5sitb++8)0@yF@%?x@seX;MavJ|uA z=$V77BPP?mY)zizj-IBA4t1WvtDbAD$9E;#IkVB+hp#2zxx`3vaL87A@+=6|3~@vU zDda@?*E+H08JzJx6t0{gk9bG|PLd_2&P1rLwxeKL^T+%w_)c#&4Mi=okYS~)%@dSO zUY_|p3%v&>@sSwX?X->E<#pwQcMX}hlvebX*_5wv0}X1<ex$0WAho*tO81Gyt4(j; zv8J^%?|y+~ACj*Tm~|rICAjb%VTM||S6dYhulD8{8>86vUcWx$Uv~e`$f(PwSdLcE z=er_4ZX(-0rg@ReR&QRl`NP4Mmb!3=fW)AB=Yo2fm94>pZM(g@w&EIB{F3U}aV%UB zu6j3b8AL{Gy$snk!9?Y$lt{Wv=r{~@&Po8b`j9O@$-5W{25#Col-cZh$E{`KrPoHJfOia~xdX{amKp=Vw{ST+h z-c?q5hw45^kvS3e77$36Uk2Bsi4)Vj1c`S1n2Tsqm)Rj}EEh zjf-x@omnH{fyKBsD$Bv*k+1t7ji@seHS}VPotCd$nO!8-7xS9M#F%YZf1ch^t*eYr z|KS=|W~(A$v+uD~ky=Tl1r^_q_+wGsNvPM19J$XVP98 zsJxG^@%oPumes%NBHwvu1?2*s4=XVm2 zHFx!)VLVaEn0{mBozzs2tdZWx+}wzUJ@uOt{`kjx@9KDec1@Gl9zm{Jzepd$--#C| z_wcU$L9+nWgT0rQm#80vc*YAN0wwYiFQ*+J(5VW3TOO(Xj$82EWT+!at187O*G+ul zpkICKS&pj19FE(5%;2i2rs9O%6eu0EH#p2UFwfj+mXc~t+UJSd^elW)`wExN#HiKL zA%%#$RnC#b0;jTzf;S?N_47F7**uOs7J}rz-RqFno?J8Ry#?w+)mZvco>mnGy?m=q zx|D|*XaJV9!#|MYRxoIzah|71Z|QKE`N?y<(9W|MdC}}(hPFJcaCkI!H`K7-RdQPE zDz4O}zlqm-K0_vr!THTPq_@WyB+~(E*^0n~(y*K=L!w|(AqX0h9ylMRiK^U})JeJr z%Of>k=-Gr|H1Can#s>WZ>9ujb_$YBBv7$b;?Z#8N(=m0)(vqcCsQvH-pC;o;j(k%z z>uXgVCb($QR-Slbp@IA3>S#i&5rc_*awA9Q+ZPNTnsDwxEY|&*93t@0D z*W$Atvn|=BQvRC_M%1auD)uk@$UVRA`enJYcNOX8oIct)S^{&N>yYhc2tOT^M*c$C zsZseAKa~SabXNlvh)LO;m6KS6q?LT0oplep~bnE5P*sB#y#Y}kg z+%Sdj{^^{8?&6cF7z%?*1G6@Uq+{tvV5^Z;j#JNkL%D8MQ%ykV3zkHiC9ID=B zJ8>Qa`UnY$Xb!{z7${uXjfQ=3iwI3ZG#mwIM}*ATfxkwq6Y+vLuvoX;U8L(v?qb$MWnPdJavJ4VqR`q=h%cB6wLMj>)gGOm$UYVp}3Z3T7t3u(!!&ML{W-P3z>h?Z>}4( zT7DpHcEkGNS>!i%>QQYA`?%s0IQQ3xHH29B2Aq2+0&|5hSME%p(as`PNz#7HPl1ha z1P?bu^5OTMdYrKZe@XRAxxd`F?hTg;^0=ibe?RY!TUnzB1yd7FiOacH zvClPkf%~n$(@ri_cC+(G7q`wtL|W1b^^4DIp>%0g+WPX;LfO)_kyv;K7I_mwwE#{D zB4#Kk&MsI^R@;<0h44ZTN*i^vN~ds=MNvuD*xy zUurieoH_kbl>?gc`gc>9Bs=j!?Wh(T8P|Z~%xuQL!hBq*-C|*?XhW~JCdOb%YYAVG zvy_tMaO$=#i<4QSm?_4X#S@jv4bO-CmdW`fUCOy%tRokYitbGZ}JlSs@bO z!R^xWQ3qqSMDO%lrp+|*gMq~aq0NbDP%v+GqH&#A(F*Z^7>-Ed?uQ_i9S~N%wET?T z3*a1}VcuGUbNRxgn;}^MSilg21As@sn!e0LW!Jb0p5|o{EQRU5K-ZfF^d}Ho>3?r; z#~YD9t*gqud6WIWSMiO=ql!D$GAL9~#N?&$9;K1~*PEEON4T+yXPAm|m;WdgDok5s z`j|a;VtYFas_H-Ao(O2Pdph66GLT59jk#StR)4qW@dqhQwz0qlCF2@wlWXwaNM6u% zcjstw4)~HcwWG~Up=*feO%t!Gk?;aI6{NUDafJ(6+~N{JaeDfaXMt0pX!$Fg7|mTA zB$gD0KoTMlG$LN%DE7EbUlu`+q81A)4i(G05C4q#C_SjD9rvbMvT4^Xzl)xLQLq%U zS6@~-YrP-4)J9W>hr4|j&@61U~}b`vs9-d2d9I-8YQG%TZ!_M=iB{V#km#;^H94zy+AiL3%o^WGcqJ%2LZdt;=v1`E8 z+Fa$vb9?51A(N;lE{!dvwK=vCW2ZmS8*wZS3ZWyelk#Q-6H)Eug}L$m?LTFX5(yN# zHnD_7Fn&DXo1^g3Sn@X?O2fU9gY;L_D_gu2f29(hRXhjE@7(|gq*ny5p83t73Ugcj=)HlJYltkS@xTLTJl7+TC zbGJ-=b-~QL`Vp2w|4vHv9`1R*)- zcQNeajof4c;fh;aQgS$}8Rb{Xjzk-0%8nqQef6T)abn^9U}DX~2!sPp7U%BFfA5Y^ zU0NbVX<3Ro=b#7Lo$)WbwPT#Il?$RE%0s8Ry`wh$Q}DCkGFGv(g^IUxGEc$=p^E># zGBam(-ZMTNxi3Zes_2gW!>VRev(`Q{1Dg-j}SCh&y4ml3UK zA4RT^r04)|f&k#1JdvOH&3D8%iN8@3veEv8Sgei8)xHN2)f-f&5MK#`VYXwNt@!CM zuE*gIgKF+loUbW9-*eReS$XDC#*`O(7fhzr<@MmHy-;_vxeun_x?!t8#{kn@n1LiA zUMF0}+T*msSx`@{ra5N<{=wdvNs}%v)cRE6LD(->XI$=r!)v>I0=}Vq zx!|3Bg)cyU2#SSb-#O_mU8c!7#wKsZHb+10-O<)lGG-*fGos~p!{MA>;Xoe)q?ca= zVlALvr&9BS4t%KZ%t+@rJoh)o3=690|X8x&Kg(NHZ*k|*+y{(+7nbtf!1 zR~-X`Z~1;W4OVwxZOPo&6zUv@TeYw?VTNYlCL1Vuk{bz15YjHv1e(!$YbN4hY_d)r4E8I%0l=Wtfer!Z& zm+bt=AnZhs$!wqp{U?Pq;uRxi%V3ZO+3?R?>j4?V)N6 zX*UV0a`dwdQk$pEFQi~BT(x#cZjRA0=<+OufCoLl-lxJ?hX4gsY-*}c@YSD9y25vH zSqfN^i|=$;P@s_>R~2ZjWbR3(SEdf#u>%G1_nqo?>rB>OkkT$fznjswCRb-M+SI)3n$ zK1*jIw_0c?fu58-OE{bwwOOV6^4xGmOxc7*aPig0rR~8UeZ8T81P^62=5=m*+qh^f z0rrujcShBIAqk5F78(^$Ca+f=2EcHRkR>>@X4uQsLQ^3e^})jTc2V>4Pqd;;;(5yN zs-6XYH@DGQi_fEye-HbLA-DMx?$>EHr>V8oT0FEH_ka4(J3_Eq>*17ebMsX|z?Gx# zi?TBdFQt_9cPhmjNac_Da7M2PC!i?=tSlB+!M@XGP_{ zKeE65;E>?9XOH0~D+()_l2@2cCUaNyOo**o<*Woj_>IV)e@{aJ9qsX_v_tl$Drc4s zDpw3)e)oh5+m`S!he~8)S=GLeyBZDJbfD(zhmt|~iO`4;ocKIFH9sqPww#}%FIK=M zpf&dc)G%cMqI3AB)Zl#B@!B7?0lIKcZuEM&~~RN zDA}6o7V(NiRW_QK$@iIv7kkTPu;UFEhE>)1DR4BP<^KVwM1BBOfl+s_5O#~b_wb$p zg7#lhO;XgXTBA@xEBuLmzBz19=KD$FuhqX6*1TwOzr2)YjgF!YU*Kpi+)FkWz91- z#AX0nm-`S#!D=WtcWt-uo%Sn!?o?{-ei8r+viE}ifqYq96^k2ZO6d$I8YMX9a$|XA zC0mTQ_sn$e+@tMbA7b867@l;2{#V}UYN9o6{`6TMXKPVKs)R+X^Y)tP*N$mvynq0f zBnjX};tK#q8(HyAz>A#@-oXp6J%=s`W(T##Nra9?kL!01SXYZGmj2gC3%SiaPu>(I4l%i>PHCn`BPzSNc#Q@;tzb*=)aJek6aD1OwioTB?$t2B zbf;U}A8nU2wur|^e!~U!!oDH}5-*4HU zxwVD$y5zR(>K|W2{(+7$m@pm|U4?em-hZIkI!7a+(T@RQDlyb}6PEr@j-9zAT+6%0 z?$wn~dn(kF`H_FiR)z{DR7YbQ+QD1h>=eB5qQ3@2g;UJr^LbU3n}~qg8jKJJYV4^p z;d&OF763r}s~HT6h+GEe`-B51m}4J{S~!Xnb)L+ayF(P)rab(ePv{Sgn}IjcAm&R@ zb`O2=u48Bx?cdW8UTo6XD)15&Cd1 zR*ln40xKIiLn2QT{(oWkkRDn$xoJ(Zs*hi4P!hMF5ktyr7fsbV#F19)F209>_Bo#74~sp0o z@98J)5nT1cu%l3o+a8GdDjuULxv8>kY!He2oyJLvs^Pb+lE*HUK3DNig z?RIa|*H+DYoqxoTLiK0!6>NV6yJt@O-9*h4Z||^9u?DFV67rcTUfO$Bq)TeWHpgaU z@udxW?^yZ77E=3C^We-oApEzqATs;m06-)F-4zST1lHwsXZVFM2S9c+$(eEzXdTi| zjI~-r^v_5N&32&$gz8f6f5#lPJbtBDWWTDa(9Jk^@}gO`UdAUYFo5j!Tnwee6GGgy zvs|&4&hp?E^7HeTmTz|y*>{Ab&a#`;n{SSOcc8(I3unl=C)czc*pl4feP+)g-Wiw^ zOwG3y+uO`oFLK)0_f-rT#MMkD!SKOgzPz*<{Z}~sPUgk-z#s9uj}o55#Lp!s=k+Rh z<7Cb{V_n&HLqx_UX8i+;p5n_8q{x=m|92`aWu_=j^xH;nPg7Z4B+wg0{%|Jxy=6tQR4BAEdk5GY37+;yij0c0z60GopBwHE1 z;DxS2N(w7;Gg0?J6d^m;Z?SpxW;&rl(<Zc3Rc{@6|U@X&5%eIw{Gb-69d#( z2AJejazF?Gx)!iXukmm{v3?XeFR(<{E|du&II;izzHv}Q+s?iBJMDWg;b*A!J02I}H2AzSMlp*RNn`H|m`!8BGyDHZ%oz%Dce{``^-Xg5n z5k=p-&`Fs2a?YaoZGpty^AP#G>eZPpuenEYIihL8Gi~v0VsuVO*+nQ#V8+8OcN3f^ z-M2dT?7{_e#@__$w7uO88MozqQWUTV|A$q3sXVXwWF|l)VSoh$FuZG~z|36;XbUi) z*U-SPJ0*2~2Wh8~q}-RJ{_}Y`K&YQ}XV;jJI;|&rWo`-c*O|`=HK}#4Hz@R**ek7U zkX6|}k z!xnF%NF76|`YRhm#4v44lAcvS_tO2yo18_3RVA_Y*^kaQAEijw?rtO}q1{;7bX^m8 zt@0m_G}|l(58qqKq85MTifO1s+uFYMEpMt}-Z!S^->W0OM`uV=1GVY~ zr?m4WJ(tpRL?f?Bd#(Wm{UmiIVSaX-pYK^`k1(<*%;U+L=R8eF1@Z|%4%JiPT)aU4 zfGBQ(uICI;9jbj_2-e|wIcE(JuVIazFgom$sN62hTU=zo3**o<10e(vlEu@&hWc?&Nw z8med^#G@$Me#lz@iX2{l^WekqJ~Z2fv2iTvZ7&BM%zQ97mE}q=d?Mp9g|Qm{Ro}gS zqT2Ksw!-7w2&}G3pc^6nt9L4G#>;d|ab3l?HD5$Oq^{@6@*XwsJ3{!?Ml3rS4Rwvn;ocHCMk9ep`+yy1T(=&T#N zU0nOOx=eD)*_?fd<@2v&O?8Pj=irhQGqDOfR_aZN;~n=X?$qQ|!{G%YULxfi`w2uyHj5(2G34-FmppJd7cXA)6vhZCXi;+_)2*>P12@`>DTkcA$|1#Z?&HbDRD zGVhhq9KMJHmBaKrQlNXPw!#l0S#C(s!d#DjOIJMHgB-q`_Zl92c4m{kx;lOINxwS*MrU*u}|`!nzW`*Gm?wla)#=Ra&S{x=!hu7Z$j{O5+t4 ze<^@$)Yh~VSAVY^5HqTX%sgDa40{mq{jcX5-dvG}9Z*DJfO4A%IG`*5ZxeQa0k!Sz z3~^^GE)ZBX04TV|1qd;$E_)9fuGi9SavB*Wk%Zjm`+yodKBL0#B}*-brA2Z{3nmO0 zr%S@<_}#0deozRlKkAY5C$m6Sjh&eLr4E=0=4cMBt7RVfL^ySj)}5o?)bGgE6)Yb! zjH^cGz}zo+;|XtG?Y^^rG$EBK$Trd{0TX=M9GZx7@yEx`)NHwMLYU>bk~$$JH!<6+U^8{d{EWFFxwD$jWv~> z4S0>7X|eg;qpV8b>e4Iy)CFN{vWE{}2L|4lJ^h5_Dk-aq&ogMi|C~P226pC43+!e( z*>GofkeE=a=|@SO@y0giT<*jGc3jCw@WhbbZZP8ils8k0;333tPN$jGkndT({q6RG#5hk`@f>)3U@=R9M8C>lk%x$hgN) z@K<7z(02i89TyAAxvndYL`ufAO2!nSXbB30Ln@Gg0I~xBL`V{0*J~%x)%OvAR z&s+zam&gSxN&>`lMcCHZ`1~Wy9bq~j>iNI{ z!|qWSjl`ejLJkxA===UB_8!Z|CjUU~myAFEPP(>{JsUQa-=|(6dBH_qaqB6*ZT@@V zOONFwt5g6c|NM;{w@*)aIq$-9bujOA3HXQ4a)T;eaRm;(UdNPizGM$4cJ?LH-k%6m z@Fe%N*G zKkWC<8in{NrcL|i6}!iOq-|S8R3rqJ*HZQmaIeKjKa|Bv8>Y{u#);<0Ji5Z;Z$yz} zMnM*9IU5f_aiWSjZ4sjPCeooh#IB;1}o@YnS;_n44JnZYLPh>jZH#)!DI~7m>cUpwr08(4zIKhKdM{$3cs!=L{GZDRHe5MkU7CDh6U~;dCquIp%s#Pd873fxu}YJ^;fFR zX{}?E(-Q=^J=ZUVHSlExGK2E3@Lx`urizVGcEuH4j@e)295*9UCu!^UoI79hB*)ud z{@qp#;+Ng6y79&QDCd~R$(P3UN7MY0n#gGQG}Bu0@h)}%ZH=$}l(35b(RYk5Uot|% ze3<9IJ8eaFTP$`yS``|rG#y=RZ!}HXR6CxWYN(s3Ds&t#OL00qFPJEer%34Ke6$bd{jh-nF+)qeQe zDL?O5fVf3OM%}R2P5`0uYPJQ_PEC8XX({)Qq{zlBOJ{xSb4F`d>bC`XbBmDvBGjX_ z?{?bwCMIEq=AWZ!KX~mJIbtqjXJZ?(1b8s>dYXI!0{LRZS|mV*hZq+KINZ?tP^`+e z_x%7H5o2F)lVm+~W7Q{Vz})<9@r5_)iG%k(mba(rf5JzS@MEBHf7}n}0X%bxYqQS$ zO!*=Ss0V<_v5&U4-1kfGi#qnBj_+(ojn($tcvKxY7glYYq~=0v^^#zr}V;t=3jW`TRUbf|Qmif79T%IDW2*;P410dYCA{+{8ifTs0E92k(Le~mNpw7Y5;cx!trv2s; zM$JzB3J4{Bk1ff?TZeNRKlOEtokQ)M6Y3Li7-^-uNv+S#xt}d0a=g4`kBj1xRzy5! zJ#m6mdsO%)G&{#;z2>iWf9jg8(Hr|@b3KV7E-|gWwKKy%_U_*7IM#Qb;jQ+B*G6fm zpJ1Nq_E@5BabJ34$P7rFa(%s>TVcef?Mb+%SI;E0p}cM(M)$t8iD{3P`T(1r)$?AY zUnP3_N4zbATh-mtlD-7_-O;rx+)mhQ`&-~S5RFF&>-R3DZa&ItDZ!KN(@&ZOKQ;>p z)6p2!^FaNIn_0P5L(fBKe8iUuBmXjDDMxUFvH+CO$sK=2?E|m4-TCkSUrn) ze?U98C$)h=_5}3*x_BJ_$>xkBQvH}1cb@gr=qJmU|6(~Tg^Su`gP*)D#=Lc?A*gJR zx98>~wl1td!u|@;ATW${{4&vSt8!fmHy+?JU_BI#;$biz%UlB%6W4el^#|LTxu35q z6mM2Z>r#JVeOfXh>z^%lKc@psqmugW9(#6sk4o|sTv!q{LX4+ znUb)TG#EN<@M!rx&9c}WUu;78s(cIODEonlmy>}xd1-Of#Aj)$#L#35N>xfnwy%C7 z$OJZaAf(3C23P)-x5a}+B9&qE6!{Ktc6OXO2?Pdbz6k-H^55eZnhYR)%OD{f$Oi$# zw8rJdD2ND`D$ENPN|P>G^=c>Y?^-<0ox0-D@r`31Q2SiiF42Osk>h@vQ@86E zH&{xl@Q4T8o>rkj#94QC_PEWSRMZ%0m#w&&ey8x=b49`g^`tnW@5g>+sw;M!%Znw& zfJnVTi1C9~v(YKbI^M|BNSA%dq2wAB{a+EiV*5_M93H*E59l5r(%2~I*_S-kiR>#pG;r$Bd zhh_;v;R$+5uF_sU{O?PV_FohI$i)kr)yW=sF(WLHg6Zt*=uX&8fA!knZA^UtGPUEzg=@y4V%TW2q zkZz^I`$%=JzXH#+5BJ=MYFeKQUm3CZwY8&Ox$Z2CHYO@@YtH3<^R#K~C|XbCI3NC! z|4PV&s%*u$s;GYC#ucBQk(RaQed>e%{_>Q$wIt?@|u}#4WM< z=*T6d8J5BycTN&oCyBVv1q9uN8V6>^HMxt|&pPdwcI5GjZ}smQf9Nxik9Y8v__Xi+ z*;ToZ7uKJE2vOY$d%0lytZiCFU$=C(L7?(^F822FP$_j!<;}iAM ze0L=Fj6S!dG5a~j@4YLN!*(`P*<%P+LPpFLphHNfp8aL-q-j~dBz zQ7eOYOH#+y@F`|Yt!rrv`f@<@=m-FhoS`GcII$pH2mo~f0DYaAXvICc&Lv@hri9`F za5Z2=@fDJ!f^PzL&Hr2)g6ul5;evYCgbrFxyn zZ^B4F%-eb`mr>arZ?7iQmq&I7nBlv&|K7BbdHepIg}_Tz7t7obv_g&B1FM<9xlWbD z8NDQrV`}=kfqm)75+OP%HeDRqvx3)0pZ1uA6}?BO9T{GZ{u02$|+(1)xJRP`^K4WC~wO*Z$`wb5aGKWYq zF4+6z*CpiIX$=XSlzlE69JxpT{+%Q5L*5k8w@pnR?21;)FuC)r$<#19+nJNF6-vrd zmw-Oyfre$3i#TyZ6R^~u*+osN5MnO2<@lpkbvEssAP|1$-Q}$VA1_Q1&4)7|%F{tW zNXm*coz|Gy^jOVjhJ8cyxCn(oAcdvRJ8^L2-Z0wO^ixmH_k4cY#E$3HxRKwsMbl>$ zmT9^i*pyNX1BqZ+y0h(#B8Nwm(b|1|2=_@%PW%KH`+p4V8iZWIGWYaqHp?<$uG*sb zvH1o4nRh3oZVvIUBT>WaHx0Tf-c40XOfqQ=yfB&iWvsokpF#Td#Dr?!>dYZxm&Uol z^_Y?`9Tm4)LFv+f?)G8bO=YaTul;7pggdOcjJ-#xb-x`ps~_?AhGvISOeG~@S@qoY z(_!-k#x=JRp7nl!*d&=lA46?sjdq z#q?FmD}BZuo`ZDS8rKG9)6sE$$!Ti8U83|0O-cooZsZ|!+a{8-{22?Sv2fKmLtLI1 zG7_}_yWP4ix1OM`YN^f*(G#;s6#?21)r=}&dJ>^IPElC|=eH$0PYBsCn$>9l@Romj z7UnemA@;{aoNu^OTF;{j(b=L{8iVdja&Cw>;NHwwb+>Js`(%wz^lvuJrD&xaPB)m) zC#h#a`VIk8GyK|1?I+0{5kbRt0Jj~nmn60Z6C+8%nsWe_fOH2u1L)QK#6Z{7MA2yh z1_2O1q#S_*y%ZqQQRF;04Q55Oe0W3#S2IP`TSKeeU-cF)F(5fdOLgP%%fI9J@-Bw; zcxrAIe`ym&i?`7d(@@qQcU%eL(WR?zt$f$J7eo_W0>PYW^d)s&Z#8V*r$`CNlGSLbU`T8S02Iz%Px(Pcc>~m;ub+et> zc9jPgALSx%Mbl{KXnqD!m1q~{vd$bjceAzSF}1|2l5m8g?4sukL~r=W>~FRledO?N zy4o$7(QEHGh|X1LFA{$L-wyShMFp9&D!p-0dR~IM=pYa0dw)_EnIGfLDb;pm`w8z- z)HPNdHhDIyeeg3}>_#1{g6jM%JjalJN~z5%Uyf4s2ea?HHK^dluXCucUQzxbMPczP zdf9j?&t0t#;x+f2^b0Bd_k`0YBn?!aR(QSVo^rTxe}e{f;dRijr>^W1IeAP!)rNTb ztT-ETZaD~!eU`A^y1SMfGtX&vihde$W7%;da@q6cZ@SiB+AIlYp18EKz&jO>!frw; z^~D!z_9ItTZ)eB4#St`y;0mZi{IHShK#7FSTk9F(t=m(x`zv#Ld3E!`X`U=J2A?l% z2l9#~*eNe_lWgZ}ts}J>Sbvy3xXM&g$opz;CZT@*B!^2)e2&sL!Fk9+7BSoC`8oFQ z9Vu(GbEX-IRj%#vPWEWc9i%^Rb(qm_z0WLsX*f4X{Wpo{xg)7!hUQzUY@m(YA)Zg? z99FAMsPf^8z_*rxDMqi@Ey?xwzsQDFP#J_xX1G=veGzMvmH{EYunKme`>44q$YX`% zeDG<>@Z7JzB9aNz7QbmjWP7^y`9`0Q6uV`cX?)5c|F}3`U+smV=e+Rh&k49OujTpSd?|rvpL!Zcta2YLT<|@hY z{+kZe8+^&zmyyQSOb1ST10_gOP^w|0!QJ?yyz)ua?g**_ZmkgGZh zV47&E$%}^(GPXWUv#;n``4}5sdm^etK=|quNXX29LSso%XxO{1Gs1zuiyg4MF2G`j zYQeq&(letL#A6+t6afS|>7ne%a;CYt+83(0;I38h~$){Sd(QzZK9LF}K*$Z_<2wnz;!GYye{ znw=}h5z0_%Z?1)$cMOx;e9DHEh0NPM>G#T2FBiHreA!j%_L+u?llh$=JNZM`J^kQ3 zjUO)SuHp%3uj=j}xm23?3ZRjJl|2n=e`AKW_vghsT)>=wc98*P>?s6_2_W^J0u?rD^uk3i?=?|o^sA| zxLv(~NRr82qR;(X@Oka(14 zVg6Jx@BtIc!vpgn-XY$#nm9W32%`T(6MinFGT*6z7FE_q;%YaFz4*fxWz&u#C|uL`SVQG z)6b}(^DDoGZ^sX+9o!hENlAF9AXMvepO%zI6U*W9pG^F-j;o4<<%AD3!}z2G(xL zMI__sIWon+BI*7pZ`EwzleK-ef+oij8#H333XB^1E7ium^x1=n%_ApMvs%*GufCm} zdhkX9aT<>wWqg_aZ`HOfMgOe@anAIbPR|pa$$Ph5%IAF?v*wz<{4rtq?yrn^aDJT! z0DJF;5B1V0_HuR+XKGugr@&D)&U?0D1Y?30>x>2XH!g?avB8qB84VZS*%De<7gWVf zvfiW_@sZ<3(T_z}_gl=HJFMQ5cQK2%MqSCRJRE4{M%vj&u_jSomC04U?wnYKN;ej|Vase>1Jph*-qU;f|h7$+w8ao2Al$=|{L_mSfM&{D5s`K_yRsL_YNOG0@t+|xs@i&!s8T;}NfSbBo?LixV!9nOb*6NY)p8T_ z46J(F_34RFg20YC24zX^5SKT@@&|?XS`^rNb#UtXf}qwYllP1xu@9kiZ%!_B!Ypau z*AR_fsNfA=E|2Td*;=Ss7^1$~B^r}BVqR{9arRPxn@Q`c{Rf@B6+j&5Cmcn7ai-<> zJ~~_0`foLa8f~r7N(2gXGoPWpDbl(7r8Os<`6lF(sQKo2YFV62? zSh8>y_5PKQ$gOE}NB@fBf+;P=OzvnsT;cO(kVsS-T!!5rSE8Jy>;I(RP{w}@yJCy0%hZnLjj`~>ndd zhgTPl_4)TeyF7t?K;(`!^0ho>h;2X8yG~)WV}y#vL6}Ku)CdFf2ptKwzY=Zaq8tm( z=c?mCCLfRWxz$K6rM>St`xTr7f22V8d;U2T(zdu4ReaHeh*%+ajWElM zG@H(;Fq=0OmnrsHxl1uix0hICp34wysfzuC-XJzp7CU&V7nw6TTUoU)YCNtG#nDb? z;A-=hBUyt6&2kvN0Ngj&&QFmF<|hU?F3>>p9bh8Lr~Jg!GRjW7yU5aLt7SD_)k z-rT$(G9aL$MFOO`-p&y917XDLWEVM*P1wikCh`Hd!&Nc(jls8Z!Sk#2M76Stso(wf z_xg-%mO4=rO{;8t4}AHBtfZFbZ=R%dnHjd{xCQ7H<$9YX29VxOGp!PbmoU&O-cIK< z{68F>Wn9y57siLwkd~0xUk=UnHyzK7{Kg_PsG2n$uo(o4_uv1Cp|0v$#6M{#pk)v-ItzI(Ab zWnyaiPK~xpe3^?;!smv$V|q(TDx~7GjGpR-bCK%|ojwVye$_-7A>mAS2J^X=9fqcM zk=mUT{FO(wkMLrLE7-|yR6}Br1*qoF5qwz1bEH!#29=YsYr7s`Xn1|PGso)jJnh08 zn?Qd!FmZ;k<+V`Kcisu9xt2y!aED?aE^8A6VeKd^F2eOYWxobpqBjl8KGa{kSPOzz z5}UiQA)PH$5--P+NpQypZU{Gmd&AL&Va_c#^4BB8j~A0ZW<_8R7joFXS&=2iypK0v z{=)ovWZnFSeXNpB@Ho#t{Dpat$e+KKDi+H~ZRs~IYFKz9qQVyQs#6q3h8HivBSd=oeGJ=PdNLEXr}g>_64rEXAvpbw zS;+qmnN(Si*cJ+(+=&8!KTzK@TXukvrY}bBpwb5|shhox8EIcW^&Na(O&0H85%SZg z?0i?L5U1bu_&EMw^pr)`sM$P$&4!aX%ex9k$Xwl zr!-~y^8qw2m!s{O%(gg|X>$wiZwb^o_a=h3l!+{3mrF7a*Jz2*b2Y!{mq@bGPVL0_NKUQ1_pRQk97&W4Yc~gjW!%z4|INnD}du9We0f%oc;) zs5IYb&X<%Pil`baFf#A#uq$t3HKLQh>KLiH-zlc9q*$=>QbL4ncBr$BUb@xtsA4G1 zvE-6^`z%$DWU6`u?H+82drgZ%sx}L7NgttfR!<^%rDqb1=>HnJ$bC`)J5kx=T^2wOE&^LWYKiY;R5oku*j&EArarg9v8BWBxCsK(6}R$LTPZZcZ9 z?o$_a_PI+~y4kb?F+}88q<^N&785Tx(dPy5M*j-)6+Y(K)F{XT`oF=C0lOcTLP6Oi29a zX(-@BxZyt#%(fLaDa)=j-kjpz6B!Bck%;u`Z`YhTIFQy+OW>3)1V_oYYDVmx)JHW^(#V zgv?RtGGUmGE${O(yIWdZ^}e4sAZ=Q{Xfbx9941bv&iEtESz2ni#G_$YJ1$z-w$*?_ z^couOc=V~)yS0JSOG_k)U%cb-|sZ3i`&y5_#9;Rj&)uL=93>`T@$o0;= z>)zAOFC`C@NCXmO2780Az5HRnEi^>FQq!=5qJGISftMrhu&S-PN`^{y-fy7-4_?EHy9rBVT z;*cck{TQ7$rI*F)N_z6vf;vVP7Sberj5mMz@KfreEgEE`WBq2`{l2Y&`5cF+mUb-B zjm4>za(?Jz=Tpc1{q6FPcOB*RRIPGGgtX^bmgXwd1Am0RA9!OdyTMsSS>7!p;-_F= zoD~rmjqQGs6;ZKiSZSB@PM}j~c%|F_VoO^7OEU{GoXUN+ETwibS%!b3FKeJ}Va^Lt zWFoXWFr~IYokZPI*cNxTA9BB$N}&M{Fd_WuW)Me+@DGTQBPurMq3+GS%n&{Y@A;n& z-{g!+4BQ<ah4{3Qs>fq5 zDtCHpkhUpz4$3RiEr@9288$iCef$9Xz^l;WYC>-LsJD5eB=xBYr~6M1qxv<3q}yLw$Pc}P5N%WA^I7e;5j#vBQSlo#dUT0&e0-ToVwnxx zZ^sX7pBXO)iAn-aAVp&8C2IzMiI1fcuZq^-WZHV+eo@e$7K7IdIgdZRWLu3J={;Pp zPZl2#XU|+Eyr&62Mr@ky>@8(1hqci9sHP;~5PN zPbG7Mx9*Y+g3iNz{_gg~?SI!e($-UjdO5zpxqHAZop6z>#H*`}M+wmNH`j2xCR2i> zEwNPl?8Fc80-|o+`#z|nNJ{iwEhoLf%GqKxCG(viZ?}v}PN;M&Tgz{idHfzH3LjcL z?;aT-8P}M;LQ5y$n?MH1Dkkp=OJZ~V@iha^n^#9+@kl^g9*8NoSV936Ag{@YquN-b zNaHc7cZ#b~+!$te>HhPf-oA!a3$F*gJAKmc zC+Nu^zp!;IHTQi^B!ynN{A@V?G+wM(n?VEa%Pmkz?lI_ghMZSa`lnSZgytuvMZgB>2EzK>Pdf!$c{DK@kF2sLS@0uJ- z14ICbjwkYi$FYW3*g9F*9hy1UmuelniWqjU(&uN-W#5y9=FCJ^N<1_?6{B9^Dz+h@ znxdO2e6#ydC4oc66RTlaZN|%$Dq|MZs zOtbhe2xnU4K@dfyEgtuyWbPSYh25qPpx89w$G7)T^mB3}QX@sZ)*leC^%o>9bpJ)` z*AL0wwbNWlOa3@{qsVq+*Td9tgeae}pm=XvTs4_wK@vQU`Z96bpP>A0-&uKOHF;&Uc{z~axE=Xg@LZHtmf z^9}uGNyh6kUxxI0DyYn6(emNQcrf@T>!*6;%g(*oEApB0qj0XSRI5<)!~sESQEL91 zMPBoEtTePknVYZH2jP{M$z8IFQnywfQRZFWB7!VfZ7-PZ8nf2B=&STtG~3QXu?sGF z(WJSirW$EsNvcFgQr1#`-KE0a0siingo!1h4X)h9;v0 zuf?^F#@rU3jHp4YY!SaJE0#z2q!G@&lyLaIp3*1hI-e^JN5$fGvV;?%L3eE>u2o+M z1*tKm9F;v^!~9ddhw;N|952emq%xRs>+bklA-3Q54={90pD+hcB`>Mt*;sYP7kY>` z$uxCFtM0x}rD0>Re?2r2{1=2$?CJ&8IfTQQCe{hoxgHJoOy=Nc#LP0_G)0BcE9nHZ zb1tsL^LOkcn4MfvB`lP0>N__C)09-^PCm>TmHrhGq3~Y!?s#AwABaXIjHTJ?R|m+OcnmfhT>pEn~eLVO_^AFl}ROPI#g)^DX+O&qgUtl5%T>5JHA`VYuxH2>L< zm>1R~ANi8WXuGxf&iO5S)UIqHmr%cHD-OD?=DT}l#37jDsm7K@{rDkgqxZ!U5XS7+ zM1KAc)XEap@YBQ!Yg{^Nz4~mT_I3Bc=I^m`<1hQuw;6$`X$?p6>xz${m+&3C8} z{Ty@i60ibqWnLEs=~y$Iq57xtG*x4rZm%gn%6Z&pj95%Gzv}G{PZ8!gYtLUZo4w z*KzL%ic&yrpl*0272}FzgN)<^3R>wrt;6WO6;R6wkaF_s<5Kuk9fo6cU82qomfPHywGELYo+?t8eMP9S}U^L;pa}rzF}tMX*;{65YP#Br$CC)`KE7Kl)Kr zNDzs9yy;2*;mzZ`l5f5tKddb)%duW9?CJ42MKtq-tIeY>4Xmez)(uU6JZ-Mf8xYB% zikC&ZRQhUL&3034t2P(UEp4vKbq4FRJ|32FMqDy^56(yS6(q^+YdH8B3rH(~92zvTV)0UdAK^NOt1Ui>h8KPaY#npAK*J2+^Sdn!jw;VD42MTZYOr~+Z9Y=f~+3iR_`cPZzQo-|`dIF~mdRUrsxlMBnusZ9865MCSmWP^ zm_F(C`Pqp)JFS&@B;=ayy*K z^5!e#J|C+c))3=hkr&NV8`C04c{|43xWJGu?f=!upH7<*@dWQ4kxZzgBcJ9R{Fym#l6kK6u* zd`ACdVDYEuiv>$YQvXluNM3iUq)vdi+W#MDm1x{?#B+i^QSU_iZJ2WYnqR5{fbID+G12?7lBT94d<~P#YnrEYnIVSGMPY{&V!E z%!}{mEDBx^2=37YmJkMxdYWj+ZF^jf6M6_@y95P8R#?ziA8yD?axvvGA+H{qpJVWT zi~Z3rWxA$!3wr}_4zbm}f5j!Yb6Pj*`>aYFUYQWdEGM zk1IxlwrT9NFDB~slCY3_)!4@t+RbIJZKR3es`OwOgs4*Ywe3>@*?U;bei%|3;TtrI ze;5)xiTA?eTt)*UflQt>>hozVsm@qI)*m!%Ts)VN*k9I?Y4!+sbtw81!(v*Dw(!7D zRdM>*sVZr~`g{Gy_l#@xvkl3oiEC1$`YEd{d?}qnH%FEJAO8M;<_hM^NIT@NTFWLV zB?Jhr9VBiY==jw4n2PodxJ*PxIh!?E;7rsOUWQ@yZ(sjS zVED7{3%btAiI;^Z_0Fh%CoRnEdEjS0+`~v%X3I!GUCDq88DwRgz{X4`JFQTU1P`)#@?B=O5zRVR z8ywva-PUb3~kccDOhy0DKLd=&zXZ#*@jA2;{ z27fu;SNwLoy_}!vvawZ!=zE*-LpoFGEszSID86jXcB!2-%HyAazsCKHiWw@>eR4F( zR;PGpZAFZbE@I55<)y6{vreHi?XlyRcO=jw*^S`_1xX@Ig5flJo(fh*Bv90?i^Q7!COO2!L{^7oQW%Dk6gLclt3g%W-c+ zS4NclR=YH>17k}eVY2I2J*mVL;ltv1sva*Pbw8Tt2FNvrBiF=IQQyYs$iw&>Y^RAPbpjSADPhMOIbl9w zWcanN8A`(Ab1qHu-kZC?bP^i=G;|X`P2c3P{U591BEM+Qb&eE+`N7c;tn30Yn@5Yv!bDzNvN!`0?u6C~8;Y(XA;$g^s!9Pk{ zOHEH*&x$&bes4w-HkWV20;hi;?+-pf4m`9wJM)fN=3K6#0B>>CTXk&NTfIXcht{cH zmZy;#84Gl}qQqBW;buE{jKpH5wdaQ?J}sYZZopUBOHmdF!zIF`?2faqP5GSP!@86w zMi4O!&U_1Rvq;h%1<$@G6LwhLmP%Rg#Oy594anF@OhHww@}h&I*;Dhp)2#3LBuhH4 zR2@Ei_%M5bPxSGJrJ|EM)#+mEKm!gWQqhPy6uc9%IeGfp&*Ts8>{26a-uLxZ?I)GI zQN5~rmiFe>l0^{T>gSUUp~vKIZWr*7c~cr6hbVs>2Lh%>|?tmbUnS}zPGs)Wf(Pt2)B-P8Qq8_NX>wNRq1nTc&zckdyAs_)UhN+a{ zYnT~;7p3*$Dzcpy!jW6P;B(6u0tu+dv=OJA+}0LO7^3W!mblFy@w`6zZb4i=cEa_H z+I&R{N33vv*dm#W-)mRn-KeI|nPD3v+mlGAvm0QLG!&9)EH=v>*IzTuz?hMt^?*Gl z*C!yKFtkzQeiD;!BEIe1VlcZpM~jOWSXyVF-!;uhq`3B|VW_I?Zdl|FWR3pI*(xjA z=%6t zUm~p1Fd$7~lRf00{joi|RUuVZM1_>R7~8tM*-E;{DOR;?umI|Mi5SH`3H1FT*<5l%x@9{FM~aiAt|(?RQDa%xEXEHg8jxAwMY! z|7pcZ+vysmqrzI%Vj@Bq}6UpM%g&juDFewbuOZu&Ygf-_cveG<$Gqrh4x1S6lmWkSN zo*w{UAH+cZ;rr7?i8lIz@+Ax{xBbJh%XejhmbD_KrO_f-!L(Fq0kr`Y8z(q}I58WQ zKk*WV`uI)ksPM5*+P3<%-6lsE6MgJv!J0XPJ<<6>(UcdLOrUgLdbNXFaK?UNw8{lC z0dGK=iY2)dG!@}bYLqAVQ4h(iv?SX3J=6;>yv)8H2&O=0G{RUk zxFlg2UE}4$XUw{=Qt7&?xyS0n zQ&1L&25vp0tVDF!@Rg?KrUE?BG@rG4yf`4{rn}8!!fPkY_p?S|HC8d}_a5gIY*Eyx z)PJp3?L%kws0Mcra`!JK=sm(F2(f1xOiFIWNsgO|F6QJaZb!b6aqfTg(`)#Z86O8xYXZ z=t!pBPfB2}{kT++JA4w*RJ_h1DkA-yHH}+#%XaEU%W-3u0}=lfn9E@C_3gi5!w_me@YkOrjR7XqQ2gB3&8AXfNKyIfIpLJ21o48?C9zDb&Q zT*Ai7e1w1VCCxrky5`Kd{Y6wGb#GLvOG-VeqtK=Ot^t@u4#18OPzeD`D0+z~G#L>O zLjOrb(VBoi34*HD6Ofb7jjfJO;Sz=N{vubz`bjqj2e&yFlz04V_ z)(WpTYYfV4ZFUJ%+lnwTDJagSbm_L?#)&^FTzr!~dMMT$w`bv7Q>0kkP-Gpv8m|ES z7$3N*a;LarSWob9Ol~@S7#Jv}o!{<>I~ilXV<93) z9Tx7aI&R?dX}qO*>(iW8{1+L#qcff;(d|V*ld8qC-itj<-Ds@98<9G^<74>HJM%>#ufl@tO z9>tP$?p)`gNdi0I$dUxpYD2DpYusudaXCokhdyB1p(fX9OY@N3&bbi{>((UDuf9Q}*Im|DY^lk0GEj)f$ue>0q z^xol0l(WK%&xb6ru$SG7XM4A}4}P`Vt@qLibH|{c_K~;rlj{L{qxc>2Q-Z$`E3I!E zWjs^Dr7ult865>CeD>la3?6foe%_ZqY|h6;<&db%j>?Lf#4%7jz7}^G{2Z$yyf(tc zcb%u?o?{bj=IeGE>nph<_l3Tk>cDML|6}@N%SnC(=OpF1z}XE8KK{DOB1lkHiD|tgU>sclsNmf_oM3kGv^o4b2lVHU%<)u4BCxD6KK&j>Gy;=0}-Jz**Gjog8`9DBOYt0)aZ^o6%B6PFfv5 zixkc9n5lx;>v2I8Qq#MO1R>w+r}4WxH6QwU!PALF#G|PYfHze0(K>+zE;z~Y`V1Z; zA_~k@ySuO;GBS@|A~?SJIDv9U@W2M~J@sEi+WnX^QOr{G(>M%e+!cRIz}C;#8>iBQ z81CH~_cIBb?Ui^wC7=FT;vY)R<$CY9-ghi*e*l2G5U&zn_QE>NF) z`RZE?pFqtpXvhavJewCvAMP{hXK><3KH2PdG)QBIpIESf`>hhEm_Xt(S}}d=p_t~?Gg=fyM!@EZ-AC2Edv$sBRIv{2~-I2 z=VFq9ATz{55*7>Fq2iSEZ+3XE$eS^*X-$krh2KEn0hJ4ygRFwqtI4QC#x`*EgGwCFG9fSkf;qnGrNg;>PvKT0ay z>>qbLf6||KB@%xW`?23vT7A+kG5@r{{@o{F-rx=Iysv@}DCJKNgl@Bm1(HLhbTORc zi@0oCXVdFuom*vIJ|9{AX>O>A&&Zh}m;vrrBNP*b{t_JjT$JnCJI|OtEZ9v(2`{ry z`sD$4JF`jMA||xaVl*jR$tlw=O2X39@UoWZGEUv_d4M-tsrW&+FZwVI(8*6bsVs#i za>tl>F4T&uOGoVeJ3n3@yriDzA5w9) z_lBidMk-G_7(Pc_!N&G{h|;Vje2tn&WdF7t((L#?8ITE4s5g4N8=q3bok8=x)`vA4 z2b_wrALxM%kc+08nM5JAxD%pV_d#6!!90ld$P#T75-W0unpn2YZm7G-p|FSy4-Tiq zl54N$mDsv*P+u$fw@xqbF6@NdIcW5m4H<*Mv;LuI066f!-5{3#kEC<4$o=~; z#K^^dm(tG8Usk@jbfBnU)h&I#^_2u$|K)n_vS~u;eGhb|3 zrK3Vfn)ira*>$Z>((0Y!$7uwMm;0G6rI+|-t*ip|fJjd-alHCJ?<=Q&%>11xPcCY4 zoaRHfI!nBx1WJMv_zz%Dnirhd7p4Gg3;B1uVDVZrH>i*RoY~mL1qHt+BF4pVp-!d5 z%I~R^4pW@+q#~Eucw|!dV)+7HuwIvoBJm(*c0gsp2HeI81;En4P%B<7x)rvS@U3aH z>EXgPzdhZ!&S=X-RN|dX^kpQhnbDZk;IS*ITA0YZM|A9i4sYS<%Hb(ty4s~~uBp>D z;Xmup_H7-uKN@FMa>ESv&-?K?dz6)mgq#v?Dmy+!@%m%pGYu9qN#1&n2yi1hDraHo z*6pjw2KpgRjoQnc?T)t?Ib_MpIboUPysx8mcB+ruRL)%k5RY6S^1k;d9TK1tzq-^( zkbDcwJC|z%7aUGQdaB&(7BO#o#EmIOof#1+m>f(-bH22$Fxk%epMSm5fkx*Uz2&zi z7V4=#YonSBYd@4JMt;NH9TQ&l!r>5hbQ(V2t z9>U8+VBH@;H7gqrBxKI?sx z`1q6WgZP|9`HoLUgv9r2u9pM?y}mX}Sh>-uORVBgMLJ_a)*u*uWhMNhb0`sf>b8)9 zqopx8Q^|P<`13McCC1OY6O1Vkq|7{b(6mdI<~4znB`hCMQ{?Bav1*2pMv6sR^nyZ( zsGa~}94>&C2_U3_$SjPC@gJTNNa!FQ9V0eyEC<|UW5FkjOOMEVHUcvB;vedI)YjyT zg^y;})^c4nTs15>^?FDM6JtR|{<2bsYHD6ZmBoX9G|dUlv4N&>BPxZ<&wK=SjH z85Zr;i!Vt_EgewE(oqiAq!gde1*@|E4OAe-5=Wilf;J@1;LRWIh%^6_;7A)`G47Po zmlP3qc2BwJSN`5cJQ@y3H^)o&+CXst^iFC%*m@=4m28=G2O(Jl3Lil$xX3dqalzJp z(cP@i29}G#&>j%F=38RI@lii}iUosOG_qGR{kFJsc}Ri0a?u@%S=^eniGQ3pQv6B$ zu~}-|ug5baQTYuQe*UinnHFf@$H{`lX8IENu{o3P(H|yxTzBV>8i^}T-8@g(*qn0l z(Q~^HndQ#Uneh@6`m=mwBp-Vux{cd<&1`3Tb3}T3 z5XwvW4X=r^y8cpv0tKzL68)1Atfb-(oeruE?y|8_p&QCG>kC+)%h8oU4N+meUVqtt zAg9^1&ihrW#Z%&#FXze@Z+5)J!IGvVfMCT5JoHGDn$Y8b1Pw|@VP+_MII%-N9}pF= zmkSx!R~sZhr_P^Np|Rb_jl%4YX^AmnyecHKyr3w`MAI4GpQK$>IEi;h9xgWSC(V(( z*A-n64TduF8g2=}%XIJ{#N;hYGYfEIIkzi)v~iy&i@Np?e7c5v`&s&p(sV=54tYf7 zu^dK2QhtA?wyi@=SLlSk&v>U=M>scO3_NEs;1hp+4>(TxFKg+g=$a2`v^MTaw$MI7 z8a^FW<4TGbGof-YpE7^qmTsubxD|I2wR10s(;b`?mMj(o>R~?yixX8W^ZL)&HA%K7 zA+&^^9`iVVuS<(hTxfjge11r2(M_rC^JGA;V%$+8Aah*mjKq%Taam%$a57WfWg;Cx zAk7cF>0ELss02IGTnf$uqeM_Lo+{&O6A_(F zAm3Np4e#ujCuEv=HK{c=)X*xD!}(KP!i@~J-6%OGue-@a`Z?RExJ<=`zm~ zcY4O8J#&&!Z)T*_B7Y%J?cZa2tIRcbD|Z{2sqwa;Q@4-=XRHxO8pZyEuN^w?V@|hr2I7NlAK82G4W-k^s`T z5Ad<`(;j`Kt0 zr?`$glWP^_opK_TXtnAX57$}$ASL6y*vr0>?a+GYJs3b`91@-II>Gl*Uzg%VlT^Ee z`=?OPNw1-cy5%Wi{$UunCiL4g>X0ri; z-svs{jtiL660aK$^1ZnW3W9*(ZBR{ub&LWLzyTMTqa$!jPn0K!4wunXY>gCedKO#} zGU;qd;{@hyT>zE@^}RH5;ux@(Cehfda6E$!0mB=9kLvG}Y3V(9Vl+xW0&Z#R4LU7K zXt0G;GM0ESAiaHuIAj%{5zH>i^;nVG8$?kk@>L|Rq#Pp<5iPP)qdX&D^-8yAaQcpn zDkv^0_Gzu=L&zOax(6<3yI}*3{{u#{Q)n>I>aR+$wwsPaaZ$^3lV73@_Je>ue=APK!aH=i_xaTE@k*4 zeK@S1ybq2W|Mo82JG;DQVK;Wpaa{A&&?^O2+RE7TRr5Vut<*tr%^rmeM1*Y|k7|w7O3_Oi796e)B!pWljAsOA~~Q-N0hPy_o5sGDX$nqx0^o{U~1# z+@JqIuRfJ=2I#wqN@4mm{655edz&LdiGxh6d$lj&-H0ggn=%IquFQT<=?c_L()#*E zV@2?u50P-xZ3q{-M=S2>qJrgdyw^RY(XThO5)zZ(_k_jo!;zSVSEIVa1~L5{emlHR zog)mrJOe+Y5j*p;aG`u*qSWuNZysAcR^a9JT5&#L6_@-nm%u6}ThkGYWon~HSxSl+ zrXKpkSMz<;l&AD~HBNn~bz>#5^uqh-xA;B@PW?`W6ry#2z%D?@?)?V0SyFuei#6;r z(id#`;+Fo@Z2*jq^Slcj6Z4$vS6>%T({e}B4FB}1-hD(=nd>Dz|L5pxfYVj~Wf%Z{ z%0jxS*+Z>toU+i_)o-4}YtZQ?01rWl!_Yu0Jf7#1iwXgBYB73|-KqBD(?g@b67hyg z`mVxd(O=Sk(HMg4nbxoOTJfKHuB@Pkg!h=Z96S=4be?Mq+!QT$Sbiv9Eyy0+8|#+k zBU%jM<8+|Nc`>vuG$GMj@}uTe$qyBuW@T|jg^(nkcdYw=Bm64s=KQ)E9@B^j{5{iD zb1GycAY13sa>t?kE|?QYv$z-t(qW)g&kYt;d~ucymY* zl+`Q~HRTrEU+9@Gm~%*+7|6WICzEdamyE)mH=P;mTc71$D3Hs(pOY)R^80XQ*=@eAQZ7x0L-cEXHU z5L!S2{gD$5Zz;wjXq$DX{K{Nhc$7#*Y+VS?2%aRQBfC&wn0*`6*}Cpd$|?egWH7ks z8L)VJh}8_0j*&Dce1fBNL4{(V`*>Rtp$vVBgF5@S%e)JUde65Edi<@Din{h|C~)V4 zui0gkdVQm}ehw|MGNx^H{IuKU_p9xYhWhh98LK1pS3?RvZU{-EkkJ=fo$^&7G%n~& zZ8iPOCvYvLn<8X#k(k6i_wr2^R`7uSGVfUZoik$QpRLTQQs$}=zdl9}aF{)LxKWTY7-OSic5&-=fK@5(^j$C7am7N(&( z%Wj2^LO*4&4IO4v%iXim#!F0+2`q@k7QbDq z6;?FA;nA8da>5k`vcIZp7#4vxxEiaQq~BD;ip-(EW9N58nElRt=Q}gQKBYDuX=uSL z7^Hiqi7CgfUyMVP1ZIwrg`=0Y>v3mFqDi$)88<{(XHR511KvvDjlXj}ruQu2t@@=r zL#oKk{nu%=w1>~j3xE%bow3KiBHZK02eVqOzLSGm z9&-p<6Wa=g02FvYi;;lgwN9ZG*2{HC{;fjkaHDClG7{*xsU^{Uv}|A zfDi+kPaT%AV6k;~+H^0(bBnm^SPQ#3WzH%J{hy9c?Z#Xrm=n3aB(T0*w(j%`4@_2I zaUVBi+Qe|Um)aL|9aZ-;*G+fSP3Dl>f0 zDikNZI+sWt)yHJ)a_U6%3&W`CuUENsBV8nP%~bHqFT385C;M7K`1q)1Uq;G0MG9ik zvlG&`K)*2aIscdq$3z+Q=&P0;ea(gmmPjw%q1smi%3; zY)r#Lc*72_;6V#qLd_45`WiNmy5vsP+?vM8MhtDAZLae24Bb2(-6ac_f zY#scF1Wq#wX3@|N;-caJsS=4Yhf=nl!mTCIf|b)CMCUveq>R%nZ21!HxY|Q;P(|Q1 z+fLw$a^JQ5-bGtZUAbp(ygX&?TF^&LBW>cz`yf9M4`aJ4@o>8+Y9x36Om*h&My^M$ zSjS2fjBS%#0$fVeG7PV?P}gUD7U0^gIKsABV*=0Mb@BT zZN4=Qfk-<}`f3A6DS!9SS{w@8%~R24;_g64JYLr_A!>$r^&R^4`VY`9KLz`Z-C z*cv_N;tlF0{q&wJnjCmFBv?KS35)tf{5j9)i<`E$^pVuC?ek2jt2Ia)TC2k*+YQwx z|146P62Ivd+J#Rln^cJJhp04+RJQH%uZU5{z)tmy|J-!=+-=`ccvo`~Z`1aI& z;%?VvjYz%Iy{dTY-6I()oDyq-lal!&5nmcVd%x|5GUAwW@%xK~qW7}KyMj-i8E>0E ziaW9tOn0YXbD?~3RTfvVb*ZGYg_Xo**UueKe8)ImD$ncoD+T1IjoOjR^5@zM9P(E% z;4`p)(2mhYE{93juBB{=n3Pn(bE=s#(d&KO8Y_ zX*ES8V}^2sISv!FiMNy71G-mGDAgPUX0}|e09wc)GWLbxS5Zl&!|)ck$UB#FNNDC@ zc&zSZ!T)RNZ2Xzr|37|hyJpwi%r!Tm*}526iI9^Cb*<(u#T4fhIT78Rn7bkBWE&NQ zhMjKFTFP2CN0gXTu{s*3+*FEKa*!p~iPX{E_jjGg-s_LENX7VbpH)?n1ffB&UPqOG-(i%GW zz9FD7_ONmO{ILTi2Rmn345nX*ZRV;lXt^Kh-W$H^rBf*g5+{dx1ngs01`wcsSJc1^I>2$q~~D( zt8YBtDHX`0A%5Mii67A+A-vJa2ZUfl;A}0{aM%Gcnq`H6fW=xj_;JBk zH(-Z*)$xTz%h}uZ%qR88!0UU}F|`Z0mQe>Z&h_VT1lP6)kb^C3`|TLl6iam<__fl^1@?oH%jM*^9E9Q@4fvTW(X&{G4)H^;pZk zK-U8u>W#-Hd=4hu46{ty#|V3u_1W2@$fzQ8Y|&`91CM=k*ttqJR%_dtTP^wgTZ>S6Klb8jqw+S@N7n;8PERj z9PG<`@wRt(6y&U&R9v?f8euANKxiM!u2gE=d~&=F%J7l7R~6tNW63X^2lQ@^zHJ!v zo=#O6npGBn|8kCA(UYf-JlC6OwA5?Q?x%&qahH+7%SJ{7T6P_ovvmFK6mil~>lS@k z$SQua^O=UsaGL+kS3YTZaTjyfSy&aNIw7DH?^Q({@g67BLwq@4IfVC-9}jBfF3W2~ zU!;iF3@EYS015VAix7zx@U^g6 zkB1n2Xdzt^=~IkTRZt zYvb7rKnxsu{SF-R8)ysZ#l8<1I((?de@_VyH{qVctKkr^;saV}(`E_pCGkZZ{`<;5 zWOQNnYNPC0TxUPaz1Q1Y(}$>kx*r-=(((8SDH?7C66V6K*D9J$b0Rm5P$*-DK>@h$ z+liZAJPz!Dw<|QJ)@*2*G|YQ9$wyH%>skGZe!F}7qCtv#<)_HaQ0IhwGcPiEU74t~ z>L7kFkq3chbU27wgkanzdiP45Lud*dEJOAVu^7uLWO=7aTq7rlQn2tbc`%b>?~`wa z8Y6k9#k9PW_`Ro%EBw%N_T>Lm5y%;>+n^by)^yW2fu)Nd7g_$!pNyf>Kdz3`OoS+QoH!6^VG_fF0n$^F<2%YDH9xHKxPv+AL!WgP=(fUnFSLG4|nw zG=y7y>gCItkC{x;QD*)NU8qn)!LgT8qH*$ zQG}XIyd4qX{hnQctUsF69a&-z`JtR_z&U*54V!)Bh0_e@2ckZ$(?wT4C+S9MLi}(7kpIG))74(<;&zjIXOqXs=e(o0{IQ}+6A?P)ycg6braK4rSXFPJ@ z&ug}HwBs|Fl-zHD>EC$UB^gCiJ-|M`$b6XKh#z8E56B5Ds*^Wb*a3=)I{?PUd~=N& z^6t-sxyEC_BuGWuS@vOGTob%g9e`!Vwzi|*bJ*Ap=*3BU)x@sSIxwb0v8ZVdE0JKq znl}AdzN-<-xa1(-NsI4FZ_rTzV_9B(6K9W4-fCmPgT&&xJUV;au{mCO-eyBLS$*XG zGp=o#_I)pPo9>?=7Y+{oM|^qPyL>B)fAka#G85WX3%t~LJk__qm)b<_v>i5B>qPV) zpx^pgX;=*Cc@g{-vQQ?QE-`s4H5*)zU_8n<#E3jW)P5j~v(Ox4P!Uu><6bQ&>iicq zFBThw_I2tIawkb(^2i|}1M}DGD09$a&l%jLI65&vV?PdOav0lipltuk)x_?p?hjb3 zPQ{0=2;9`*XUJSm`|ws3I*@y63v!;hQ43iZ6~^zdJtt7=q_vQ(W3 zr{kY|+SJo?l`iD?xhH#tjL{h$Pmq281K#k*KVzVYTR0(rZYOPGvhX5v6@g{VqPjZ7 z%Qy~@>xDF_xixCa!k8mLURVVIVJH>-TvF0+ zP_rSa^q3MF^_tw=M(jcgHy0K^4Y{R_2(qp0-t%H8>cx%qmwIQXNsksrhlM`hKiy3K z12_1Qmz^9japs!xzo~e*)uCoAcGZ$Z`uv_g)A8Q$La_3V#!GJ<-Bfd_$@^}peBs&j zrtczB;2^TB>KrMWpdt{|ki-`WBqU;{eGtb+3pH5gz16SXM9sV`bb%76tQ8@qTrB=* zGp6!lrThSxd5ndG35?Fr4GCxb)2Bhl_eB*Y z1@=+CvZNhh`IaMbkn6VHlj83{rk3~>7{%w=840Zk0xK6Mmh%te*Ex~5b7aTU#7P|2 zg8#yN_+Fgl<4Uq#=-Y>${+lukHnp%_6RZf8R@dBzg1a&Ls} z8G#$b7dihZ<(tC%skYvYEu6-bi7z#iRvjUS3qzyoX!FH)WYGP^}Dwof6`+5XxUd&AgR26 zLse{VRMlJMwZ~fiO-A)G_MX7e;>wfQ%)ZV8XP!(HlzXI@CeUlv4BXwhyMy;}x}81y z(sWC6>et%5m11bc%QTo42WHW`Y4KV-+Tw`IlNu3mSku+97zw>T--u*`?(7FsRTvQ= zjd&{ol0ve=wj7y=%`qE=T{(;c8vCEczTdiu+C%+l-aowcCD{|aFc;Uzb!=AtcyiI= zTF!$rOq!*`olD-2m?tg7IhPKP9v2rJ9VM`tESC3NJBxMue?XUD-n*==0*eJhESIWP z5>ApUrU{83|5$Z_Sl=oNB1Uoe-0+&*SUoOGQTCf*Ci z0wt5?2sfi zU)l%oR<4u0y6VE<^n+WX9s|1{s0xyNYn%k;l-;P0G~c3qEHfYgcJkAgKVR_9y=4FX zzW34#O?zJ4`)NS1{pu&@qjMJyM1#QBnN=+xr}x?WKDvA}vMW-%Ahjui)NCCeUH@PA z;NI`bHJiiAxB4hM9BkvY2CE-%`Cd`KAcLRl3`(bl<`BI^s5#x@2DETIf>B9E**=gA zh&ktJvNcKr9Of+zvf6;{j5t8-)kS1-@}MzspU z=%jUf{t49~le5;GpjUY+L)Xkem0=iy$i^{IMgINpe%Z}jfdyl56uGsJx6yr=Ko#d8 zzuRUH5~&%qwML3V25w^gD!Ed1RA9A4OWcvv$ca2h3>U-e1RU4IA`9bKsd14lb|>fu z2ZSEtIE}*=*gnA0V$er{h}W>ku#09p0MdJij4g~}MYd)lYQBMK8kPz| z$*MC~x!^?xPUEVAB zm0o%2M4UErv0cLKggCGzGGgv8GN?EbdLRv(&H;$kIHwnvAKNIks7T9^RcC2fi~NN2 z4rt|aQ3WDJQ2mI1@SNQrLI3})~Q zIk^`?c!1sqIsPi%j~7$~qy6C4>02zf7w02icots_x%pxXZu(F2urB8>Kb-&i1)2U> z`|PKrxQw#lROumo-#OCg!L#b28NZ&)SSqOp42x;dg2GOcl%9OJ;k|#&$jMu#%2esM z6{e%BPMe&W6qVf3;o%G{_+i`{oy$Z`B-Yjw@*o`EF%ldGC^-ncB%kUKZ->Xid0Ws} z#EldINqF3Eyp0F6-5Z?*7K5V}FU3bY;SJf7;uEW4c|qAM`|;Qh{a|(p&)sf!Kf$z1 zK=Klpy{7Y)jPI9K@INPtZvRU|I4nFFa+aCeq(yrDo9|xb8R* zn)H#akM-7c0L!F$@#W|;xwCsUwa(~}Ddfr|gU%0bMMkEztdL!KB=rv{9bA0LtHV(E ziQ{*@hrss`qshHs(^|67)(dTM(Fs#JAY4<2fdLE(MQK%v#n)Sk)!=(6709baD?ey~ z)DjF6?02`!V5P#mB7IJ>EhALXusg)}MD&e6uHTrxUi|g(s`@CON=bHZ)Z37Y^{N$j znp&^eB*HhomM&}gG`&wg@UwM?-76`MmaKx}fBh^|$*RllT$|6%_3he2Y6y#jQVZL^;qdg5G%@&2YI4niFHC)H-N7Q!Ca+o? z6?LvIzfzC0n7d-urwK#G3I@)`odP~sfg=!n`aMM$G4l^zM*LE;-x!9iP2j>X2x?C-8Nt_H@snl(FrZ>hYT^ z*RWsKlElAa57vwpR*}j_<&)1%_uCtPkzv)q$|p=r7;W$LMF#d}@PEi^jRt5(3Ki$`X93BS#Q+Kbs`jw;P-o@ z21VskvTQsh@bc^fREu09@ z61$fvXytX}n>BuL#He*Yz71X%_ef2g%f!T_kvj4yW8&de*+`k3S=k*T`;7SzFkr6P zQns3ScXf)8-HGeRqm)tP!Pa*lA1&K+`fa8nk#~Pk^rb6n$BisU(#ed@rlz+(=amx` z@ijaA{n(k&=DCj^H2L>mF)1|x)9;2QBJuRY*jvGRRRqKzrEfgc(53F*y5;>$jXo&&F6^OE@BTams z62>)m$V6{p{;mWIv(_BK3Cuk`HHK?%NE0D2vj^~iS2nS1eE9H^L=jyQ|NDzW{TGwc zWAslN*l{%Dum3;9r!rpOR=wSG>e8is=c)_N-rGpHku<%(@e}KZ7*!krGw}{!%kiw7 z-~gK@0H0-7!_2Esm0oX3*X$xRv3xFED~O)z4);tlPD&o4$^PqgfL8Q>L`$I0$g(TcEFU_Nm~wPcMa4e34au6Ol$E); ziJ2!WhPlBHoop5>QCx$?YM0J8&aB%_bT2OIMmfJzl6}iq= z&-eVoJx%(d)XJedRd6CSN7n}(&G`#u%bKPL;Y9QZ|c9(0u%f&~=r>hN~ zFMymX>)^n%ET>8p!i`0OtVwmGvL}tGZx+NX5({Y-rZqi4XaH=VM>}vg+OzlCo~ti% z*FuM%Hh$a_n8wRK@$=i}lAEger%zbFk*8XGc=h%At@i1WL0NB|doTXuCzLt{rehSD zp#&qQ8p!6{PRUyP^cU?;qG!s92Z81jqXV%t;n27H4wTmP`Y?|3DW)ytr>-X_#-Cn& zM2rLSu3BZH5)jt|tdQ+Lhi9ruPyS<0Q(*tj4)A~i7$q%-mxy`3ad<>lfOhqQp}dVO ze1MzyBrqzw;7rB@Cjb0do%qa1>t8uaC4YAtCEQ}&UVsI-O?{CiWJZP%!7ZqD=bPo?do z4^!#4R7lMdH)ASfMBt&}$lxLqnxfDf=*g2>&i`+blGxBfyrB?L^h{#=J9Y%eh{SM^ zWcWG<-iIh!>kRXNc*tHKt_4Gb)xGibHxm10`{EJ~R zy{2i|f!I1S;8DCkK}aYWqKx4YJPtkdU5DkR6bJKf4(Ok&^x-c1uU;%T`){I6*2H-3 z)Q@H{6LZx`KTV|lyQy=V2V{7@Y$Aye!!PYBv5zwQ?Lyaj&!tQD1=;QREs(@UsrmHn zw_(s2If5hnLdJ@9rq}^cU@zoQpUO9buk7CVtv4=? zR1M!sUAa#o6k$>HR=5$>;zfAZHy^_-2DIRrUhswToSk<#pcndhB9}~2u|IzD%9Tr1 z7r1M#qoCQOm^p)7UEu%w!gJwVrw_rt#doEOgM+d&*wF4nPU^&$ba2G6X_-<~qF5jW zFwsjV-ppp%kK%NqA8=X%)@Y5D*y%m^{{dX{WC1mc82$`= ze17Ab-{w!JmfsmyD=^)4)hO(R*#^LOnzhi!Z#=sm{JW13ZH4SZprNhqL-FrVQg=j6 zXNP*t+TJw&t0&5J^VYR5ciSGQS;TbDDe-!Ix3V}>+qQw6Y7%X+UXiAguOfHdhMXrx3ss7UV}rT5;E zj!3W4Z{FWG-^{&#-j$hs&e?nR**i09ukx(t+)Up52Ef&o)sz81AOHX)`~WvIfJXo@ z=s)?d1rr294EaxB#Kc6zBrsA^5*P^yDLEB6DH$ah2?+%?1tk?6P7Nm|r=g{R(-Q9C z|GfnG-%KzBMwkdEBOxR7{{NJlW&kw|*b1ru1E~QZY9N>zc=Hp$O4ug^{NHx}uK)oc zFocL03L_y5>%akog+UN75rl{Y3W5+3{hwiK;yX~9hiFTL79if#qD14poB__h< z*Yt|nlU;))9gf_WaYlUz`AHi216$$)Bg1}kXTOZOpc?=U{9)LrMBwxa8#=~mpNGx% z+qWwmU*5$U_`sIva@8r0jWsR&I{Sy$iUQ#83<*fuffjnj=JYiZ^>(Ku??^LDSn3w4 zJp+%LnEye`-tbaRDqsptw#gSekhaTxnyLE-Z0Yp}xXFlq2{}8a1Ur>cS`H*Q4 z7twNlHwmY_^nBScFSoiadMzDe61S7eo=I*$>XDRPnwhNHxyds8@DL3E`z2AVa;{MC z@G$qq1c6yGGGPg+<%^J**r##T^JW{u*zL^k0fA4GuvbZx4y6@y=63!TAHH37gZ^4u z_f{N5%PG8Yx4)RK+v>E~_R4BiTU4AackfDDiw#Iab##p)K!zi0Wm$vXjf``^!Z| zDv75`93QpYT#nF;QC)&2td9rZUu;oWCspg&pMFFE7iHOkYqETR2co5?t|s8Yp7VkNET!G|I?x=C znuM^KnYP&qi&F9G(nNa`237)RZPZ@I`*}uSOpF4S9RM2!>ZD83If<0$&`+Y>M z$=Z+ZnB4#{u)7|OjUpA2Z)7JQbqs;Y^(n5ZQ-|ffvk?sOTO8d`6_sZ@8F7MYjy*;*&juDnxXRxEi1ehd(z9!za(yN&9gKU~ZR~sfzZ6R7Md_2C zFz^+;Xr2Gk*UCq3&XolO^hhrP1RW<)H-OrQi9yg}$_RMEm#I0>zOp}tidnLg3+&xi zxynQ0hLZ_Gg%~c^faUTzErjcU39>(rR&C@HNj}?D*KezFsC=I3Im3HbcCihQ4y&y9 zVR|pIsEy39PuCoR`$BQEZgDGcOZ?b--HPJTxnCB@j&K2qD5_tbkufuhV>f_bQ=6vV zf4S~Avt6rL(w$6~&v_Ez8q;=U8K3e-F8q@hrTe;d`p#4^v5V|^Otv|Bj66$x2<_#v z5w(E1c{E$=ttxg!a{u9_wcq-x(5#X(MA7+lsq?x5TwjHR9HAs57e23H-=sEZVFdkB@kDJCV?d~^Rwt!VHH2f9*+nZl97F`>g`C+}@Y2B%F_ZYP{XtaV1`wMs3 zM)2PNwvSO>E{3K$&Y*OH8MS5sOMob`p3?JfZBzVBEP&L&pJ(_4l92Vv8T&Gg!0Uem{SI z374FZhH${AY+pO?%3>~YLudH7v(0F16I83m9_j5@ygh zg~D&&+M*f*tZ_Ix;Xv%&!Z04@fq_OLY@gsUYR4=ZX$fXIvEq01-(cy?&9KgNi+hij zPb97( z@<&xZ_2^0{iHnEelLa&cL=M$7n4#Be7V^4rnPlA0=OXU(<+L1RNBg6?Np)Xps`cqh zcV7SOcN*bDe0yo--I-W=o2|Z&ioFFK(4nd=Eod(w-^Bd+%o5U9F>vo_jPAfk{Pp^Z zD$gBU*s_+J7=N?(Ka04JXrNuoMK9tUe`mXWgUMx-vN0d#@+U2x&D0lf^{^j)7d45u zq3m}R!tQte8xY}i<~Y@YTiS?e+UtAL!_1mCdOk2DLMub)uH-s>_$288%BdY&)%Cl&#tN zR=#DM-T=PI2ZMP2l=X3SlT*!7x?IM~sJxC|9jnkjvY=ppvZDCf*CMb?1+%~Qr}>=t z20*9VxS&jIURmb&cEGJE0!1{h_3F8j>Vn_%|J?2v!O42$iU*Fwe7}YS8 zBN)^M9#thme{T^~SX6XOB!1FnHU5O$%#}REee7)c^I7F<(bI(bjC8ozc|ajTQ^_Cl zBCgPCj|=i@%+coR)eS%u8b}lue~t3TsPmR*b9@>*B~9^Gc|1<_IW>@z+`}W5x`zn& z<+@CNd1E}T58$wq$p1#1>0XA!p=v-5_y#aNQ||jjDm~@;tu#}>8`PSeiSn>w6{Dri z<`g9wO?5aXW)LvrK*{a8vF3cv5(*srGaYsvTa=mn=$~b@WYe0{HC*)BOQ9?EqGbFD zMUtCeEGg;8wA~*qTN`%v0w}vEJdV1Cf#Y{j#ZPb|cJaak1+MCXQDW|@&13>hCe1*U zUEPouE-~?fQ_$a73p&6-S|kk6%s5a35Oi*#f&0S^a~tOipaNp;*}#9^UF;mCWP#ga ze$C>gVZmQ}yR-&(KRaU#b1uZJwry-WWlc2i2c03|!81p{(qFs13q7Lz+x49J;h|mG z5gNjzmF{(`OlQU9HHpNhS^A^!-f=@Cdzhnrhb1=(l(lN%J6-;e$#lJsb zP*QwQsvv2zedLm`&_XG1jE^;1opuS=?_$=r9zdKU3eR2#&L=*Vmz`b0+&ZYsXXhmQ z5aif5D0EQ1;)PlaX+-g`_N`z<>jn`56g$G$Z0v#s#5A^(%VI?3ie9lKW2-)tR``!= zwE1?a^hLAurUI$oWm_&>gH_Dp-=59v;u@1WNt#W~RzMdIw8n-VNBqvxT;9I5_xiGr z{TDa}!Y`j!GgQ{=mJ&Ek3i;@+X*pCHoC8A=AwQL{-2~&cgl*W!&H}DXUK{g)PtJchOTap>!rZod0cYEh+ zkB$A%Pzo38@BC8=V67J5^o`e~aL~Vh_Gi_XMWTlUCeG|wFgkqDCMH?^Yb5cFj4@T< z%R=%tfg}kls!AK%X=r+BOBuA`#|@wx(btCa*4|`FoImgpwh3XAd#r3a4CwqUUn*$uLVRtTGXN0q{7Ur5XeJ@xYI5WgMJ*;5}??sC^kz=VQJ!*7nkuF;{DnDi@o$I+;V=*np^Pujbu_2`V0a|IOkF4f3r5S4k0?&rna>eGNOiFlI`+tkG zV)(0%i6Hw=^hepp{$vN98mf~i{PMhXFN$W{ZIc%zstoFQmAR;LyAh-MPlAW#+>Rc3 zCHuQ`m&c5I(>Yka;@L-7YHDb-tvsVZs9L z=D{s2CMnqnij7nqjk!t7*B|I$BzIl9;uGPbj3UXM3S@A7eTAJje3miu4ldA*;J+TM zi!rOo)x9!#F{M<;AZ+WE+P$$#Qbv)np>W0Bqf~$R!w*ugy_VE%&mX6M^X0Vu$3jQj zIAflcwdE5=p3$Piyd*C}eT-%pnINIsd`+5hPFu3RLW$8Ytenlqiizs}id%>drJLSy z^_&B^y^{(hYwvJY056F;1!34}t8IyTrM7|&C2GzP&H`^HO)my1y-s2LfwHqeV3CFS z1$9YNykc1Gp-Vh`vmiFGQb&J5>~T|-NQA5~MuM{ajE6y`pp`f*Sj#1pvKaw@3mT`A z`xaxjt-<-IEnqPZ)4C^`u}eCMrcGwBDV^82gEEu_(XX?)nZ=M-r~AkRKKUkO7rWt; z$uGW;>m(_v-=CQ;9g%mH=ogaktoBO6qcZUfAsBt+OC_TH6Vcw#@7NFV9TfTLq}d9Y zsOWIT&Tb!~{0w5=#e)vC=TK`Yr$msU5d$r6vz$+7SK~CnGoq_!7nKv3@w1xLCLGD9 zoSmT8xrJd#fxG%b{y;98ltcPlFs?yYQFU|jIcG*QM9(o?a1;K0U##2Ad z&FtW+EHw`7Eues2en;)+Tbr>L{`vamKv+tRYHSkCT;VWCgNRK`_1v?`a+E`M!z@Nm z|DY{Wq%x_JaS?KBvyao^26=dt`S+6({|ikDG3Tw9Pfr^Kru3c^6x9toTn=bzTuu93nIti6 zzT4h;S-UwkE$@++<{&8}M*q;$%cR%oPm z*iXFi3{^eWatc)wAq$t5I|56h9xnXYLk%~35dl`58M%2_#^J6*-73z($FiG;s**N4 z75vs)oX9h}TbZNB*=v=_QB|^jwy&+$X6dLr=G$}|G_ixUqa#`>LsOT7%9EnswKZZ) zcnP*HNQUa2_8wZKyp3CCyr-}BYgeO0*zWtiV3P8&9qIwD##clCvRIbaW0{vF`leO!vs1+>t%$BIfU2Ek8Cwd}SOMOd>az z#e3?Ix%edT)E3urVCQy>>e!U_dqijGILEMMvCk#{)O-V*r9bTV@mGQMV^SaKkfyrN3QwkPY%VcPM}6PNU7 z)++%EfDnhu3)y{x-Nnwi2Lk*~jOzu-$dX+fFQGHUto?kCvC_MQ-Nr!-+vWR)e)d%c zbi?3vv*kZcU$e(n~Th=Ih7q8;XaHd8GCARU(h{HGQ4$0 z^RFz@=|av6tLL;1_nZNjq!h24G#3O^j(gmDop!?#NA{T!?eb}%kqjy=5XmQ_$2yS3pX!UfMmO{+9@9C zTN@XI8cz|mtZyNzwVUgYcWp5dL0xi9v2)&Pn&#!?*dCvj`ZD|R%;eA!E_=-MBHKyD zNc9FFuFB=q`TGh(Y$Pxyzn4Dgp~28W|(5+*IrHJ z7CnQbl_WAaoC)@O%Na|%f+YqY?UYOfs8OTDDW~HZi?_{P#XrnMRr(UqzLNka( z-~$F=Ha>3mww2pjFscK|g79;vANl=Alk?Nn`1>^Sg>Bv38=9tTL3wR7=vZx5r_&NSf?oct+xZrUG#4{{jVskwZLgC+| z(pDjhtMv22WlP8tSN+3BZ<4ur<&3y%c0A%pKRiaFn7=s^0EgBmn3k*V*Wg1$67{GZ zs}e>sFzueH?8hCQBXnHyqLI#fF~zv+!!DGKUExMLSI)=w{aHH34UdvfnYarjRy_;z z41kQEJ}t9&MnfD;hdaD?`;s)K>NG!EtVhe_yRY5|vi!)682vA^WVXmg=6A3(0^Pxi zLDFc)qYMWmOc6?rHKzzu^HkSim(@_3()3L89*CB2Jx(|vLd3I?^>5Dr_n~KEoz}#4 z&x{K99Rkou_{Y=R^ZmxgKiXo`E`($^`8cdbIPp_F4T;t7SI3_jOfC!PXC=KMl!@~Ydu*PZ9-GL%(@H7lt*9iP z)6gp!nEKlKYCK)%Na>0Ha)d;A9&{70gJEp2 z_8GiVA9M^v>9lJGSOXlRW=|n_XED6ikk#5!$uR*K-wIxuqp-`Kk8lMs^89$`k;56d6 z97l^fgHh>jKGa}ISK~&O%c!9%?QA5g`m&)>nVarBM#}!IhR}AQK!|MC3UnK>z2gj?bPYa?)*~24D z;({r16Z@>If_MbP^J0*G>RZ0Wd(|WW4x&UWy-9*XuJ89 zALy;f}4)>7NB)CMy~c6LU36XRNU11QVs{xslQz8tY|R9SQR zI%7}%!vZ2=EhU|9)_RjwTjR-u`h2{e*r3Ms(?$BP#-hIt#+UAYANdJ&9jH5mJ^WQ< ze)gh6g7pINT;OjtD*S;SOq#nEdKg0)P5G zLSHXt@7sx;2b?`J9<=)j9rtbAC$Y))UHuAMpC_~v(Jqyni$ByBN!NB&LoR2>9Hy#j{=F69N{$<3Wf!M)O0wI<_O3#1;=xqxhgp(Z9ouHRoK*61$ z-BJ4>H;2??l<|o@(_)4Xzyb_##HRjC4ZU?Y%DdBENOpaw2Az^MbdIYAQ>14lU2}^h z`E`?jM*8b&pYEL6G6AI3klZV9zZHJkXVBRh_=F zg7=qgul(%e)Aj25Zv;9%PIngfP_$&U>hyI?5qmO*@qvL)LR1~yW8~b?!7cWLPSo14 z&2+ES{nVuFYsRe3v#J{ajAdI)?_@1FH@(<{jV?=`qn6xXvvys5$1qCL{Q6K8#+M@b zSuz{JCO3zEfU7S8vQ<@WN95;;8>R$RLDE@2DW~uABOt9v=ae9{tbntI#i=V(i*80VRa6t zJn%O=Ac*n0hb)}ZlyViC-;n%VNj#={v^4S7xQdG()kjgcT6szdvFzh^HT3M=d>lBr zx@vBSSb;1bNn6G~4SS%%=~{)82&Yn{0{^FS5Q@PEiexZ2%2^umY!1|Zfnb;e0zn9G z#Iqf&sU@gg0_7ZJN_c|ZB8HP&l@f)lU`_GQP$(43T9xZ>*;UAc!aS?z&^C8!sb#=b zay35kR6&>#{x6Bn&S_sqRL$h2wt5E(m}9zGyBKnBWj|ek z__ui>74`5!QSwxDk_7LPY>fr-4AGDNX%xL}|Fq77wO=m0J;Kee^{&;Z^YwmMmxjLe zhlR*cH3qrm+AoRDdt-65+6z2I;8Ug@mCL9Qu=9vl&*M;oK@A4z$ve-p%#s~$nIZ_n ziWjh@4i0`8$4TZ^?06l)8J1j{wWB-IdAKo>#8}HpR#-&A##-cAzT3OsEoVurRxfqI zOIg40{m96oVgxF^LJgR5CxU$X)}%LH?LoJ95cfG=eOn`QgSp3HIQL86#`!0=BUs_E z%iWE(9>?q~yeTUJi@)sOc&I;JhnYpw-?j}GJy}PdK^Q*0#+fXLr0w!B_U?q50U>Z@ z3|mM(O7#c@LvmLYf=1Ho5RfxEn5a2d3jo}SS5O0&PE=E`U@Q=gFL(j=9tX+hp6?S5 zcmz}m9t{YzPN?Wnxv_H)FwXph5gWsSO+M?{K#x}C8vqEqT|Be-IqLp4N8IbKj{_5y z^afdv7YbV3-332|)H_lVf|Q9i9p!l)rX0=TByvmRy;9vwhKwF39DPel-=O*>=7y%92fE>8LA zfb<>o&$f>Nd+3CyOx|{LXSuXNRh2{t5EU^8ngX>Fg%T0$>Hm!C{~Gcj2_&jRn@rx; z;Brv$?_1=C@vbwPw#cDlHf{~`h^ybAykWqcNrJl=9a%V*T<90|c}`k&A?Y#68O5O4 z`b1@b>$IxfR~G3Gpj}|^H70r=M%) zXL&Nw)lBvZOJ0c=W>s9kDgs1EnBW?Uzx&Duv}>tivS!k!&}F$=L@Fk^YLIF;-C|<2;6u z$U^l1)p2b} zSou*>5_Ie@lasgNN)MSi>eHUjs@Krkoy(7N`iN5g@a_HX6N91twtt^7Lr2Ib0%qno z)p;@!qI?Mxj-Ng~It~Kn^{P~J0^Xgi4a&=IBZh&`hnZ#+qb<>n8o>4qNrzJ{G&r698!FL7wVB{}VxPVu*bh#cWzXZ#`nix9{jj+YQI;j@y{QDCC# z%?rI{*x*0x4)n3v&j>;h=SMyGCoM}JIPFF@FvbhgH1~V65>-$f`!Pzq?11!s z<;DFMU-@=#*YedC+!M@=)#+by317Yee1c{ZFT-G{c!@SgjnAiQ2Pp7rbg)R(k}dgL z*=ZCY$t_N9Ll{1W#>gx0XK<9Dh5z4yaZ&QUfYBJXgW%gwbtTSwFM?rd?$H6gj&g^g z)N<<&7VT8Vh}6H1I*ZokHu4y)tykm=(K8)tDefp6za$WJ_?~6RT`ToLs3Kv!O)np| z9c$3rMKZq`urQaa<|GgbGM?J<#+v5gbDe&OcH97x5CvlE7`5tqeozMFr$g3AsA+NMN_p^d{Fbu}Iov^@kQ#82c1NbH7KBZmtA zG}}HMb*~ zXmGT#a3yy6>BL06XRMrZMkK1kPT+w;;GC2?lzQk`P}pCJ?`}qvRLsynQRVc=aC{#2 zd&e&&)2|-%oAoIM#+�ZvZ|D0TB;()1O*2K8^RsysX?bYDk+s`5U^=j#!RMn^On^WpmP&g$aWq{^xu%;EO z6LqV>sL(a24)Rk}*c=J!wf!-94>W-KFYuCw8$smYF~A-CDIpN3 z-U+%z;L|{`(Fr@~TQAeo;B2nSG92kY5&bqZzYeA_Q#^_t5c@$beHF8+v0*z>;^Fy? zXc6k5Qwiq$?;1LL=|wSXK86wXG_J;4&4@9JkxITNyOl4)jK)fSs-1m!#oKwsu3hza z47nZOtf%8}-KW`bD?QI;%PL{uoDVBlTC>Gl@Q3&FOlzLCyfA5!UJB-g74%n)Uh2ud zkQ|y`^O&};{=Mw{VG{N2M4v?Xt!3#@D(Tn=hDR8{(5NNU;>5T}^ilyA%|ePJG4$Vd z)4tYWt6}xVRAF|CvD0m)4z@-v4O|<6095uN;~t*k zOP1BvNXL4e0!a|SlpF#^qJFy-6UzTb=Lpt4Y$pf==Op8S>M{MGbMz4RCv&fUqHc~8 zZ)e)`vT-L+PSI;V-&K5m%onZd-t(1Gz?fV3rh6}NMDl=Nv`x6}pfo;e0cK`{+?+zm z%!dH|o~^)2w@|X3v{X1~JWli$qA)+l*o@YE z%8xg%ZhKE(g2;g+* z0z#QXVRa>_n)+aHLMVmcDV}BCnzfg*6Dm$jK!Q(rSWFV)H~~$?PTHJ|m9s|`@<-xo zxg7hN@_VHJLaz)bE5DS@{O(ZTSeMtQH#zUXux5SR>qxS<3q%CND!8^Db0s!DQBg1% zf})3I9{WCYYN*$yt>o&AZu~Mh-lwGH=o4U&sPfR1?*@>S^n(AxNo@%0W3FmsJL&yf zYhKLsKtd|+45v=rQiljjC1TxtjtHEnNj!RT6KlnRz=O>aG46tZr~dDw#ue5NDy@1* zj@KgpvCAM%st-}W2>=Bph9A$(!@OA0@%hUkD+a+fED|g;_&m1OlhU9sVZ?tgIA=g- zX4~FwrwV6_It=@?ZtpiA!f8o-*Tf~S_$9sDrk1b_!;8yHRL2;xlp{iQ={Y*jj`P4@ zF*-6sVV&v#pCkT#OxLP8YC@f4=2M~;>a2u_+hAdxb8M5ZDx`_i!9tTQfFIvc;ibbDD)paT6+5{ z@5>fO_T+1b)RTtg3+XRfv3;)Zy%amcPv+(CB+*hx-*3vPu4sIPJUr$Rrn|N2>!$JS z%#yo4)E@xjN+y-+OChkYZRLUT020Z zB+LG;VNG{{496%#b~ZBBkd2UswqriQ!zzX_*4(SDDqK$KIyq z*JjlB%@->!-W1vjh)C~sg%`62>MM%LJS<8Jv!icKTxNec*mWBBPo2WHvCXTZzO-^d zRMBJ2Oy}9UW!~-2@^m`65$=9hfzLqr~Zaq{5)nRtiXfA-Xj`uz>Sy!=XN zrTXQPeR!FcbN*1x+(jXe8_RM^AyjlZ9|q)*g;T*RrYJaOLtYP0FRh!Vy-k!HS|`fh zeycOO_-(}SJTB3ogZ_n7TC8qJ+U5@XEWeZQQgkD?BaBfihCh;nrHDb6PWRD)wgsd* zJuRL;Jrn|y_QP|oAb>N=JmBnZiXU&q1hSXzrKfcOQy5hGngi+B4y;hv#s8vkA|NUl z6rwdYxb_>C{OoMW+AEynQ!4FTHe!O;{-jXyrK~`0I75^X# zLJGnnY*547@p|72gnph<;_0A|UDy(BmMg|vH=k?N3mMBT9?TK{m30>?Z}bTh^5{tg zk=vhV{?ein^K+DY+|$I#FjcXNK<41nUp_Sp`G^0u{n9nV+U83r+qxhRyw-S)J@>0O zw0P1VelIOv2EoBNy9lB87^UN1|NcFgIQBr5NiJXPa|ZoCf9oDwF){vF_Av79z+qAf zkNSY&5A^b{v$MV-Qb}H0o0I&b!8jT|!pQ5H+=)yF=Drb>V=nda#xDm9-M&bbn*Z^* z&FH?s;3IHjKkF&kJMT!2nl5%umV|*$lt|?-P*?jeP`^4z`xOBq*ua7wdBWf>Pg>VAbD+A10%?<>k=Ch6~vbQlOOTD&^kQrgue(H~4H{|Eqde{}4C|bviI0 zxgPqm)$FQ#-a#c2gwZQp;tgfkHkd33NBtJYnC>tY9y)iWmp-Kuv?ts%-Jo{11r8))Z(F%yp|_5B1ZQ^jJ|bN({2T+PvVz%q`xk+p}xy z;1S%47cp=iPA}y)=2!Y*#)$AhcmMrP?|C*y|5(t*DU&ZG_4m>&91mQf7(}vGZUi0T zosj*VKv(kI&((qA3j(L?S6q*E6V|(b2L@Ap`F5v|k~yT7nC9v{`~Tuwa8ahugH;N}q=9;GLH)US3}dxnJ;2JjUBdVEWwlPR---iZQ(v_zngjXg0Ye4JYitIZ)?G z`}t?i;<+!5tHoDc1kgWw`TaG`3X_rvmqV?&wvnbNjl`=i4gu$Xtb>Z|Ygnkq9Jr>= zis$yjeo_c)Oc+MArWx<1Eso*;eU9KfVTJQ&1QYd=5|wOW*?oxOv8M1KYHTTh1>M30 za*LH1XaQ#x;_k{w8V^fshDh2@)FuwAObO}|$F-UeAQEw8^%pf~>vy^~=jzQq4KXW$ zL(~#eZ(asAXBXvHXzj!#xrxXfE7{J|nanP*^_Zx+yvu*6Dp|6FvD2@8apmM~X;SH# zu+|zySL=EB?Dr%Omt1`gqVI|GPW_V6TRpw+yZtVu`HeGL;pMSD(+d?14UeQ~f*Hle z(&v(&f7@4H9NJ;zRc32?`SQN-h@QF4)?BboXmV{)_L^b1v|J%?YV)xqO8Ws0YQBOM zJx9d!dkVotr3r=4ggLNRfBzH^a)cUIoApG!BOobDX@k@pBoNl(5Wk^WwIAi3lbf8v zD9=0d>c_04MN@emtG8p6|4m^Q({*ACTDmK=BCDU}aSb7ht^5$9Ib5Nu4Hx;jZ_<@O z`>bQ&n)>!tfS{Z;SFqO8U_dujCX+$Qgn*cBwM_6Pj)%+T*bT@dod3Vd2q__qWE%fr zHIJQ-WlyBAV?epoLVWOO;GbIH6o`ijjT#w(JTZ0Lj(=4oalu-WJu&+S-(jUH8P`@w zVOtgD^CXoTa?r1$^=v-_N8#EO-G9+nWr&kWAZmE=pc5 zU-WNLPSJ;c|JE!1>|?6b>dVp)px8lDz(C}kBZl)NI)3;2+ zZQ#EY)lZ*vT<8u-|Ds@Xw7%$L%LasKyS*4TT#H{UB^$5f+BufCu|J9Go-!Fq+LKaY z4?&}AV}biNC#SPFfGOUO?XgZI!|nH+kF3N4STSyA%Q&13Z=t!nYx`11NgGiS6hgg= z8sCD0)HZ`wXm?ODk1yik#u&j@a7xE@cgi(Rdu;uc*BOFkJx>_ICNl^>f`PO)Zjs1} z?4WIN6EC0bP4aSjACb0{7`^fJF9fMEO)}5cFO$$zsxw=bX(e|(&1adY@>4isv_UpG zRh8?uYx*(?`FXDMfp62fd-Ub<;YhZ3Jb&%Eqm`F)H;z&3CAJ%{-NJ?*@2L1z86@P- zReKbEmvk?uQ6HGMnujjY8I4M+A#%^&GDZnB*3ZdoOQ=qjjNf@PT(BXfc3NC`2 zS;96)ui%NAlPEe_;esxMNfd&N8$l`H1sGIFq$1#vn-T=>h1Ty*x!aRjc@ZJ_D^H_VQJu`i#)^fVYBBWIryNVqR@wu!EyaCI z@2!fqS-3^Pw~E04&|-$bpykGMej_#JkNyhebNnBzB~S6)x}CG&-ViZ|irJkvqI6=k z(aWC_5*IQQnYq}hDj;|@gGpYFoj(>WXAnjo6E5>F&i*P+8=zyGr64HTRC5r3-PF&ZEc;o5W4T9~40_xTfCyDg`|AW)=AI7?*w~}S!*DAIK-aB zh902}enjjQA_Z@wZN^0L}xm_U{7Ve#0Yn&IBX*O#zod8g(f%^hl>?CC-t`EsJZin$fiQJRVTtU_RfsstKig%iKs7; zc3c#)IA^(tyOxkxNlCdQ+RE|eDWZ?|MP3Fp!I$Dt+AAiq5}Pg(2FLjoMkWXT1LbE+ zA@?=2)fgWx&xddj#|N~%CnSa{Ss&#Nm*nXfeH?fhTBzd^$p-%@(^j`*jNYlLjEdHc zzyw>qSmgtYhij&;`{5R*ixx$UMYwdF{8a}iKvm#Zn?J4MTGvzO`~o+h4yrl3rfc6p z%YuTV@8z%Na&1bbqyigvi!jeqFvi&+(s&&mSkH@Hg`G&!Ld4aTL7A&21_x((zL7iXQ9pXO9MuRV%h>!| z+BgCi+!8d?2c9-0UInc)qDXpb@sy0R@wa6AByBosh_x2-oy2P(Nn(eJix)rc5YIR* zZEq+e>Yj|u-j${n0m_Rq-g=3&%U2O-AH6W{-~8ugEw}Q>7HR&v7A%e%9W6T~k67`# z-_RWsP!{G>8~c)chU?ANn*Z+rb^82&pJre=scFH)i7S9a;^oaCv7bj%Ah%R)OpseO zUUI;H@D5!ZM>03d5!w~k;racIgBbaM{FE7i>bLl!xCq!f`7b;*JP9$$Q>|!SW6`il zN-7@Hn*RMh`rb?_kk=U1*i%Ohkz z3Iz+Qe_H6{m|ya(UWE)9S-5OqjH8BKF60$&BgztqIr<3|$KskfLxKxAT9^3EMXW_3 zs>)L0|KIbtPdS8<&tHsz<4Ez6@THsk;tV|cu5kIe^LDZs{reE@lIk8bfjZ1*$Njoh zyM@^By@o+w9Ay%AGvwi;EOyb}JinngKak{#L7BQwao+DPT8?LjNC<&O4s!_y7L~$2mthj*@*iqKL@e;~Zrcj;yRw z$eza@g(D=6kv&hcMP<*jva^9{?fK=Nq~V3&p@S#ix#~=fP9=(% zSFq>q;t{2FEmc$C5+@Z&c)pMU8}~GqO?b#XbT6KI22x{O;23{?sbNCsbF?St{V^*V zdXk}uMIEN0OvZU&vK==;z&8{oiG!xfpiDXt93;?MvN)I(4~@d>0G!$OIZ?p-Z`=*$ z+7zqM-!hXbF__Y+>i8o5y)%UAn`I;!!5MG3iZ(J*F+tfagX}%gU+hb-|FCLBlao)H zD)?3_B*f0ibRN9Y=X_nYmuNWlYWMRVvv0?aX&h7anS$11aAJd!%2Sy@)Ln39_cTwb z)wY3c_*zwdnAxpeU9xX()cGVfgJ0u&);DJ2$(etOyqFyP185vsw6x$HK$7qCE9|0j zB}UsTN%RCt!uuU(Qe-=8s%^m8mzt(d%OF!0eV8fAL}_|ZIU$(B^ifqVyaE}j>>{7> z6VgBXre3VGLz=0F!aBu)ol{5c3B96^<@!uN((aFuQ$tMpS`ikBFChmOH zOI<1ha-*wtPHE z{_1{rG)URpLze2tQcnpB9pc&eH2RO~8LDe=WAPnXI8}vwvJ2?U3lpC^xCD}V4>3x8 z`kf>!+R~EW?B4qc`QV%m&||tAc5j_KH%-?C<@3YinfuXF{FV6}2e|9~YqCQnmsz<>eZw?FhKkzwz|{a!1#Cn5Yol~jgyEj1thWfR_uNhI8xTuk1|cw%3Xd#{pr9`vW%A0#`S zXK%qagF4Kt=sR%7`2K8f)g;r_nIbnSc35qvpjGT&qZ)1$rv_Qn3jHACM`CEud#R!2 zwJOS!<(lbkPPt_|;%SMhQXgw;mfbIVx&C1tMk@Jo$f(M65|tHL}*X~Zp)@*5dEUK|6H z#rur|m)tDDUtWA0llU7bf7cGL^=6CM+G!|;xu?dqbd{|uuqwBwNOH-!8y)z$(H*^G zf6N1uIYz4ijXAk~0rMfir&voKt*H(+-3+h<%ARI2z);{AkO*8{TA3{@YcMR@qYDx( zgEICe&g6S3eJ$KOx8cmQ+2#BZ%#L9TNK{iig%griw3Uk@8BR$jnT>44%|S|xjF^&X$-sgV0q2arSj-lC;K2>; zp!{!Ni{4u0$Fz^MW@Y_}diK_uDZ)3J|3~FIt)q-PIyrF4jfUGEOywf4%AH%_M+1*+ zrQHl$XO{Tj?vZRvbs*IZ{mgshE^^&#H;Jql*QMPUkra2by1Fm_X(Tb59PlrDo7Z2)anC1m&#vnaX}}OzVN9xS>ORo zXs|ViLN-hUuLVV@FDC_<=MdGeMs-+6z#C*R!|?*zf7{Gsn}S}HMds2 zw0SIHcp~HQ#PBt)bm7myw*xOGXbA?@A^&SnBI<(js#S5 zRi<5jt#l+|CT=({CMN2^vCHvY?N5WAe6!zvMatP15ORMt-|85PxsWU)c*gWw*`H!Y z-}G1hHKlcLzJA(m;}$C}IG!5#ODD4s|LNs1{(j+dPMPXtSdz<0s9?aZGjD|6H^Z65 zuWn-$ezsPUG?XpWIF{)k>5NO_-1Z26t<=}g_pGF*KNqw6%DF_jQrwFh>R7juXPI<1 zx(btDM*J)yFFOOdCThHg~fNt_<`-*x|8kjr-E4e&HFU_BsOMKKU3 z8QFhFCOUv{i9&uy@V6@lTDBLUF_OS=+&qiC=O^&G5XoB|18>cMR{42gE;4c8>NOsU zw^+ndWdDQRDqYIdJ{W^UELpd6AQaUz_P1EWMc`6z)|JNbHJ(z=-&CzTp2jm-fQJM3 zv8od=i7_Fukg6IN^oJ%ih6m_}43%s?8Al<$o`o2(E#H4?> z4ZoD#j%At#$q5&$GetDTGqj(%lq)Qw`B# zv2^-W=No0g1anA`$A}a*Lid(j)`OhN4Q(oe-XGG=EQ12S{TwCr+T8hT@ zke#)m9!O%F{4E=}n2mJ9{jb(64}^m*yeIqbeMw~ZP)(m``Sn^D-XU-JH|otM;r6~` zsQSL*xdtZtZgJ-@Sf)86KGVCY*bEn(^Cj^Ui)7?}Ee+Nt)4tCV4*M;hGXIYHVZ7)V z#Zv6gtc-^c=&Snr#y*aiR+^Ts(H&3B_}Qn{sWtz(QCenRl4L=9-G>W$Mx`k^ODA8Tv5smlL_=eKGYBKdF+ zTqVsFT;9(#Uh{AarCEROH#*70nq&-_#X6PgWn|Ht2~~jL+o)StvAasp=O^!TtEbB? zC2k#oV}{!)$u?K=oSkFSqUw0sO;{ZjDEcgM8tn<@i>s9(Pd}Ci!+YCknY!2>>W)=4 z4kIe{V}j=MQ;g|9jqnQ_7fw(GTSV;O_3N!Ef0w1Gz7j(m!{1z@MlFM$zc3cnd?R!F zHs#?C&{C1@r;iyYaxE30%cgkX{#Y)M`EtN+WHeP85k)lQxk;XeQkwaW<$|T1pevz; z0Ra}ll(T_;Sk6r>>&a#y9VKU<8wlvy zSD6qEVI+-B>j4($M8-bTev~SDf!hKpGtspzMnk_P6w0Rlfh+hj{ZD% z3~uD4U9dIIW^Xw%pidXMZ#yNPO$1cUHMy$ygk`G{AWooX8h%4VBZq5$Lx64vbhU1> z^XAvAjBme_2hzr|PV(6ZiOO?vp_&Q1s1wt|@(gC<}_iEwl? zR{01~Pb}uE54v%iyO7F$NeU4BeX%F3u^<3TSXau&?4G^VlJspB&`D@rG!E|_qJFg+gi`0)ewDpIRX*` zb;kO9QMOavF}Xc>o37L=c0-NtK_Ucynq^-G9AQNT_hvOlny2lAbrDgcjZDv@cFqxK zzb5TVvwCL(^^s>!S?9_ilI3e~yR=x z+r6%E31n0j+_OziDd$+ekoav#&*5u>3+>ktbZo zg3q*EQ(F-7TBAsY`+xAh5|ZFdSx;RTheyx(wsdq3t&&53Wx;pmFgc;_o`!ZOzaJw7z|(2hUrg@;fFYNG~>OXHA!Y7bF*S>`E*IY+%PtpcZ+K_9d#`Nv`kj zm=ljV!nBHsevG~HvB<9dJFSdUbXL5 zP5WMk!{6I9Ont*rtXsj`w*|LWFPkaT5$Zk7WV>hzG#m?PY@7X}m6zfWs#v`ka%TJp zIg{s3(3gqWAQ8AP$~o7D5rtZ-*E;c9$fP&-yGUpqo&G1UTB2LBS7=x@^CxsWaCu&l z2KKjsrB%y{TFclWKSf{L;PHirzEIlm*bQ8bdEk_s@K7};APnrum#lb4EGAvjqAbX` zN@wJMz;sHy@Za*xpMyu`-1eV!eb=sv#XuZ+=t5j`wz z+nF!A;t=&rrzWU``^<@;X=ofkBWuA5{T#ZUyO4Cb^N2uF3l&9wN7|5~Hz}#nNqu zwjLaXzNyRV6`Z)r{X286);WN5z*&aD9B>?2Z}aCHE*Wl4+?wgPgyebmGkkn0l1dwo z|B@seU2JQ8FYsS%+iE5@D``>XHCC{WrHY4@ZK)OtwIt;N{%3{cnOtN%FnMdJ_&SX1 z6up{;GCU<=IT$laT{z2Rz=>o@k)24me|sQ~;Y13@Qki3hdK+v3HhM@f^9Ezv+op`cnV0 zZsc2V|Dl1Np)SmC;lJ30Dw4q10O!j8a(z{1G$)(2WJW<$?4mItvb`gY`DkDzk4I3< zS+YKQC@`v%oKs!X)#n@)8=*I#E1pGA$$8zOMP{LrE~>WNJDWDCpW1;ylwuWp!9)XWU13 zH&UVA6WzQfQ-H<`2R3uj*jwMTcpD}f>HFDjj8@eDRLk~{ogGh3>@yNcKP~gOf5&%< zowtAqKK-N|{&?st&#Cl9f&9c5i{uL78FOFbo~QDsA**Z2rR)<^4hINN{+HS1?cn1E z8A&UPywY|$ZM`!W($!?)g;-XtR}rXRxTWh~^)KxuCMQQJ9?-1jS@18LpI3T$^)B>W z=JiKMdq!I3mFF>fd1^eHQTTUmQ&X;?Mdey4wZ7WR%6xb!U|tH_k)va+o!H`gq9$5W zH0-!nLlK~&YUyjDIlbJ$>@3nxl^Lr&A?gG^Vuv~qMm_6B#1g{8C77ow=6{riU6wwG z?qGJA$j(SV!1tQCU2BKe=KaE43TrbP(H{zbd8Yp;nTuOWbYJGg@1M%<@<2o!D|_hJ z$H;?&DJz8g%-Ggx_-K!Fjh@cBtf*KP-iUrv!#>W?TN-{K@HPHg(1FsrQ66 z2Nz2XktxF2gsL7$_Jrq4H=qEosTp4&U2WHe!@1niQVrM#!IT^%tL=}WNrZI<3E=Su znqq}yab&1dG-j%hJna-+R*7J95~bz}2+a9CgXQc8tSf1NJkqfPf@QOSrI#Wg)fXt) zWuUv)3H2kwdFWMHPSFsTQu1!>gR9weghZx)KfUCqXiv;hi^}wr&!C509b{zm!YAfh za&mVOF9;m}8)W-HW0q_mwNzX3@HDMvo3s5Q+V0>{%mBIgGnKoKSU80Tw`f;`c<~yn z2N(@il2Hz$G4mUp#+A83CjA!lO!)%kLaf1No1mgNbntIxFNcj<)vqM=g7 zGwmeg%tbRLaR*Nf*aiRbODQ~Ntf|oBn@Hi|@?NKGBc(F+zg|C!3OV_mDE7AKO?S!@iS0|6NklCX8FT=F~brN%$wSJ zX{lU=FF6HdB+Ho-b|K75LvJ!V1PqMaL%t;xX+0Z;J}*GY#zp4%KKc?<%t+%KIJ48a1s6o%QpGcKDh9;j zw!ndPwXylPt30qb7k8e`PGD;GP7>Bi97TtH6l0F#34i`D{R$b4Xy`kzQ(ittt$RMP zbRewgys0^RT}Uu^BpA7{y=v36;yfO8Cn$F&S|AL9;h~kWBqaegZqI;!Gz>(q)|V3& zAWd&Zt5P2Y5DI$D{s~CwXFJBRVoGPt=}rrkEvIk`SUXX%@MEU@($TgtnYT)iRL=p1 zRO6XG^%qTNsnx3bHKMMMcMQsdWDr@&ed(3xM;%*%I66wXe%2KdFbEKQ64AifL}NP8 zfdGr(W&j|inCJqllLHR0Qs;nW_&SMaAqjA9r_+`IA{|! z(h0X5hg!zvqT%1)dGVHWv`T6@ zg#JGek$n-LW>rY)lD1Y#IjIn)IaK?(UV1bUZc6#h6bb&+_3xeN^yE8(d~@J!^c;MXf zBT5nLAt&Zz`I3`eByFNygt8Vt&92LG-?I>M2n@5e3dui3Sdw-k`%zn`9HeX4gJgZB zU@ke5X3B)io~}7=Iewif!i0Xd6Fq@Pi-m=JkXA&qHI8Wr@^QrFP_$i3q@Ez5Ygbjm zFsewcRJ{1c9dsKtROBEw{ETtaW{xHFHC;GytNiqg$nRMQ1w`6ObYR+5pvz%TG-)CW z+y!z1cOEzzUC9Gic^$B30b_rRShHUMJw)R}3xP@wXH^PGL_G$q`yAtcYr&?=&VltE zG(s?DHSR1@IO2|L01m|x`L7>NTmjjA#}UHh4!4?2?7ZZx$s1F=xkK5WN2mE?-GeDe z&WK9DtcpgL@>dg7Vs!uY&u20nTK#v#48(3T2;7B^kgF~5*Xl}M3%2_U{X@vKbdfB0 zqGf4+G9FgY-glYiXPlf;2j9jEu(%b(g6r9b^|eW>xJ#U zntRF{%?;M(AH&k*?OiG>wd&6wiD!RfnsW)u-g2c`YD}pn)^3<6`C9P4gk}zys9vRP&OGvYllfg+Z^rJ$lgDn( z$*#LIjGO*5G7C_2!`|Woar;QZU)!T<@FkZwPIMXP6;HRleOD(rp^VeH5m$Xi?(4pz zA{CMEzlPuufWwND44BDl?S);8T(CC0p|dyB}jnnf0JRb+97%<8kdm|LmmWLxq)f>!Js-n6xUG` zde*$3$k72 zfP-4B(CR!#$SU@fai)@M6eNtF%w0_6r)cn z$ZD{xtf(ek(b^s^|K+rDKg(w7$Ru_!o7|FH^NV{gY2tdEy2OK-d4Mvsnd}oGUubXG z^vJQiVqZrUn)*BQ$X&G9lg}{@ew`AlCI6~U4afw2sUUol5+Cbt{CvrmJyaE*GO3~D zM95lsLM~2 zAdu_QEd|@Bk%1F6lAY`EoZg=%Swd6pJU@H4)s(wgke?g1bxLhucuUD&b?Od6W&KM> zuZNttBdw8%o>&=K#=WxeuWvVQs3F_CJexOzRXT|7+3E}l97qXiU=+Y-kp^U>(!peUNWcqV zU*cmQV1^2#64>_j3#|fu9GnW&QsN{1%E4jkWe!2sUALxzzqK_Y7hC z81;VpvICX$W?|?e=0A`NKu@H2Y|U^741~2@QP2-E)}DTS-*?YZZ|DE@Q<@7=;k&G^ zt?!jM+OY3BT{V$6_6L?YdK@)F+ZvgJu){Y&q)<@6k{dWO`qdkd@dBH>(7)~`h)WU@ z>(%#hXKhjQ^HH(a1(@0TZ!Hw(gL1@G3J0w5aLxBYy_kypKYyk3!-VPRy?n_P_gX(x zM^FDTS+J(v&voBM$&Tp=cMiuwo~?f?_}1@$tzdek zfpX5)HGU5AKja7Mg&R|1hJGThNl6R!jyohfG^=>aRb=!XEnT=>lnL=MfU#Ir07GR^ zO0zknom&C_#L=OTq4KIEAR;FRd5Y~t_@f@Gl2=GUy#f}~s1J!xJo$K8-tHb z)>f(6hP5)llIaLn3-7g+|F%f;t}=h*f2665?&5n~XZ^RQc=^c_4zg;;E=;hWYx9M02~z&?wJKap28S3J4m=rf%-TY3P9`E z0~s840QJlkmOh#k3bm>QxnhNSdplTJrRi?|rurmvq%AeE5r7}c`2Brss^T6oFF$bL zx51-Z*L!WItid$d@9)SthN}X7pD5S=mCC@KXS#f1v1P`t!u~Hybd4%2%Xx;}Giofw zW%Q2xXYfKk121`30R07uJfCqj;t2Che=%>Y<(lVqxqqj}bdKhz(mwrkqHuHGe030y~ zH=|;jskM@h0Qb;5AQ{~`N7n>Q@d!!Bb~}0e2fA^i#`^F5WlN3Q76SYU37`00HKIgEs!!#-GV8Q=STkVJBRU#{^WextzepHYV z8NtVN(#q86-<$7eaq-a^>M2qRZ|_S-VO?pQv3|QtYo&R#4H=86&xShOl|Kd(eB*>% zhqXo1-u^)J&2*Bb=dt+}s31OJ^=cO|)Z_)nx?+(o35604BxH`Smi1`Ik~eLo3=^FK z`tc9#vSLAlMo$TnAn%MO$T^++_lka#{JiXf_ia*lGDKJ=mD~B9!R(5G^FauXXe?_c z7iBUj&0I+bjpPB^yJ~`jW;+-hLkI(w6!f#%pTg*|G9*nP>ZUfVT$G>H18=rPyqxvO zsjtrD`d>EmmZo9_r+3A^e8`U=%2q1Wmga5MU-D@K7r7$*R9`JZ-_?35*-FeZnea$u z=Qu?)^_M$l^Jx|l3%|J7AMMyct5x$^?s?#Z-jfJyK@j(9Nd9Lpls5}FBt?jx6Ul#* zLODpeN61VxWuqnT0x5qjTRyFa59*a?GWt=71P?n4J4dTorYq%9B})#j#%6=d<>*Fh zal%yd)bHnZo6umIBsKh-tcCXp!4!_}kz7s@g%7X3VK(+J#9O!`52mxE8OnYk98O={ zYk!j+86)l^)!4qsPcnW^`u2uxg9+U;;EjViL?eLHD#q_IH_-U+Ekjg3=1UwEa8kWh z_$?GB&D)oQoP`5lkv4-BA<=<3`Mm1WBY|s7|N2?XU08ubn)V;42V7BnrLX0=kFgg6 z;m~NNT?`KzgG7j{eGUv!%eG^lEpcgt-T!&W8refGJ7RGpR7L$CNT~7Ll8no8vsB(- zxJ7ZyeJ^!UEoxV0Cn^TRL0k@ryhDr43=|y;Hh22bc?AS$k9O$tR*-{8Ok3~KyK_i4C^u&$>Cc5Y+bxFn27p-amka-X{i^6M@7!SoH+-e z6<0A=wfT}GIIA0Hd6td|i(;~d_KbHDHks$@&nT`E?Mf#mN9K&2+;hQcHI8on*6W>$Q_M2ptaWmi_ zmegg2RO)}m-ck%22MEWPn9%*|WSOp{G=jUQE{ETr8-!@c1`Q5A` zAe;2RxR<&pE&)nV+~ci{Pb0D{ZUznoRsJ&8?bQu-T!Nn zueDt%lJo}P0FbW<2%WNq{2us^AS0F?M{l#OH^Pk=l50IDf35E^)l#(L8|W^RG_+Q# zSXuXu0u}lBlsQ2HsYunTuR&|ZIwXJp#cXR(evx5oq?{c*eCBbpit|jgorFB!jIHpb z*&UlHvmEA%w|Vs@6vBGHpjATZ%J&buuK;7~X?_uXkIKs&JF{O#B{v5~24$a64b;KS zLtV~&g4x$kMvP9$t}y3^_t>6m?enTH1gA2xB2ZLPCwM!IH`$s8BXAKJ|f<+)T-i zi{Kk!u9e!r_J-w~`VJ}&Pv3=8YOuTld0l2-puX`xrQ6!Ky=S3u=ozTIPqyU74Z%48Y7=G?NqTrQS^*Nh9Xx+Js6$SNFC z(KBGOI2>x{id1;tYt7|Hfi*13&iR&|5mcKYwXtdLrlZ7(v5#WM+nR=4dICf;3PT14294$sk0{OUAdU8Tv8;zD zn=_buVKtCGr(w6jsm;%FY^*K#b(PoBr~@T;k^H~h*}nL6Dndle9F)BYEOm%>#j>vD z1MxgE4E-oHmOR>*2!PayOfbkiQHlrVN|yPU3~04%VP#wqC^$l@{(Oo@K!-Vce?hA8 zq`5j}PBdM);9+Ep28W{$ax`XqE5)Z|vn@3aC`}G#i+CsRyG4csLw~~Xp+xPcMYYDo zyND*TC;p@~3=AX#WE5@dAXoCSTCnO?0DYPTDwbEepo6yc^w#oCsu9SCpJOqd>hm73bTfDR?)L6^eO8{UGgn&gmPfiM>JX^Y{1p zDPiU*C-Q?9q}XLF@iL%gGp*kjaL3&*5yP$hj*j(>jSG`i)G7=oZ!d%-MvL=sy5)$2jYgQPmWO1b^YpJ z5Yz-jC!D!OtZXU;pF|+{D-q^PrTtggBUfopq^>Jp)~i&fhc=O~>O|~ZXJEi-Uu`BD zWYYU(l0MaRqBG_PVzD;0OA)d{3l&`PwNu8E4jK^*jH~$&EA!LWjxPXue=NSoXzEz(FHrIwk8F7;2+giET9trhB->Zavrc;RmUf$ZLL*|pbZl%D>Z(h!&>2kj}#ehgey z5T#YZPNc9Q({@L|zu58--15uNR327Vml4u6z?{8|qzPa)3N_rvX^!v2oW(g7h;+9M zY=6l4m)D;VxUa#ke%CF+&OBG>kjj21t>J=)l9zQ&G@$)^8iUweY0&gDv8Xjke&?2U z>^#2xMgO3-HPXS*CToSjoRn$^HoIFHAr9S6<~3#s#v)jrW( zP52%qUUs*A8u|>MDQ|esJ3)m(YB^TRHGnjbjx33gL(=QfMP7|o0~*|Dd;{PhUNgh8 zf?;u#3Zh`vV;+*e6mo#O$a~wQ#8xMT!G!)tS#!UvM-%AUQ?eJlZ#?6WRj0gH~Z_g#UHiNq6=zt6=H&)}X zEAj%Y{(5_^TQNTcOLJqo1G_^EGMrgQi2nVz9K}%?$ z{-)md1TB2|_M5DWWY`-uQqg|v%(ul3w^RG~xsiQ&HyE$?Y*Y>y??m*8%v>b|`6Ilo zKCpLLwmi9InZ58cxq8#+bM$0*=E(hq%b-)=8kGiUf>-?ZpKWMsl4Vtyj);bF?!@q@ zJ|o-eIa8@+JJA_hjcK`?UtFy#UHG%aCpp7)<6d+_uYC3n_C;1iD5(r;PBeQ^_>H3n zkIeh(;lHI zca4al3^ebRV_tjnMqS)PQ9rqBDcQ$XY09 z?QKUV#x-`pSbsGvi(5XtwRlQvZ+69*e>FJ3|MsGEZu)|f94FIVW21fvsb@uY4~Kkg z*?usHI%?7}zs*`AN6N4xIoqb-daq1Mu3BxUKF)OV?fG^6G#lF7iN7r%5VNCjnpxUjNQ2OgpqJ$3!TqEYu=w?E)Ac;38ZbDt?}+lRMx)+RfwrlAwY ztM9_DIW^Vk6!?wvGYB2M_t&>H_67PvH~StCR$~bJhxk^?GsafX~_T&Hyt74yJm`2+r+DN5rWps$jOrvW6 zrmxKyOnTlE6I_Uw0;7%}{`gj<`Q_wYwT`tWO2fcw;p$Nfvq+z|HTQl?`V70K_2KtU z$8$JM@r8z*|&U74O=j zLsnnXWX1gebPp=%VVP;6XTdiI8Lj6VQ=hIq-+>TM$g^Va+;vb0+k2Ot_)zLJj=`AL z`A>QjS~#Hn)^pRq;kET38NAkb?)3sj@LfiS*tS)x98F8nyTjg^5&b`RnHVkNE2uxV za_)VMb z6xPL_`J(BS8j*6J(@JBm3TBcOx{Txy-Y09g+Bx1i=LVC_znj@JL%Q7?FZ_30?vi`7 z$wq5-^cx4swRH#|39huv;@yX^^xZ>*_fW$!)yGenw(w>_Pb2${><%Z$Qg#Icr)R_X zOdZShZ7FsVDS~y6w$^<6R(829Sbru)05+S>=7bPl+XoA2b3Tf)o$GQP;y=FKx7m0) zqV=Jq4S;v<&MohcreVfpxoc;{%s07yG`YLqOZVGqi4wI=f2z@rOd@*}i)Gs=95az^U1i;Af*idnIXv3_+h z-Vp6+SSdj$Jn%itP|j@KoqgA6E@c4G`)XlN+txo?4k?E>^0E$tFZ=mxg92ORt!cSS zN#RpOV-$ci1gdKoLOu*8wT@72lYZ1SDjBD&Kapo=m)76qnU;C?l_^wXucWYe+iiHK z>Chl-(?gSaayzC{z4E*3Zf(4wQQc1ZPz-(R>s7WDsQmChQ(vRAf*k8D5T7>d&-3CP zPYJ~4C;T{F;i%=;lxI)oM${jZPsrqd-baVlkWIRb(;3&1hkl!?ij_KGbGl`QIk9e^2Nj2Sqf8Npc1i#r_f_tfrxv#;;Vfh zT)wp1eZzMal0GzB?ru^)M#&nxKm=gV6xW2Oe#rh4lzhit(MKbihzrF;fR|` zkc;CW=AQ8D_)rg7E9bXNEW~MLUm}mth7g9?ob|gn7|gNP>XR z2j;fW^5sn3+dZ@1->2NcLu(i9Q8$G4J=W%LfH!@MHRXq#5fXJaQ}}Bui+=$aQE>pj z#%(F+htK|Y*?S(x0EV)AFUhA80p$)--j@gt22}^s{Vh59qpMj^GuHG3(YTg^Zd;qh zzH&60?USo@TJup_L;pgKKZIyf^gwx#r%Xy%3 zhBoSMvuk2r@GEmyQ8du? z@1ihjz4e<7`y%h7GhPA%>%de$Pwm)`dP-dP_&~$c5^XO!Xy%9m9s|?_cms z!L@1-#MLj_8O~!@Bj!JC=pej0^7tQ4;y=(17t(YG3GIQ%x4fz~;mxX=ELhDb^n@r; z2_I= zJ$udMJK23GNks@a#_azGijwa)8k@QmULl%rpR01c$ZqcTEk9JJ@ssp94wl2tF8Ljg zaSz_ej82Oxo4=-VStFX`HU&w{ZG>x!jOFxB-4}DUq!a+CfoO=vRjwl>CA-KH-O)I} zx->wB50OA46Ww6<@^VsKnE_N-*tmnV^pc6n1I?x*{o8|X?XbMWShc0Ut2bNS>NG!; zjxW*_KKSFaqMm2!UYycN>mc|Bttv&xS)zX27t8DFGW7bZ2G02Bw`vovdulK7Q@na+ zD@AVEi8pbZagWzll&CUAp~$lO>axsKch05j6|sHZK8^F?%$g+BEhC_3I@zTr~c9NoYxjUlp@8w4ruNwt0FdPb ztxl+T(rW|Xex-Y4Y8bMOe+HEpgm3D17c!?07*v4yuB0D=TZK`|9JnENA2tE>?9vEC ze)nD3cmexMpW0{rIx3esy4~YRayu?0(Dbvs?bAk0w#5F)ha$F9slrtB9=PTfAc%zh z2kJ2KYs9Pw05**K42n3HzH}0|2G&88-e3O?OtYPQOi1q^(${0PmvF6%^LabxH8`zQ8KU`W-@?hX z>iObvYjxe$8o7>T(dS&K6snxxYJ;RNW(AkjG5{*4L8iZ64r+G1ZMC&VfDQ4$n?O<@-w_%<7 zdN0Nua-92=7O|^i_5d|7K_#o@`sfa34$;_oJpw+FB|qRO^=7+;Zrw_8zpxS=_(J65Zb!|fsB3- z#RUbpAtz$(Me3BgqnjzAB&?bo&*RI--Kg6Z_cTNT9&STs1?S-IzNJ)Q~t5xVao?bsb-q{`w!2bN`B6#DwmZQ^4Jzq-3rvv zzF09lW+D~8tTElitjyT8mZ0|U)K4Fe{-~W@>zfgC7w~0TZ+rU(a>We76o&)^5Pj7g z7a*Dwo&}%dzY!D%;p2SXU)!A*LRkgGr4|XciLOD?@jh}fEhQp`6&iGIi4;sIFEY5y z*Bt@d-iG>teeMxg2fS zUTL(55fBM!h#&M{n_KmjQxpX8Qch-I3)DpMJgGRQ-1r5VGS;eKt{b9G)liz?8~Mb> zCb|36o!e|+Rm%d|@_tgEnKJ&i?5iN3(AS24FmDCbsJTy69HL$NtV_u4-rl=37_c!F zaq=75OffQ7<4k$#{F~LURBo;8IkSn@HP&BoUIJVm1*-PM5Z!WQgkZM}^b$z!x@%k0 zBwy!&NG6CR0~Qw5Rlgf3n&fVoemi^bLzuD4vL@q9QCpS~=Sh5|+)nJIDXy~WwYUhhNPFCN`@9~P^S@LgHVs;vEd z%~ht`b#9s5UVxj4)v7O)F(5f}zIan*^kQS5bLt}4akJk;nD%eK-@j;&c~=kg(wG}S z#6ekQfdd;ah*DE-lu~k7sYn425cf1K6E6$DrFm#5OO?EObCrW!i}b~5`5%@5`S5+D zfu?gtN_<3YaileytzKk9%*M7Hyqs}viKULYZFz>@lf1A&gsg6ws`WjJ{)(CDO1^ahjh zkdns$g#5tl^H-owxqd)2KDYpIsai@wKw60v%mmbu-oy_(Bw$S*zNeb&Ji5qQV%vx# z;#Co-=>YR>v>btbwV6aAKe)XK_2Dn^=?UE}zq%LcklWU-oDe z?%OA60l2VhgC8x2(9h7<6yR6T(K+)>$8@P}a@&uJf0OTTvnqx#grWtze7_h?C!;zi z&cL3|HeDbAdWs#J#@2nED;&=~;Vx#p9@lb|F0^63Bzne>PTFUSs+Olcyt998Q zC1-W5*Y`%%j7yGxPi}3%{q7gS0)Iw+s5V!r`3xa4A`o+rq46XuhiLQx41R+Y0&LMN zh`mW^qSvE3cVs|YB7P%j2Kfk&IW+#-;MA;O{d~n<^f(^91`5)hHrhEH*dU;$YLYmB zsHah7xOluqc;GARnrv%b;Mdz^C&t-rl!}?Qub?5=T7ibfZnWCHd+n#ylKMWfEx{}z z!al1^mulJ`Z$WhI5IJHo=eb+6DQ*1pHR5rF7Q3t9mifpm266{7TjJ_<>=RVbxVxZo zAsKoG>@V}glp0pNspvP5=GS^vkYDUx>Y*#0+U9Z3Tx<3fTXDx3@q(k}1;^Ae`R&wj zW@dGt7(I2yRk_HA38eED0d+-Oc7cpntMmCXS6XzUdcTy${{Brr$sqLD=J_kR9m*tb zHQ@#9+Oa$1n`(@k_(h3Ii34j>yCaq{9Udurak=XgUtM^ znnqpk{TZy=PxxNPX4k%NeX~+-Jg{muEhf#y`@T`Y}yb6aZ@tG%7kKme$btOJ#t z9Tc!aiZ;^3DwMPrk{Y2qU|iu$mXdbD&!`%zo*IlvibdbbRLYOB`jVn1OJ6XY1LKiiS&b}+pc~)MMD9znhCbd_s>Rkt` z;h|>dx4j~z3%9kOExr^X`0EzkjtEX$&i@Qtlvtq=GFQKT;2HsnxfDR^E38NgLjzhT zbWJ$y0}r5Kg2V>kz@Tbiatq?_2Fes_E|iUY7|H)dw=qdi9!^{UhK@iE*7P8~F(kV{ zPLVzVkR>q&TfXYZSc@3X*r z>g6+jnCo|GqRW5$y2H*{|m{lMQ~*0+=oz(!gkVNtpuQDm5Zq;SJ)-_Rj}$JSO8 z0@*QejWV{r=6qfePj>(BOP2EhCN7Hyj!MP8VfD8vU)p3Be*O>z2M6_+*i;`R)XyI` z|JLT5dU}o3LRSpqytjpQ)H+rXm;=LU`um0*^Ds{Lcq^W?@IP1CI?tXw+lf(L%XDVK z{JCEtg4E;h{VVh^er1^?)*p0$MA)AY?rxkdTj&gpv`XU=Dq5ECambq^9+fjTN*cAr zpV~bB&^%i93#Xn6l{NUemr?2SNAG?~<#4r{u_Js%m@Py#O1U#iE%HyHl zzxRxpF=HEJ-}SMDL|kOo46-DQLbev!X~9^sbN@9$+^<}>q}|K7_v=Q-zj9z^9The`8gpX(eBK<&!;TYcVNj_F~cy?RdK@6&z` z@Z8_ZRyIju5O4ju^h@~L5i7gKeaDLX!~t$|acSP|mz>kCeW$wSHwmRH|H3>uf^<_t z#B2>FE|!E!dxfS_lMRL7>%NYb8hV!KMs!%s#EK#>(Wyw{n%d49S6f>``T%7{6M+%y zU5eViKFGARK{0Jt>0=ykwUF+Em-+YSR4TZ>VAM~L(apCxb1KCY%r}$G%#WzKCEAp% z>}ImKzi2r^6l4pTI&-vkwOcWn`y>06SDl33AS(fJw%mdT`t}OMfM0#}bzettmi(OjHp&(Mg393&j&+%d5v?D69Yx9i zKrt)PgD}e9&%TpWN#)9Ntzr)x{4Pi^unPkF-GiafDTIL{!gmNFPZ$)ID{gm?NM85c zMIDGdkTi}sdpia#iRxsK1HvHPrWk=^i0;*>d;5??k+?9q*N4R(Lr8jBmX?lR(v1%* z_b8Yz+58t4_fUlQ+shH16s{@Xvc{n14XvTcr_}U{;95cy36JQYo}fWO>~y|vc;+s^~tmA7kQ(fC(X53O(iv%{0o!QxvoUduXCDv zR(NaSG5Ni$|H>wzXiC4^r>Xt+tJ-(x+GC@W8d7_2>AUu#ORuL#T|6H6@Iu>G+0shpoaG-fcqDn2|S;(JN z7m`KY7VR}ej&LfJnuq2{>Br?3d1rA|Cb(7O$X{9Pv^n@QD?iTlG>IE@w12L>>;2Mb z>3ka1dffiPiBVC2~lN6Gao%xVVXGDF_MJ68!9@*tR!NkE+S0-L29Y!*nj z=i(t%)KyBdDJH3 znuff5qWO5WQuc=w3o5;Bxz_cu$LVs;mM5yqQFJg?^pP zOP?}YJ%!ssKU50^rK=8=o?QO=bt}3!Ftx2@I)5$YeC6cMh~GA%W`;d+hSJ+Sdm*4S zt)|M;?0BD2c;+NM_VvUSI$(O!X3J$HRr%NT92^~m*naHTiIo4a+^ny7UOi;6e!yp9 zJM1i1knihO6we-7Y^QPb{K_wO2fxHe@}s_CcVc&Jtm{&S)Su?Ewp3gwsx5Umw~Q&+ zFKzjfJ^5WPh%~v}6Qb{J8BW59L!1}R!_?^6KLweY45uk_7} zG~1*)f}`=W76I{zB2bA`x{8?`;nIqcj0h$0>wDE@5rUl>2*L}2Cl z(XRIUQ5p&&apOV!_g<{}m{=GKZn$K~h@zeS(h5HBiLsvwx!r9me6(`b`oSGX>h|A- zIQ*`aVwR^4Ry{C@#m$$rEb=^}&42jX>U>*IN&kBFX@>&0>f{<$d$;rpYafh8S=o*Hli+f}sp->05ntcbWQezWT3iFCD$zk?+q7#hock*h4FiH+jzB z!VRfuU&M~44i7l3f2%6UPS>19z`P0<8FRW*@t)5Bm}c!%oZeY*hn+(AOV&yC~5 zL)B{(yvi`j2W$KHT%?6>hKSVjh&X>?y~sZ$)f=R&`D~k#wkA*A4XaiU+GjVStOQek z4(P<-f>)!yW0?PVVT18nG;uc&VekZfFRUdFiWoRfi2@vRP7SbgaH7$;j4TGT?f@|P zq9YG^j&KY!j>&-e0V9f=s4^}msl&_RkC6ngFxH{W8jO4g(KclpYVXq^7z9W29`))Z z7ze|FCaA}<8=p+#AjX+Lm0sMtlrTL-a(4Wxd~xAL$)0-aCHOa<=#WnhN`+Mx`=#Ayzp1oF2g_c2 zbyFo#(pC^Fvf8yF=38p~Jg<;Pdy05O+URdHq4D(}X~}n1zWyS;M;MAlUV1Y;vf0h! z-d&+g888kJoeCjPntoaPNxnb*yR(4&A;iHFqQ4xB%pdN~tlH8tKG=$EMW3(r3P1QV zPKh*W;ZWcJUb?KG918}G{*cTO?gvQO5#!|t)UWcH7Nm=c&1juuvz7i9MH_0i$AF!$ z4q{dC9l1XB>f(Ewk86HOEb;t>mRg?+=Dxtfp<=Hee4stK*K(|DOx*EB-I}#=MAN4nCBEq#UP*pA`HX9n==l;>RpsvlOS^rjP>R`)l9#j(mFxzMqe6uk6tu=5 z($WKGG|QmKs)N0v{BjRmC75nKoLVJp0j~wN3zi*kNHi73=>gV~JtbHj^=M+)jsL0- z8|{^U6??wICbN!$b>;X?TQzQU%bW`Ji$l?dv(8+ryU2W;cML*oAShF{t(TB{E9St- zBlQKr8mT-otecI^QT}|t<4!UsF=AiTr;+nQabsp&Ji4e}mCc85! zKPR=KxX!x`{`0YWAoVB9QN?{|_4TRU@R?ID;(4aNhA23XlG2jYudD02XJkH&I~gA| z4ad zAYUT~F({IeIB7VL7-U+)zyn~G;dJl*Ksdrux0zWBI3$lV$kACHf@}2H4#`^tWTrN~ z_^1ZKVc`ZP?=3x7)iMk!RtT1p>+7Z2Bt6*yVP%by7f(QZq@bVQprBs`P-In*H*V%& zx+8IFuLcoptju*q!cGiwehgXyU#EdL#A#{_BGN~=tBYiOacA4;l|24as7K9g)qh~gLoe-)IXhV?dPhb z*DZS_kiRY@Q#sdB?Gsi4K`&n&$chD??3i&^JLTi$y1*fOVi7qbx`zF8%dsc^dq@7W z^bnHX@>2eJts^+TusK(beGb6;)=Ra<*_hc=h{A-2~wb0xdP}Y2&Pp+cQCL61$10CZ0 z_dh-v8XLD?yYq3`-+$wuptgxny8CtHw-JJBz}WM($Ui27?#^%Q!__yp9nJKd6a&T; zj>>GL-A^qeC59LiyuZIikD{gO!ufr)LoX?6mke8T9b}7VnO^+Hp@fltx8_|Tx@Hwo zX*~TI%)rgwH8B{x)aj^dp_TfnXL&M zfQbc+!Wp0uRY2&%@H6>s3R>R_~#@(%!oB%rxM_FMSMdXO5r{lM2z5HvER zB`2x5L1f<`yZxpyS*62>NH(cnggJ%zAukuGN7WIWHXL%obGidYa}?QR3VIRc8BZto z$|-bkrn4qfD0w|va`IhMG}~JQJL5!YzC5pYph5t@kU*YrkqzY1i;*JXj2+2$bLE5` z!Lkb5M+HF6F=!d>l-OX4AqZ%Ze?vU-!ZNFCap1k zLbolo4bNa9{z%pPf4YiF&nFZHd@zp&K8%iTfAP9fMeE~3B@R-uB&Tk4H+s>5uJV;Y!@PFi44qh5f1>-6oR6$NO1-$EGj-4!%gPareEe| z0ZU&O#|)V=8^C)P$ayJn7(R~K4NOlVKotl;XS!l z=MH4F&S%^NTv3?ZvBm~Exu=X}kELX(M)UXosW0 z(PhJ7ox$=7NHPf%HB~=Tj9cahc=_o$$tGAk%~I|fos&uBwYuuhHJ1l{q>5IQ*z7Kt zwws;(eZ*)pBvRn*EeT&S^;55D1uJ4VMsr^N$&A*|eGjI-s#34Ajp54DG~)vcPV)cg zFxA|snSY*`NgHMVI@s0n?9>;_6O+F2@cZ%arNG! z_sGkqRa>OmAP2iAWwoBD^OvQSDVPpOAzkxE@j&&-AGI~;YZ0l&sn#aafAKd)yI8c^ z9dA#MyUdH01yneCFi;*uOZCDrqGZTWk0zRe`L=Bh)fSNie+%cJN0=YDy*jZEvl<*D}DvYzGxz@8L zQ;UuPH)8xQy<&;}Op25N-fvK3Ro!sf`V7f%J)F_53-a_`L?}_M8ez_gbOost)4K)o zE!R#s*FHpYQIh8h26ncFQLd_~Wi913?eD*&zUyU=qDAuch}|^tQz|L$2^?uhi=}Rc zT$gyes(n&r`@EWKfT_cjJ!9uXq(-4cPm_?M7*nPo$LZE^+Y$|vvp+wglMQOys^)Vi zoj>|u|CCxQ#QW$U9h znbU~-q}V>xV8J}^Cc;sipXklHR8W8PQKJp9?peaZ73%5;^&4F?S6wHE>P`Jzq{o(D zy^fk=Zq-fjlM*Set!?~!h*zK_#N1MN!)5$fZC2H6-hjTDWMW}X^`pfL<}#;6x~1de zdGB6zi+Mg%R-B8;!)ybv4JQi8Vb3tJ;0etL8c;9gW{O$>?Abwh$07d^4h~Zz4nQj? zq!ylK2jD7)s=#Ahpo#O@R1hF>AoUdn%2uv11QGDcpa^8_L*zXxy?@$-cMFj*Jt)RZwB8QI!pT8G#b$oqoR8gz;;OVK))6y2VF8@b!A?*7>>$*Kc=8ri@SK7j2!gnpgVZ z+m0rYgQC`P{-WnBH3YR3R7e-4+kHm@>wewsV^w(aMPIO0_0muJHiQ3#1696g$K9gI zuY;xTrGdLnb0B+Pk#f7>2t$J*2rXp{bjn=TK~g9&(p!=nXy0|?N7bD4yK4UiFA zQP5>x3^#B=fV41&h69O+P9{zKBzY8IV^u^XESdv90(u87`Z0oL_~9&ulmr4p5W+}> zVMK98ze5O!KXT9m*&K{CT28@qh*IZ+5$^%ni|gcJdTNyj4w@POKn~;F5~zP(3?j_` ziW1z#BSY6HcIWgho`4Wm_2EF#34laARI4l1-1XQ;vmDKhYf9t^Fn(yXvNtY<7YRPL zB;$8*u`R4VdAD6Pra%38z{H1F70*JIlBU&i9g3c%(-&JdUf3zbC!1MYB6{JA8x)Nf zpvNKD%$nSyn!**cJ&ue|jBr8KUKP1^N5QlQUd6u1uZ1V17f8XG9n;QDqI^#JDm^Wt zr{+JCV$H2$WXUygi3W58Pm~xm1l_kCxGX;*+V5JWUAA$IS~T!7#57a-xOYe2JLe(I zw2Il5oqp21%S4C52+2I5#K%mu{dqha-ACMMMlab?8-U9gw z0w@>=;wz~!{AZXra}cl20^P0{JWezP{TS(%!lAVh1p*$N79}7Gxk%Gp@EGvdjQiiA zOS}dpw9FzcI|*zQ4CvD=f#WwXMl+O(1lQw2AmL)~J2}a4B7T?p2%uNGG=tqeB(AQo z6M4f0Kh$!#hR1jCNa-DKx!9+#dR5>_+!ZbkzbxZxFK99k)!t!La}DjhLalze)NXdh zFA^8LF7md+g*`AO_ogz4SeHhht_91zUqxP5T(3$sSg$yqCijng&viwyb6BggTeIvD z>v5(1^>5^zO>F&xtE&6CY#Jhd*pQqGO3N!~4=oQ4&Lu^s7kI}ig~#>UT;Unn$jR&+ zcH=~d(b#VeA}U`Q;X0;`aC(_UJmUw0+=L_O`Uetxi0Owwup^S5* z-^OE>~IMR#xKSarm4vrwWBfS;3 z@t<7|hn58ch-%a#!3C}c(737$@gOU)3Ut*_&q=W4d z2xu^hhH?;q8>f&Se?^^S+ODcRHmX-LyE2nrR9oyeBCs-2ZIlkuI? zH9zXNfxXU+2Q!U|s`h&>BB6JWwHxMFdLNv^1s+B(hV&&Zr>s2m1TAAfUy66d?SXEqN11Ahryu>6 zmspY|j2GZp{!I+HR|f{uZp1+{23zr30M6j*bPiH-I)}wcaFvNoMR~o7Z9qeikQ{YQ znR0OI>K!SpHoaPi;7)C~5%4Y%eV>-0U|r)qb-|V(CDL0HF>2y9=zR7T$w9hSY83iX z^QE`u;H;2@H;K}1ansiCPkJ>qS@RvbfT^xn)ZEUC#anc%V=5{l)lzFQsOF4knpU3c zphc@|j~mAbyA*~_4m_+1=E(2fcY^R%gC`=va)B~%0sRQlBT6GMoUKT}pAO??$I~RE zv=A&>z+?zPlqBEJfrZgs2qF!17Y0QDilMvKM{wa9a*oO4j5hL-HwcKRF3jaAq!mI8 zXRxV3V5?8zqB7u!PMospfZ~-#qc(w!cU!h1AD&PUvrGJ9?X#?NI>B-I1;4UOTPHSA zsqMbQHk+^>LqR}fI)6a~)!RqSW|zqotFd;@wI8trUk`Wwxmq1t!Btk`!HpK ygVy*T><=8nV>RKYTTNh9e_Ll2(aDem{H76#2_vcv1l|5~@IYf@0GsRI@&5xI@d#%C literal 0 HcmV?d00001 diff --git a/docs/source/_static/tasks/manipulation/openarm_uni_reach.jpg b/docs/source/_static/tasks/manipulation/openarm_uni_reach.jpg new file mode 100644 index 0000000000000000000000000000000000000000..46128f7607be0dcfe6fa14c87a28d245b55556c2 GIT binary patch literal 40019 zcmb4qcQ~70+;<2`)Lykmi`rV7T1nL|V%MrFYVV--rqrG-MeI#&qNQ3}?Y*jME7989 zbNfB-dtL9p@9m0^`%2E868$OO693$GPbQF@r$3IQTfX*ZY4D99%FS zJ_HIQxC5M5Cj;G%48{eNMs}pM^dQku>^6x{m(3gmKM3G;u78=rH#2lnTxMd;bPB-rp?3o1^#e6I9!< z@-WS2{_uGG8~ySP=zUB{rO--X>ms|5!9p3Q>uTE*KyCnt53Su}ZP6wmD6a*35|VA@FfAHV%z z#?ZL)A!~aA#mk~u-&k2Bn(kx$+-%szh1hF#b=1pvOr6rY$it&;<;sgU@b%p<`9~cH z^pa@m&ml9XCd1{1M~-PdM=X8`86rM^vOK=&@LQSGNo1S+*42X~ZzDC^Y3UHGzk>Qf zL0<5>FoK?b{2W~(R^go>iN8oXIO|Jn$kX#>Jk429P(S`c@M;S6R+VV|Ly9pyHOihn z!Bv*kP^bDMHT`i#?(OaS%^f`h6)~!UCsOFe!-nc-N5pHX=K`t(j4pOIIT8LB%Cow$ zMLD^Pa!r~CJbM}`v7HYSV>xFLaZ}wFQ?H#z4i)0mol->;^ya$HgfX@11|5bzFF-%Z=vGYp{8dVZ9^892VBe0D+Y2 z3E?XXmJH&SrWYTM$a5b2QM*!c^`hvxAmNGi)keKKa(p{AYh^W-fMp@TTiMAqInRsB zOEOT(ZvkSE|4+##einv4%k_!%vgAe~bS<^W@7 zK};#&=VwfF-AS4tJi0$G-cA@iV(zCTQu^>(CKl&;YWfYRZcgl*)Sh^!3gHx+Y;H~zOt!(%F%&7_!m6WC+l63;k8z9Z=Owvs-LL~G;mcMF0UndZ?e zn!QO`%k%z8{PrHYq9XA`Wx@Zx6uT^kpz~HjLQLnEL8hTGXoWSL#S}s=W>x$Yi2of3 z6E-;X7``9u#VQpIZblozSxbqW6FVwx+0R)QM5fgm9u&A+MkkJpUmuQL@#B!UHhv$M z0n_-e*PE8V7v8tHO7Negzs~)mK37GFcv%oVtt^|?NFExG2}P8CUa(se*467j$?9|O zdm@zP?_K8L1X+Aj65D3sKJY$ZSL%MFqKE8~hjriNW7WmyrgcT(IXs$ePY8NmZAIkS zid|f(XM4Fa8G}FMX#9FxSH1NhFFe9mzO<@-#pPT@K7Om8SEstcq%w)Nyu>>Ad%`hU z$gso_f<_V-DCGpEUKX$B+xwqyX(hQx_F&9Pd9V#EQ0CT)xEvsj1y;ioc+?>m$;u7r zTX1L!5$+p0L_*`%{Nir}b?vMU@^_$X*bPX8*Ex6dXpXB(zn}#e z`Pp`&m>@YN=QKv0+@h(e^^+vDm%8d5&}l1$)QxSA#wO0S4D9Hym*pP})VjO)9_ z)pre_8SrqwWIN3ar;e3!K(g-Xk~aGQU$CVQ+WhAxtqa_eRVal094$4X#?}u$j<(O$1*g531R*BgKEk6`e*dFl#F>zBf9 zrGt0CkKrQ%zmPciU821%CwDXtHCb#Bb;JjlhkJ)i~ z(PQr~jZA`~{kfmjO>RKNvR`r`0&A1IruyGC5n9xZIl6NQsI6PMsqE% zy;r|W8i2V!7_R1V_HyL0VN{l8#<})U>Nkf`W4jb^_Uz zR2q(w7QKq^?s`~8H-ve9cn@+pK|CHxx8*klmmhNM3v$zm)Jfs_@<<+|M|{#Xl-Erh z$3#eff)aG;|B;yQx+}|BY6}2s>q-hKD;@+%*SE^5!4}W;(6N#C%bXT9KHgaJs>sTb zvRHpWc8}A`(upP?BQft7=8fyw?Q3IW?0!G~%_>Cz}MjIsiviWPCLS9@*X5+koR`IwC41ZS(}c8_tPG{WUI#9!(Z5syLT=phyDxNX^*;o=md zy&QP{5!<{vrRa+Mgf2ZbJ`KjmPa$%;RF9PI0Z303%z;-J^-rQe6z+mKg4!y9z{7nYb7=wXP~6mr(RqD6 z$E!;rXI}%8+{0P$OM$g6;(SCKA|A*LNk=}?wS(AzUo}>)AvSWoLUqgYI%#WHRAcVS%QyP| zQu(Uj*X9dW1A(d;kwZwR{OkuBn_X&B8|(#o-D}s-cR~l_TZpQ&yzcY-zC%Upw38Qv zlwHMszxw|7P`Fv*$zZpc3pvw&GE?mA7}TblXW=(p@7+b!pGQ} zB|4gA)DbatHVLTst(V0$pA{t2eZs5tbA(#zR1rGoB#9!grVGo-zJ`+=Mk-6jw}uP1 z0%_*qCk3Cd0@wge0DqStuu2NhK-*Oxb@AWR_J?3m(wgS_oCp_E!}e)QW4*askzAL45X%Y38C-vE10b z*`U{|vNFwDYG6S%Reynsh%5*?f+k?=2Qf8qfxO|?-J7=^5$Y92D8&kHgzw8B?*|Q$ z-A5`lqZ8afRHPg@Nx`_mwYIr|e%g{@E=Dd$hqSm{JKpEy^wpi;JK|h_!Y(HZthcJp zS#;&rmiQqdxl6mHr^C$#6IQku2GOIzOihE!IfLuV82+z1xwSfn)rvOCax7)M>JB?} zXM(ZGe_uLZ*=MBD%-0uUcu^qFNKv#D3yQIOBcOS)*h9h5GFhf4U5dvk(c-7_LSC9% zQ15@B0n9~#pA>|L7RCmjyn!D899;T>Rk$BNYXk;zK}u&OFrd9OF8X`F3re}r{+L`~`qoFb?n%ta2=27V5Tlmh_SUcP7{fI67=lI)>C zT(|25z#|gq7V)2>lU^|}FmAAbtRUa*w$^ho<~N{lk$-NM?~jAzL|^G!Vcef=EnqHu zMeCXZ6E#=Qt?ucTVUpDq$cx9*Xt^>VcyUa_+{&@Z6`1ZxiRANdDi%ZkK8L_m70)y$ zWOM9G!XH#LDyiuHi_f9$zTOI@_S>{A51(dY@Q7%GlB|D{+J;G{PHQagBw?~Q6!;!O zS#&(P?{pt01Qb$H!6d<)vPhuJTNgoqc3>@S1s+Zz=VV4Q&0~YDz$9=lDx7}&bF}aY z9QO`1=PA?;atB0#G$_t5DSHzKdjarV;}l-su`jd}P1w1Nl6HKxfr3oORK*>x$7bUt zH=wcCR#PoG7;!pX`;5q{>GS46ro_bgt;{-OSjV?e9QjG#%cni=mg2Ci0c$$BGHn4< zv++gMz_HRL+Y&EP}3XhT$?JC4+1s-L6H9v2E8ey+rRd3=5u$@wl@bAu* z1zhE93AfBGLH1XWzzN*T3ir0wPgrqoSMxmfB|WFsV(%m4LQCtb zg4kW>ZM`UC1`&7nu-qmEi8Ekn6#m zmH4B&vH$DRPvY5oMjQ4K^1*mqB?xI7*f8`^B8itH!@ZB*YFnFwnduS-FN(soak{b z>el=*vkdwEpl~Z)V?}Vb)wUCQLIlvg|a=(#nk0)owr@^L1Q;(;68swr1@3tKya+LM%9aJ;3`d)FZZH_~9Y4 z|8%*A)ag!i(?FyojAUgMZ4N+!{|Gk-=wJW|!3Xyp0ixnUa3pJj8=$B3Lm+>5Nvgl}hf-^ax|k7al%!FioUi8Bg_g5E%9cy!zM7&L+IRe1wSZ zP!y7gnXz)WE_Qt>B~28=-TX*lv6zHb>zR}^t0g)PDX@nk1MlQR_mJ~FE zgfSSIexgI9G;C!~E_bAeommd=c`oN4a6=~5#-kbR<;csbCk`ta-siixU-x(F2ULtc z_HKWuF>?c=mhz;WAg=opmJjvZW-e?M>EW=A5CGplhZ87It!AreqLL&#&p3H_04?IK zAHYl>A(=XGKC(Uytp!=Y9y+EERA#v9IF%)FifmYuRWiw|AN{QF^}iO?H!#Rca%&sv6)5)ZzLQ*=v3$gzhiXK>&1wv2H% zAq8r4_4+Ny3vLa=MGEY&5{}TFz^#Xn_jgB_ev;8GrI1>J@cxon?PTa*1bp~3UwNRm z;F{KC^~yl!)8Uh(X;AYY;{uUHoP}3drWr(_*~ArLzPX5x*jQh&%`Ro{!nKWLRnhi~ zqKUEQX%lwxY&MIxHU!F(>>q|bRX7xMI8h)M7||L|Rst~hEvay!NhGs~DR?Fbq%@84LjbvW~45qAsxp+wVT!r1**^=mUdoCfzJwPd3!Ye zWB#RGCel&&?#&0N+?gy6vGaPr5%t4mRpMnhHAs~J%K8#5CxQ#+Vs>2vnxFMIFrWkY z_X47HvKApuKah05~5`G!syFeQr!!LsNL-rRvD;l417L@oo zK|9uRkd(FN+)g0-3-ejwkZ|-cv&NZ$z<;-%%K8q39$Pf*-Gtn9H~5Myw~GB=>w|jsNit+|EVI#(?%i zD{SG zjFJdPpFdW4-w7+{?oU$@+w4*t6BTc+d0m;`qJ8^VhgurOmF8t`+9wCG{n3W9C3lfb zKR1bhwFe6bC4kT2PbRwx@h1ZWgI309`a? ziz_pAl<`tP^41mij)S}2ihEyw$p$9hY~cvJ$Y3e>jbspCwWi{+lH{yFpX@e|FNK$)e$PS*;@(K= z+8UJ?H4(~rm_qEhTkt;z74Rzive51NDg&>|h5MWAX$wwr3XQHVbvnUQ5!BeTgXLHb z$dc2R)o;%`?+Qldf30E+oa1Y2=)|-SSJar#Ui<&dZO1SjT1m?oE}WOYcy3#P5;@*% zW{Sa|xhSM}^!T~rnlNB&z&9+Fv_X+q3CPVHxSW$XNq`fQHG+p$k_Au#QiPNX_bc!P7EKW=!93rCN=4n(-KG*DR_Vr`}oV3D0V;%*}iPX7nd; zf9PnI>?yKl)}dy*t=Yu70F_l8-KWNBnOp37kQ39;bIQ=nnBaz^HFb4wOY~C2W}a9v z3uPJcB{fNdomncA+iTwi(eM0)XfkbR%kec~0b6_uc2@8PL~sMTkF*gdbnKr*+B$ij zZM}Bp%Mkj0PDK_$UZRtFP#g3~U2I_1Z(y^nQii_9A20q~!9#%y`;hfdsEf4r_P2ehBnbcvLL=d0mV zQTssv?z=5+3j7pekP0Bfg#`5h0{_M$P6`ee(K6l#-W4xjrV#1a1P8HL-_nXzA;Qpt zcR#cNwdp{=z#(=Dqomb+Z{k>Nyx;TeaE0N#xcIHw_yEUpgd=as{f}9l+Rae^B;r>G z`J(tyvz1N#beE1ygI76rGw_PRom82NBe8LUIUv zhL-~4pNTLOnUr#R9FZHoOSi)rQYM&@U%FQFcVzi;&;Oz~F z9Ez9iQmHuLI!14AG)_OjUehH=w+m&sN>vhS+amlDZLOrEfgN#S3JobR>QX}JNQK@H z$GR@(7Np*v8nE4p%WtVy6X7oi+dqqU!mZ&I6Il-(+rfTbRQTq3z^L@fpMu)iV3M}< z{-sz(trMr;&d2dXR)w!rqX+*N)lzUefQ&M$;zgmtbTF7#ibg~ zZa`t!P)P%hsy{T#SQJvX=ThjC)Fslg9;)ov^rvpAu)h9b;`@ib9cO|U$tydlbaBOp zG*t=nSppel4SHW0zVNdH0ybg?{1tkn7TSZEfA+^z(Cv{uFZI~G_P*8paCRQ@i z#*?Uy)PEV3!rsM|F<9CS^X~wv&6-wS;@i8w?3}?$y6c%VepbLUloV1{grIu#Wr#Cq ztia&OIMc(j65O)CfuxYm69<j}M-YpxtLH|zV=~kZH=s|0O-gDd<(oX5yWcyj@hvTmq>WxLI{3{!9+qcc zZXu1$)!I-uF7q%|f10qs^B@+TxZiDrYbQ#{`}6k;70yY;cg?`(XxfYW9}%Mi;NV@Q zGH61uH45sL2mOc^P9bDxMoQ=C;>eZ&Odje6#QzWTB^S?w;@dsez8@Zm3RT~5qguJnD~<8kU(~-943Yv z(4^{^Qb;JL^K?dbC)oC3^4r-MA*IXi;7xE{81wH_nbU+wv(d>-=L>upCWXB8f7&Ko z85`re?ajE;tNs*>ArNI&=11tmm!g!?y3@Y~Kh{2S>-GOKj3MMlysFzSH&sa1GXB+! zoD^?-&O^&QO5?Yj{*=9@6DLH`}C*UR=((Fsj-N8HiDluG}|8y7w zAf8B|p)mE5>?Y71aS??<0lI>Vy@ic?7=ZJW1+U@Wq9i0s1_5A$!*XC01Pz@oA=rpz z*ZdUO=(6Xg+dbw`+pWq2qygr!{UWbD*YJbad*KBhr<)jarFp)T<852mK1foh!G=k# zamwVS_gLybO@gc5oHk0z7XhD*s;Q_SI(|#@l#)uX|5fz9$NYOjUd%Es_7DJN(r9lu z>r=ELFb$M(T|(H=$@Ci^MJPfgZALNC`%1rdla2!!GUt{i$|)M>UVNCZ)QbM1=T{t@ z?@q~-&Q2LnH*#)UBqQ_M@!23PMX#i6smpGa>3MQV)vun@WK9}eiMGVB0{fxn$=>UY zXZw5FyAuTt80!*)cT^P?#ka_z#Yjmhx?0tK`$gY8m4^T`K&^%w%+#y&ZB1o_i6$;1 zMXasv8R^!@(%h9PAaf0&(uPjrEbath5sYU*drJXgBvv>%mJs-Vz3x9oNct3*!}~#( z2{1f}A1f|_7ZKIn2ECLCt;as4VXjSXzeCQ4rs!Q=OYDF9&A3?1M?y|}|JB~{;yG=% z`pDWbtZSBpmBzap|2}IVL5G6;docUn}+b1{6Y? zy+rR6yNIejv$U$GiVa+nSeef+=up7oX<-@0@#`de}$6a+sA z1Jsd6Na-+K0>}o6j=?mkZ5KIXv+Q2$-Q6KfK7P3OY`3u_ya%be(6qhl`qij|Nqv%@ zS685EYi15~?i=z(GByC+Vp1$hO|6~IvgcCBnmZw$i3%~2O8M6+%j|WTQZ~Q&xJLI_ zEEzffyZT+o2F_x*ox;hok8>HrbtLkSsam_oQeDd7zi7;1)tNeZNs}zksW(aZti%O7 zuV#7U0#~+0SwV)7B-Z>6&m0%g^(TIJFSjOMdyZvjs3#zrPdV6Lc-UuM@?}h+dRh@dKHVj z$e>;$2y~H~K3v`3(c(v{p7xKGwLK06V+z2^yp>3O(bX!ZItpBA8PEBLTYj73@P z)9#U_=MTcJWO{&>@3WV8xc;g5(j)2ltZ;K3I2`csHcc~A0s=r3R2hEg12)@QC zQtA4BLejyA&Z$VbaFGC!^Pa_pTe1?|RxD7QvbW>?kD zc7#HQ&Ocg>6Nq zE`W0o98ySU^Phf&9 zBt|sI!=(aGb>Y(2iPK^PWpI(S_iQolG_WtAu@ylVkO<~(Omq<11NR`gp|L1JOmN$>5# zpNBriPqeR@BgE8@qbu&IT0f4&np>CF-5ja;yL$$~LWyN*&^QkkSJf6jd*nti8asB71Wu~NBeS91JHCw&In9#rCa z0}^;4loZ3UR79V#FfJ-1Wq5{NnRj1R918YTj}$o-DKVIXu=)xMkOK&C7u|K;w@tii}DH~0yehRdZz^U#~13R z7y|`8AS93tGt^7G0F0e|z~us3jTIj8=rc-Nkn}&TD;r+@G>I!WX3J;ljn8jAtq}~=&Hb;CoduSfUC;6I79AKE#sJ_ z#(F(ear>cKCC2>Q)%c*ip<5GpVcVxaFxgZ!@H4F%yYop#z%GnmI*dibjNMhd1xrlVtvUq# zIVQ&Q4hLUPdLNSpbLDNV>poq*Si>K$Vb`Wg0RP+YHZp3L31WY(&GWWH%hFh!=d<qQW7!$~1!cL5TGfcb(0 z2Fily4Bov-3uS|e@k`}lr_bhQSY2ZF_r>%%JfvQyj2rPJ=$jVA9*9^&8OvhL^gZO7Q333l5Zbbf(bb8fRujf++b=$InwDD06OjR!-}QB7jZvqud{7mpDb1d zPEixzfGh{Q13B<3z4Y?(V#aNKpNc%|mb!pwCl)P=0@P^#{7=}Jb&o6fP`jMg5)h;C z)S^}aaC+CXACv;%uU5-j*iQyP=GHGGvU?~B%i*YwAKtdi;gID*pLEY!<$I-x;~m{h z%SLf;ImV2R(`&jV${1yPc=EHit1=cHhEWs$KA=}6+oBa}3I{a#ppA-Tx_UC-@KZ?d zfnY#82faiS01AUk5Ee$VX9@975R0UuV{nYv@<@@FS7INMrC%tg^k^GD%&@0Ua@4GR zKt-jygC&w{V*4zZ-^XeB2P*n`Y0=F+ukfw5HaOzjFxy2>pLRKshUbt>0!pCZXx!}R z#rW%*?d>_kQa;DsLI;uG!r3DW&2btaM1c|Cr1+mN)M>H*gnZ85Z@ofQ@4WO~peM}w zWr;;P$~bN|+<@|oqSK#k6L#gTiJCIlGw?TBe~Gnq&z!>^*N3JhcRx~EWh|?*$*YQv zblQ5paV^hsgoujFf9!LmR=TI(T9HD7G1i?#-Tg;Ikbij66Yjh_B=JaP9oMEeSFt;(YLs~ zL9flIctY18^J9FKmp4=A5hb*6Ed-DO$moW{h(W9GupvHgCB1VhWE5F)*HrkKjYFdFI?jAro}|K_uE}09#;7b^f*Im@$EnJKaxsU8 z3y^#`{)=&=Z9xCU-^d=Vk^;HaeuBr^zfHV2@Cc3&L@Cg9p!<{Y#p^foGFRrx22G65Ddl zuns>*c^n{BXKc8vyj@qtUskC8$#6%fpvc6Q%dvvviV!u%9V)uAAvEd+^aO4z(uH{( zHTQ@aE_IGxGc|5IV$eovzo=p%;OI1i%ZJ$stO!Yj(&+D2b8tbB9>WMi}89~C+YBOCLi~|dj%hg4n-^5 zqf#ry2|rdsiW=c^w%ET58$=95SAB$LQB|L3+gN-|P0P#ac?23jV}>QcOp~Hc&?dPB z>)qyaA~*QGznS{)u*K~r4GPy)My;t+Wk&ritCFas-rpM%Ic}=?25G7Pl3<7(v(3V6 zJI!c)CCays`dQ5itVcG2axCSzq-9ru7zL|Mr*_QXbyd2$Nuk$_&KJb~J57aCdun{C zh<{_9V=~`y^KL-*a1ytHnBOWD&D5X8?pY~2t}-)*`DT7kinzkU$2TBPv<25*qF7^2 zBsAtDPqw%u7e;Sl(|4=T3e&JM%>V?SoDqA+uQ65g(c1y?d6Kh_8HX^lW=<(x25Rh< zOc$Bq_bUP241nq|qMh5sF4KtcH`p3p1X4Gev;S}Rqn4hRAjD@|jSmY|dk#kqg7QP# zohV9yv=NaOTuzPAm>ms0C8m!{?}!LU zT>wtOe<&5+u@Cs^LS)kMx`eXt;RnZ8NWPVCKw1XS9!)!dlqFw|F2LUS!XQsTXu}I& z*}AQIAs|=;C@ZiNJg5sC>e(uZ$oXW?P#B@#mXUh}H1OI6CjGvu!|U<_Dub8Zs>|`E zx-T0HR6Aour^Fi-S;}!_7`vD4D;tN*OT&M#O>k4&=^`0}S6K-VO#K91R7u%WxPWia zxRw3E&R>O1fdelqPOknJT;E^yPuh#vEk|BL`-bo#f%Ui*T9+$|%R5I?UxbV9c{C}` z<&oNaO$T$!#v#fc$Cirn4f&gXGm*IdZUR^P>tnynvaG?cN#w7#U0CHck`A4#9FLot zczFY=N-TC8Ubg)zjTQXRT6R3Xbw7ZAuj$+Nqpuwd`L-{eBzkC%zlA0ru`N>qO}b1o zt#%`Kb2nY5re)SuK__SL{a1$^Tl!UI{b@kxnUIk&W#eS@-;#CD( ztx_h$4(@7~XqjR;9c3`vD^fzK zu`gMZFDh-?;%v@iEh+_Ki;LcocYu|J^?n4tru{JR(Z3m#97LeU!WMAPXR-Y8ZYAfW z5r9AMr`_MIOq)_RB_@{jw7KTYdbbq3;0FRxxkfL2?yQQakf z*qQpXQ90`FE{7qniG=-+pTYuFv411>OFH+ zo{HyO#pnQbIpP2VIet3z#s)`A2O9+JFahw>ojVf^lOk>ewi~{T;&@a{G)hOU+O`{F z^wG&$njMyzJ7teO9#n2cYHfAN{Ep*MZHn;|KHzV#0+a4`1-l0X zk`7W}DTExi3mXn7ct5D)Z*ULar)F8sv;=RM_#oTFpVZtRMOA@=k+DNAcgv;XLe3pI zt8EEb_>&WR*;vu*=XFH}ynJ!lAL7!OZ{V0I?ZjN{kHkZ#5OBzgt44iuQ`N{PhbzUXZ{x0S( zeR+?m$C&IMEiJGaKBI0?p7PJ-kI&TJ(<{!}yZ0@aD|nEEU6L6;_A0ZUxI(lTA2Dp1 z$dz-ignzr+`lD9xviXhEFZY&i)+05eDG|X~VjEfz5r~=?D%avshnV-tQ5roqz?iC= z$#e955)yje``k5ME=XkvDn$+HkXq78@BQr-deAU=p{}34UG-^PnBdjjfn5(?3->5~ zd+RqgOY?VPpE8~y(rcgFJL?gLqzT9W3=qSCs_f>DrRAzHhBgzm{4DN642eSW{ZUx* z&&L}qD5k*W^s4iA^wgkwsmOzm;)GWtIvrG#F3Ae&>U8d_zC(&8Dj<-*W(?hz*g8Fr ze6ypWW_#xRrFNDVz1Mm&(tKyS^$zvR?t!3*?We?xUIO?CJE zS+Svl3N{(~etp4UI>aIPoD-FqmtJ!Ir)G(JD8IfFK9d%y`d4nf$W`4+8qSK|5HflvoarxYT8R%(JWF z{1*c5LndyzND?TFT=H)a95)Ed#p0C*XxzXa7{Ge%gImvn@mLc8>IZCef|1|D<-qez z0Coc6fP&b8&2?pXLA^(SCLz10OV|R&2dM&^)<_Hb4~#j8yIk+ITa*VQeoa6k&LtBb@*I5;>d0wc?=1_^}@-hH@*Gd_1-)i|J2 zjHTD$OqzRKR!m^b8~Be9daSYH*mIKL-L!J&tmLq&YE;H(B>g;tAtAN*95ZY(`wFcEbl|G%=Hq&lcBUL+(>nDt=3^72U;_l&H{i|ywwGW821UKVABiakV zDpE?9#`gW5PmgsLd0w`DGrjno2U|^uch0b6Ny?Ag8W3$O{N|gAw1->;9h@Lq+jV9f zQgZHxDGrS`;*xlmcsxB($%;()f!@4gI`wJxz)j;w{a|c%PzWceC z&n1+iD?$|uU8_&rCNutttqe)reH)P^SW8+SI9ge7f831F)3@d&<+gpeeGFktEe(NcK5m)P?E$ANKc8J{ckV@l3_n+ zXa?9{dAmi?l9lYy69}_$Gdt_B?XE`&YIQIv1Op#&pI>mPRNi@PU!6juZ0tOBcV^w3 zsc;os8$dMatcD4!E**4wUu{V#7w{ua=g?NPoirn2(eSE-G>B!6Icj9a*7311V(fA| zp+{r1O;JPdh@PZoyU@RHxUk7f0W|N}s7XDvZC6~Hy#DM&vgc!JD%>}P0v`1Z+=7#U zRB{I7PX8`oh5{r%eSMV=^PZ$M}* zfb`V-zY%y-)&mbcZVaUZIC+-o;*k^(bG-OL<~?3YjAn$DxTfb+ZN>&{9k)3qfja%29h(kFF7*(c|rV651*U6k-LRLyRToBq+9QLnKUgHq7X zz0&*{GAjC^vUf&DLXCIg^0v91YQ|gF5gN~Denl-<)qKMF=q)L`{mwovb`&}i zHrM@O3y{sj)SofVIql#+nB-7N>DXN3h{&2^c4=Dry5CH`hx5R0deHhW^I|C7(h`?w zcFfk6kHxepdC8U?6F*pBR7bC62)atZw7;+1e^McZlFE--6^2z7r%9rfPn;=~?J7SrV`X8e@cE*nCZFx4GmBpn@ z$)3!F?*ocLSDJ}V;q_D5IoeYLnsmN~L?o$QF#;U(Vq*S_Z10yYdu1*Pcb|MOu55fQ zBBG_O0D*!U&@AhrrhmvEZWZM+wO>)jZ~hAHbT#2Dc;6;Yjv?y0Tbx+DErCd&4{En~ zcz}qnYL?BnmSW?Q{pZIw6Zi4dZL6zru_azZOW8#*nf(=@*olhxot{>eT`G0IXs6>` z9hu8x{;FN)JW)hU)x3tZx9{p>|Nhfj1ILGUyQrP83F$L;lyz2d$$t!FfhMy z68vt%TKy1UrjP+w145?(2`U!XTb32~1lYo=3an7Kr)Yr13*`FiR>}l90NH^Az;we6 zMn4L97PTi~uX2H>I*VG;Y+x?-9WCtx_F9?FeHB%O zt}iEGRx3(NzwFp0f(#|?aibg^W1ARJx6Xazh=y5D*)8SI4Mw6Qb!{E?b;!q<4U_BM z-%)59mcJmMw1Kqubi5y9nG#1=^$Dmi~nq242{ z->~eVqqR#}OWbVh+l88(+96M{pSN@ge;d1xZMpODx?Su8Q!|dLtmUbH*ENHj0;s^w zoq#<~2Fsn$-n)a&;PponCrWGt_8C`i*z`nC_<5|Ol;1ggH}(efE-H5@sur^L%erBn(Yl}1Vh5Adz_ zla}b>#xI}6o?cG{()HO3ugwyFdSjY4s8!*#hgp1GQCiya!z!(@yiJ9N-Br>>3Zq1s zEu_bsxEU{Rhw9Q1CCL{sw+O4BhzCi0wr(_pv*Y5(R1S5nVnbW3!C49Rrq6OqssPf%@)R0=Zy5WQS_BT_oPTQ#BPAO&F7`e%Ld&qEG(!f= zYN2$>oxj%8#qBOD;uEt3Nt@fd0d+@d6`xpQgN8PN;L>giVGHhX85Edfw~-guHT*6P zYCVS#2{!krLjnqnV#1cXx~-#WucuNU$*kQ|XX>WGhq*Q}B7?Ex|3lJQhc(&1ZG14; zkQiamp@5X2bjPF{q!dIzrgRP%9fJoD=~9sxU4rxoX=%yPjex+UrOV&#`~JP-0Pb;r zy`D}1pA*$aBC@t(#=C0*ONwWil}mIFK0o_^WB)D-<`yc&hkC~L+XQ741_OTn1qi?=0G zMLH{GlHBF0K4aJcrlF|DC}Xd5MD6|OuQk2A;QyRmExoWcvim@7$>#IV$4Ge}e9}*( z0~BB*LV&`Qstf3+%D|@)jbH>s6$r)wiQx!_4)}N*yw0w82?; zf64}B$GU5lNzi3j^Tru{&o4cj;w{SpOW@2@8C}UG5lSu94w$vlhHG+sm5G;2IF%t{ zHhH?Ge)ON2i^}RF)V-S8xR9<^ZtBp`A-8pSrJ<3gNVwfwzs1!Ll0zIxc=h=dWfcqO z3c(-f7BAGzD5a!)77x^8bK^P1T2H>GvYP0}oxEb7zaVq$HgJ!j&Hi(`CSlXP1Sc-I zau=a1fREMJc}`Y!Gq~(z;ayYIl9LgU1@Pp*83<$D@*_`#u zWmc;Fogt`Pbd=E@&Tz5GG-E;iXa@$9bnUeRF~^dIV*Ot%IoOHZ+Bz;jHgfnfPVV7( zSH#^*_b&HLd--~E4_Gdvv)^)`AG?yIGHMw3FlWm`dUp5MNfq!sS$2|36Z#_}zanu` zMqQJB2&W?NPW+pPFXm;*V+SgC(%Gg7mYJ($*t{KrL737KU)0x&{}c^yyIC)I9bOIy z?~3z)cA^{A7N1YaM?+4+v57yujwsXJqa`q*I#kB684ygTS6;PI%6Qz4jA?n}mziBw zLi-PGUdoTGcTep990ZLs;_NuDSXZ1}{TFew7H7}j(ORwuCwiw^GPWhP8!8ZvM1l+p$ zVRLo%L&0pE_K%bC5%uX?7nPN2qU!fkh37cD*(a0@4$-e79{?p=JJ1jT&OBT4Wb!*8 z;06rz^8p756?-Dk36Z&Adm$G|L`b9t|7V*J(tD!E$d;svDj_S8eq-)|=Cx%xl@5j& zMQ-^jW=n;iypZ(}CaWxt#8tBu_BbafOCHAe6^q+4R)pR{F z9Ek}HUVwbXnLqvl^m50!MN(uJlK+AP<4Q_P(i8iAy{wzBG3!09U{#KowmwqT+KZt5 z%8@2cnYyTEL6+?FZZiXOPaot$*0QylW8io4IHR=6KB=kwyP}WW@hq`Z^tnVWnxc-O z4Q2C5q*s+!Lz=IY2wMIHeAo3DkRzlO?VS0t0o?Yo3=JH@nX5~;>N}LQ|-P&1Y znTDg3b&Xt0qR_F>aYLPx9wtY6WV#NB0GcDB+dZv4__Nm9i!?92(HI8|& z7jy}7!(*`H*YcAYk4we&E@jSl25tR4x2=gqI;AVC#J&2~pfxsA{kim-p5Z^4Ii)i` zF3fSb(D^$bx$dKL*SY#hb&`pw-uTxf)_K2q~TxDu^Bzqc2L-nD*y+0e&oh|j`N7g%>sc2RCV zivZdnCBDCtCuPDYKw;UiqzOuFe0$S=_`rpn?kV2SeKRUms-5x}sSh%Vdn` zZVg>}D-7MD18yhI2@a+IWoeBmI%i6hd?qv9{YA)SJ4A5I=5zx8BmA=!GZmZud!R1A zYDQC}Ypg`0h=^RahI5yrW971pXr(aP(mgad7;Oc1;qYU-oOz4y;x8;n)0rv^Ly?W2 zFhK7`yp__kn+8PmtnI^qWES(^vIwlUHOEBlgYp6mFZy5npx*179LO~A3K+V74o}Q2 zg(arnuo$f5ZgK6bKnh)JCg;rO3~o{EA2jLyLJvs%>l=cB9-^8hrq9&T=+tM9fC((t=eSl*FQ~Mo))q2SuWkY^drLZ8c$~BQeKi=r2T0hpJ z76G&E*AQVyqu*k&PU8}ZiM+3D#)<%O)43`9*#@HdK3DOwBP2wW2xvw;D4CLLl*kJ( zeX|MUfzPDlA7}vW&^LqTG}Y%LyN9cq*0$^nB}@YL7Zd^B#oz;;pS{P`wfqOj>B+5%CI+%R z*?FB!Z=!N6pO5{@nEkarw0f%NU-PAb%t+*vr-Y0>BsOJNdK;o+bdLf2^$zxd9oL8b z+tI0=Jg_ME^_aI@uk6M?idEA$B>yK~nRv3wY^S`%&+%xi7M-6Uhy55&kxm1deliGkiU0^GqtwcA9*7c zj%CZ;(OF&V1uMBNY$7J6BJ0w;yf2(m!&~C&pGMILf*Mzze4FHj;L1(NspPN>Xl4V^TKCBO|sSx6Bo$>0XF%mY;8c zeMRCxMHy}R6|OvXVHSuXx=otxgPnX2oIOCg(UR7m#DM#e9p^L#QUh0 zhQ@E}9Vk$7>)KS$F7!hFh%E2IbEmUVaIJz=la~(xyi7t~BseKF>;J%*` zP>+a2XbR9iolQHT%h@3EHcgQAh|tVG;-qviW6ZZ)MkX^28+)p(qx@F#e4+%N&~(`% z#|QNe&k@LX$9x?60&+#U^+2?c8Bj<7qYH3F7YfkR{Dw(Fu%U1D!ao2`>A^&O{=5E_ zC+W+QrU_FuAHFMniAiQi%}CLwo_)EJ%$TAaSHP@UaGrd-3rJSCNi0aW|2U3Q*qd~{ zcyBAJcSwfn)rolgwR)bvT8g0`)%`1-Y9;Ky7xAjRJa-_AMGRmd6%IJt*L?r!pg`6M z;C9Rd7Z#wcMF0>yNC4FolL*Gn5UV^rU53zv%3Fs-mxx(= z?$2%$MwPhQT+VVYDo3N)y+UT$0+C5m+Y(*|c?au84M~;C-+}q#k39@)A7;Y9rfyZw zH8zY)>>Ib3F5b-_`fzF}f1dxTupvkN!ptkJev0a}+w%QcrntOSKS0UQG2@ng`TD$y zaw!RU4kP48w7IzUu7)W}boWXQwKNYK$Rvx{{OZvdQ?i9~{XN5#) zJ!NE8Ds!xDkL`UsL%p%ra7n~eKpRg2C6Pj@H|CZRuFn@#$B$It_hFO{X%Pw~&aPc7*zzjM z9zP*nN-$AdNl34H{^wZbV7(B1ht)vJ<%`I$#f1q`MgLOAqFrydUzV!z!h7AOm-2#f z#DcH1i_6L?@eZ{>v3wy}?7*3q%4I{CBYden=hght_0q58y>u)F;UpW|cMLCB6y9W^yUNjdg;00MGKZ6w>sF(B47CzTE zbMn+GjvWQ(rff^vrtJ3F%DIAu8$U|yn7_o5`8j!xN%_8Y?p;Iz_S6+FubbzF7Bili z}rE{d4vK*goEmKx>EvL4nv9gb*Cx&U8bzI(QsmwPQ4A1Z5j?*`TaNe2%eK8c>&#Oj9w74_d@jKhSR}%d z<8PWlv}wnfZBzOsBmbwkQ8*-yC?2;CrJazc%W$29-D?)tbiwKU@H4gjDKsAMPtUkrgxartctnN+^9u?14I&r5!yJPaz-IwaVl!)V;t58)arLdJCK(Xxf93GsSX z_8u|hIR9R`LgWHiU@u>x?K`U z<;iQ;MvX0AE@V?&iny`hf8P%c4W*-q)a9r^mq1++MozsPMv_bjn2Zub*3L;_YvdBX zYys^c=1ug?f^UQAI?d>Ki@3-c?|5u(p6_*F^$G4}&ri&91XE#d9&V}8V!SaZ#hhFu zMVDz?9A0QY98nV9jb9Ld)?d_W3qn?TNZwu5c;#5t$a`_inqQ*NuH$LNZY1{g*qvwm z?A=rx6o7xq7Nh}P*#3V2q!Q2~1S}D1bVQgk;z!jIVqza|FOy^DMOrm$Rq|8H@^bvF zxlj%D0FiIT<5a0;=u=3_Y~v~`Qbm&tZ4qYFdYq(Yi$^Nv+rAbO@rsD1N!ncX{aTuq zq~HA07h4;4(<{yAYFm3Z$xx<6^~3ExK9NXO#&uU~hL@{tV2+&Xx&>AXgE@Y)E)g4l z>JJGg2j`esr#eQ@`iM>{A-6xwO|2)&7AG|{ranqa)NLF6#2eP zIJ%+L%bxAf|Bj(%xGiai`Kdb17&Z9^LP&H_z+&e)=1IH5fj#8}-U2q#Sd-Cqt?q&)qWH44!*`^}*J zST%C7$M{XSKXTp{OWEb4HsneL4qb>k$i<05vplMPp9o zk9>|df#)UL?I`43JoVQ;mltwK(?olBP&gc58OQ&E!m%A&x_c}POARZKy_`*ln&`xr zMZ48Ku9>t7=Q(axj?UKwHHX4$nBD-1HOv!;ZWtLq(V7)Oyf+E^T*ELPt>oxVMejm) z&_S|H2oowoT-=4e-t5x4bB`3?#~j>e&OTgW`xmqTeSn)14E#0^e08oG_Uj4RFmiTE`aT zCAK|!5fnvklryNUt>?f@x9j|4F78>VRm_e%%wk;IQ&em0xsz}zoaKc+yUwBX0Q`pf zY6SUX9a<-K-!pRuN5*ulE8y?iNT{2@_}=U)_?pUj7aB}(3a16Bz*MLVVC~&OiJ)u! z#s@#2??euDQJ0z5eEfLz+atgHunz{mWF;wkTas83^GmA8oH2YZCT{v1uGB!}hX&WP z`H)aVfeApW$-u9q2Vjm6rhtD(E|p*y1X=M>SeUhT4-&<_>Zt-q^bHRIkA@ogKlkuclHHISTiBk`zovW# zgh7L>QPb1Ntdp(KZ{8ckp|Q!Jnal85U#&+fvh&t_^C}(bnbb~c!7LPxt1GxPV!~A* zuVQ zVovs*yP`rQEAI|vfzyf;(&aRor2fwN*;T<`P}AF8d1M>Bdc=&Ie|smd(3byJ+wsTpr6?9;8UQ>{Z;&?$_gvWrvStJBotngP z?fY#Ar@p_S8K~3No;J@>`(ExG}oKU?^{AlwA8xz#wMK)U02ofY}54f4mxUdaCN1AvfS+OGv5r7o_4`7N_lRY&XjgY!1QXl-HXYOMBoPUk!mF7zE4IW$)RTViM8 zE?fFqr-6@)kTrKs3AZoat{#?ja5a~(b){ojrtG8s!!nxZEDjYbIOQpf07aU*p9T!a z9T++%CwnB{`I(l;y1RsHN#k_Ma{QaG?^fFWf<}q^Bp4k- zl7{^6P-Uj3m4#;(+-r`Ae@bD$o~vt@HofoG@NVOZl)^qI&G!YlC{?3)9E^kq5VVL0 ziR%Gd20Z|01x{ZG6$u4ElL43|?%?}iqF5@!sGR5N|3G~0Bw`D~jZh#AmTqK!Z^Ho;8IftWR z&7s%xZF(mUFqf+f-R@EK@1xG(k3l$BXwRiV;?5TVz4P+~M z*)wK`x7}J{ge@e(#9^y-n%nAbX;nuh$hdw#V z1!5*O)_DFQMPx9Ot8ksMs#;DH&KSEkUPGm7H?-2Z)J_^JIT05&$XIS6d#WlYO+2gc z@>lopk^0j0FUn)YIsf%74Vi$i7pN~%PRN_$iAg)|HAz7Yxgr~v1C@j7*6%)~F?uqg z8Fg@@s?e5zcr_|ygZx@ZJ@)k!lTQcHOPG+P0s`DVhk$xPalOZIsC+LyH}|JoC@)t% zq3a5rn?=31M`hoi4VtL(U0RnHB$EFHdB?PV$Bh1}HrnDPbKt{UB6q3#jC()Lv)&03 z{NWO)z<5F`XnZE8>1{fIPT%$5lE4+!FZvK{wBv{}x8Sp+g}()F8b(Ys`PhYaBsz;O-htv~!Q`2E4VT7tvce4McgEK`;3gGk+Y)%(P{ zpBCZ}6cL^8h>3Y;8F(k@@YxQtUQ0b2E08ke=%MN-r$l<_CHBubE4S!Oc50^Lor6Yk zY-+tFCIkSq1H#4(ur$emEWy8OUr+8QAbKDE+d80$RLs2(`(AdYCQ{ivN*lU<{i$li zL}Lh-4h3kO(kzK*;g4gIO*0d!yH&^{`+db`GemI$dALtIRh`6&-G1(ntwq?IFTPO! z>Qh}8>%!1@vzETejE4XEd(0h@yNtlos->>+U)*e=yxa;^?jg&VBx~dlsE=FNOPkfV zMe9L!w%?&Y@oN*Su^>tVFCnbHp-|@ihcppakIUJ!P|m$eUp5t^Dd{-c?G78eJth;1BnSXfaM)gRC1KsI2YPvXNhc+5CF(b z@M^Ofr$^5NI$YBKf|i|sup;|z)Pxh-iTUKTMYLl=J5>lFyDOI#7=_>^cRg()bL<2@ zm}A)&6N~DG5JG?-=^RS%Md0U@(qPFVR1(%EoBnGd3~7rOwZ;`e`PMKvc-~8S{!{Y)XqW3s(r(g&UKxfYs};q zWj7_M z@>EUba6!3ts{7E^X8!%^&flr$;Bf@EINwChaA^^%{dgUz>A=fq+3gY=6f*L)dtuWzKGFjXkL%c^gV} zVd00LzhpThb)}x$P^%Vx&b*{HEVW%Ep*|LhgaggJVtBXp7eB9ExUg${;34T-1D?lj zecTlBe!0tkL3tjH25Q1Zv=XG}}KTI0yH+~bc z$x<@fCx)r|$Tu%|cPynAe$M#fKqwNLxU=&DZX6`v=x5SF^?7>p<5bKmQFrlOS~ z{ue|er#g=S-i&Cbm(h=+;thwjb~m#^)>ud>R+Wz}^zC@2e|sW7QAq~Kgf-H}J(UUQ zCZ*Kym@7VNep;BW4Cfcs<}=+=-BE4bZ@P-z6bCxBlEcXauF`07u?J`MVdd(hBNgI}>#a5}!;}RnHo=J7borN@+eeBn) zztU2)&N$Jj*%{;6ZGMc`mLDjNWw4KkV`nV%_Qi>!I>)!Ie~WCF6-DlXQM$Se(CZQV z;lH3%^$R}IsZx)Ov9#>bD0LWR4*WxfN9Qw(w~nr6>!6Hzl|JZeoHql z*x=;37lsxm@O!sGg-W+* z8Ee(Z6X;sVDdNyIxX+E9H4VIrI##%i4u*0>->AWMpOSpoOSd9C?I6;bg8@;34973c zGY3o?sOuK&CJD}=XH9_jk%Qh8mT=7S^H<$xmHEKj;4SuZ z>pueBR8GnAH|d*J$hb);o0;?H(I9 zHt^u>IB6;m>d{ZUuez7gD7{|>a$HzDk9o|dIjJ*SZv@kA7T*-l-z-eOxU84?V970` zJf7hst}og={CrTQU)7|!xuRlCFvivzE~mpF6kx`2a~PgmJc_-ZjFsQ~!Z?ux?<7H-qHZxkMry9v zcm2z3sIkg-o^(%VM+-(zi{^revppx8l?`x%COJFDh7f-75|M4kyI-OsSL%EC`p#n+ z2~X78gs;dlFGQO4vz<(=IF;yi|jV|XU z``qH<=-$>NC)WGqmsjgIaYhgXZX)Rn>m2(Um6>)d(&HTPqT*FnF!%3FFamYMlvTA? z*?wX+ILKIIBx~eVoVp_;R=%}m2IqX)vre3ab) zx8I|qy<&N}Rb}mKMc?=jHv%!iLaJFps+}#X&;{*P)fnIGkyqJAC3Px`Wsgg+;OmtB zl>B`e@4oejndz%Zake3kft8cr#eqhv#-I4>a1lZvL7CMo`3f8!b#jO~sztZI#Tjqz z7)$$$B#*jwlOryY`sCIj@J{GBoAz8*AJGZBIxh1xP%=Ge2%R0T27QuIN z(RqnLTT!#rgwlLi>bve7!OPYb=sBjX`D;v9oSj1ipirSDxdC=5b2}JVbpI+NN>1?Z z9FVvo_~(59lvh+00BWf{lZ5-IdjRNgb#38~EA?zEysFA$vToybv{jOL@==P4)sI==JdV)2B`8X|&p+Lq&=IMf6Sc809$x=FEB+2`^WV3dVs!;nAfZQ#Q=a zC!7?E9wt;7_D<4x!FbO^>`LBbbREhLagBeOi1OdpAkS~rUJwAO9|kI^o~~aYPneP! znOimIHU}*D(3%dWkZBh0 zr!E)Cvxatk65I;~=(IoOMM&zw>1^+MT|%&SuH_46W*VmkQYig6!VzI-uF!C5$wWg50B6ZnPkGw42Y(kNeNt5RLEDbuecN55fRV9{*Q!8c5Q}Y`e53jlQ#Ueab$-Wi zC#FS>F$u4m(f}?m%dOKNcC9xQBDJ?&cr^A6=+>#IbB%z|Qm;2$COvA78#SuZ#@c)Nj^j_BoYOW-$e5lV`K93u1;S-=dO0h!521tI?DsvH|#B2XCbI#4q z78nXFczTPqG==54hobBc*?cHQiu1s&w6N#|-;|Lv z<(2)0Q@y|+#Vc;`4M0{x6Ix5&j#dv7-4&E0jr{aTm$}?}mT8LeDXa@p?KzTsS2A&$ zQR^@0G^jpsG0KIBL3U`^+`hY+B>ADd7mh>m4h;U zd3lA<)|q5=6r?uCMNAwMkcnQC$3{Zq78(C-7!IkaWqG@a$yaCHXJ8n3XB|Sljns8$ zCvqnx!KeXS1i?I7A&lG#SzQ4K7z2=Nfs$~LDE!&g^Xu;%=hMlHTdPx8 zJcx;^ zZEzsy7&XJ+7`Wu(>hE^iD?h8=z-k5b8fR*n|AO=-2dhm>9HhmOA3JB4nqu27-w2B< zmyO{(swP^(e=CaeE7`zeje#q|<-=dgwM0qy;8PCA5Xn4{`j9uAd;`kOIS=V{idRZc z_f~+CFT3obCBeJFP(}=8i+c!_;NE74yHE&X1x(N8vJL`4-9xOoVn*nDk}0LZNy+3a zJMU%)+w4{m6y*midXg)1t8trJU)vYEl4@usW*G$nsm)#eP=|2 zpj+W0Z6&FaMb8ISEI<0`^*4=+W-hln9rJWmw*n8LK=(GY`GEPc(D=z9m4^-Jr_+x2 z&P`?71N>As&klErOJ1zB-pPpRY)u^f>f zAogVHB_`^(5gD9ZWE=e{&quKOWVmS{-bSkHfU%&4xh_CBhqJKkTWvu)-4n}Pi5_+v zi6D|`pH&jMCs!&j?VX$7jC)Ra(&&mLen%t%jb2p$TXi{9f9_{CGR1Hb_>O$Ypzt`E zXyTUVw|AB}+9y+U%OBJGo=A9nvAa%9sFZIG*~EVL{pcuRN=Xklj!o6T*B3uP5+zC3 z0=7+g4>||_RSk!xfPN==kHRLL8Sfx5GEgbu<6HU*wS+P`$y<{#&d0dPCgGWU_P-#A zB6ckZU;QnRLZCdcU`e_dzwGf$WVv?!i!)p;AqIWRWi#0NyccLZ49^fTC+gA9A!uj_ zrC)mOqx;vbvGb|&^!O;Ntow6EE_iT7?E+;1_J!^n1!3v$qquwjI#1OWm8 zl^_79{1=Alz4sInvH}VQ5@{i)MC7bWlmPg1=R~ROR0V(W+sROcp5-Uyc4$h8swXod z58cm}7CdPvSx@fPW_QXbRc?X$rs?%101@8>#JS#zt+M`#h(^|PkwBb=NyI;TUWW$= zI^sUWJiI8F<^61~vssELbok}$r-c@h?!ICQ4XNw@)iu-dgaK=8?wK-i>QHP6nAxqP zt-jbU6D<^V>_qQlR5_yAUPvQWNgn8kF}@)rV(lZ!n1|@J6QPEB?*WtEx;I(QP60jp zS1{m)eT0d1t0Jxk0*L^1C(Dr1su7w{r>B�)|SbM`Pkah@kzPPdyaek@eVm1Y79P z*(&2TPSK%Cq3se=ypXy~h=w*v!dAe$Z39DkbW3c`=+7U8&=lbMfPE^D9iF#&<)ecI zU+g?k_aw)>Bx+9TuO(dDi9q5^cc)~itB=m>266>FFM14LwP;>0qc@NqBj2~FNNmCN z!LDT0VT=|e^m4tD3q7l5#aZOcnx3V`cJ?vwv5S-McvL%`lQQ{#xxcQ8#T*W|o7TTY zZ`g<;*E2@lCS;YZr%-jCx@zO$-I4)gN11aKqnN_BK|6&nCC&`(U+^7Snc6548*aX}pu+ zUl0@RFYH}kfyq~Tm4o6k`{@_Lkg-JRPqC12&PEd7N&gYp|2vF1xh z8D>X=BL)L^XCa^1Vs_sJ_wYqrU?UJ#)5B=P+`*DKI6%l1oj7JGXSV*rvsQ=`+1-s2 zC!Bi8Lb;9o3!-FOUvvvui+QWR+vHZ)qs`1*y(UI#e3dH1iL_=A@t5E(Xwy;d#+-Q|B#OUS-Nxjx-X7012d2}r3sPV`99-}-=>a?x@=po3fm zNZ^i@u*1_ylRy4{^@e6 zva##KCs^|3rC_}g8CO8767`S@mF%HlBk??Z1w;Z4lA}_Ub`FM45OPVvSzRW;P&q21 z59IY2rPXM*cN}q*3I|!*@iK>0kD{$fpk5&jefwyx3Giw%$*xd{)9NVrn44M#7<)j} z28GRI5{`S}YV{dyKs-=&ErefmNAC?8jQPrp>xvRVXXYL^b^M2e zIx4YyD6}duRDWw7;h82h^~mo;$qH4y>Si5*A8XtQeLY-40Blf#r=`q=dUG~47W^Z| zqvHT*@~tKErCb;Ela$-UHSw5pAt0j#=3L<^z(&aPNr%ts3A4Us+b$l#%nLf#p>wMz z5h=sIqcff;jarru?>^KMnUFD?5!Ikd%>Zzmq7n7V%J#5x0BNY6&5+HGLC@pUkEk1E zB{f5xMa$x=Jk<4F!}kRV4R_q@DTQRe2PHl@8ALQMIWRg_j}FQzHHl>=J~(YUbct(F z_RYm)kxh8yKfvUZ^?QvT3IlN!5V-+yYEqRCrWIyaBGVvg?l1jsqP81a2d6v^5vq94sxk$Th@A zF*X|^8Z%1|Xq5RB{@Jrl1&4N}FRZkBrC3QrB@aUxi$s~@G|V`@;Th9KMBE&=IK2qu z7@z`NZSEIzmET&3U9cmjwmH~2 zy9Wh@kyZ)aPoRH6vc}3oz)L`|+5zq+g#_6I^zFxy0Cj{4lZp$so4$WFTV$qHZM4!~wWH4hG6(0tXcm-tZ~Pnf~BjMk^vRH4gDG zYA=Ef50doVU=E-ndnd6vL%1sa222!KL~C~yug2sE<>Dq(bPW~61?Vz|J{!(27rJWH zoDVNp++fW!43E`DX_3B$HAU~&(Df=HF4*2JC$kWoHE-=qE|u9|L_qtC zYv=JnWWp;bxBMb&5Ou%2M*~K(VeOIo@V0&Py|d!q5el;xa+wa2IkiAJ@JTeM7F`hj z)JLA@QY7=1i=EuJM{&w8g7UcX)57on1^ES$pY%-0uzof#C|yut*|SL84i5U0%qR=( z3Tiv{2{YV+73pcSw+Z$VpWZkIxos+Rc^^>BY|G_tzCcobb1jNY`74b`WIxfuy^|WSfHsvYzrCLv_C4? zTvNj@-$W+sJup1(wqorS-Nqh}Oil%%VxGff5&#qJz&htw@ehzyU^!VmO&N+hJ^F*> zr>kz~{~2P36cpZ9VkO{Dykv^lL$Nv8=etl=56bQ{i9h&IR+D@u@z;KcD`v$rKh+WQ zP1XN07KY|lKMfS*qi`q(k^B_H^&bc9@OBe%@$c(B-rJMhS)^3}7~B-BosH z*b@r*0qP162qA{7WJ|T+P1DTT$JKKS%acDA?eljOe))y*l;lKODqpFi4Qq4jf4n`RxRnd-!{z0ra)+_nC7ao zjJeR<&%fr`pK+?YCO)84y^l^vz!}(UaK9gTZA(E|a1Xsf1-h6?^v6nnf;Ra^92kuZ zefBtCP;Nbb(5LU}>ce!3Yrfo)<*d3o`eL~X9~7N?s8xZ9NqNufTm054ZvmhxP(uWIf}TzY7Adt7{Y z#oBcM4(QE$y*@7%Eg%8|uWP4^&2?SEYI^^0j5T*1YW*2l{L_>kp#Gc|5CE;MhPml_ zG6VGZdy;9O9Uvxmv{``kpMHp2Mm+tJ2ShinDtLIa$ft*hEf&7U=Hv>*I_4>*F^aoX zj0Z6-o8+nKds&9Gq91rmCTnY--6FECZLl4Zo%B8!k`o^|mqh*;()Qgdur2+=L09LOUP_J^7MkOWyfaL0 zG-D`r_hAIpv9(EAeJur ztQKoYkdpe|dY#bCC5*(S4FK`Wun-cbXCWwt_9fv=8_B@PJN|gN)d~`7H!hY)5PY2| zu$Lm9k>R%M)z69yZ6zdtRu3`26JV0sl4B>z8*Xa(1asdt7V8= zKLT#4lHvR7Sn|8Uz!6R3>_2{yE0!&=kQ={Bloquop?wGw?&SafPr1jU>^WsHq5teWhr$1|_>^0sjy0WuEgE1k^2{j@x z(2Rm*7!BB;Eq;0h%(x$t49y|ZMFZnfhX8}cVTcU^;swkEcogj%EbZ1oJVcpHUVpYg z$Z^5s%Z7+%v$R}uJJmz*U$~!pMyZz>HhsKn%sx6etE&O9^Datf)?S7u=N11*&TGGabe$Nucvq#;wZ_EE{3hiVg^Y|d?i^DC z?4D0ZNh>QF+N>Zm`5tA;i(ZupG`E)C6w~`!6b4A<)r?h@m$0>sCaM{Dx}m;`9y6!D zJE}<(4Jl&>6MZLT4~QaiSt((PKjbJenW`XdM)|NlOeuMqgl*|L^YN8nV&HO`8sUK{LQ) zZt`Vva3hhciXQ*f9r8N_Z2NkulH3#rfaM2_AdyHy>k0ijNTx=9b49bo>#?|pfLp6b zq~-LKF4$DTl9xceEk4u*p{bfO(ndPx;>2HUV+%mU<`M&MZLj-s<+aK#cV(!`J;Vne zAAnsPh;xe#51u>6psaa2-({B`AvxsneK*k6>6CBls-NX}Yn#Q2TdNY&-m2ealP$OF zl{_R(kI2Xre@?}Q0hr!Qn5J5@66aF}KXW>W?dbI|rxQj}jqOVj+EQ(*mJ}6S7{JN9}f7T2J$bIjfd< zAISd~>~@``Lq2@f1Wok*x91hwRH?#6undhQ?_(xQ@g-kNQ2sbpt()Jf;nAQ9;YSw@ zbb!_nk5+{-VcuD-6ZyzRa=4NHzhZ~Y&>c2Q=pC+Vcc*g1rsrkfOgPS zvaOF15Qtnt#)+cBfExQ0H+A2M0UO{Vk~(^K=0a6$}? zHX`J*u}NEOtFCHmtLZ!)`?XV9k8ZSvf4dnJrTttecB-2Tpb$ywQwKjtT{S-(e53gp ziwsk$0Z0F7kRf*wM}FW9S`9x~oQ19D53;+^nYt?jlxFV%CUA8xdomqkcv4=`kL1Tx z-}YvMY~OZhKMs{otpNsoH++M~ATm*{uoY zw3J#=x7zGnF82PbX{PIo;eRu8h%cp@wb5Up!!7}|unhr9vCT>+-OxL_(k zcJ2pvZ&I&=#1+U9VFW`|P?870;2(@q^foYVjLkK8sa=7_J(%6mN5L`%sB0O4jTfjk zH}9!7l1OB6Q}lLIJs5+Mu&K;pav!Sgw9OEI3k&HdXP!+YokpNb9`-S|!yIOrn1DKz zZz6yLcM95aa!FkhICr#Z6bf3F349J86v*Hn_jogu8z5_@3X-o}$_1iXq8Axl#df!D zzpxLNsm)kDc794GK3fi)Az$hy#P`S|&e_~%%aeji>L%oG=w1f(-Fl&^9Qva3*~6OI z-#H(*XTZ{A{@bguxV((?7G!@lu9gmD$%zZ5wz7o*aC^R?fV3=QdPAS+}9E{{ei1 zF^rn+b`? zx&sVM(1c0AnS18hB6oI)V!i=G4kPm&VNtx6Q}uCQ{+vAXn%q_Yn7`EOCA?kAeHx&2 zfr%&QAgJqQm!a-o?0Y^{aX3XDcJIknlUfN4=k$@ro@>vcAN-(mT-mi;reSMJ89 z`dr*Z%v$lTA&4w#K(*Wt=GYGgB}Kc2+zw3-hzFkZ7VunRLwb)9l+X^aRU=Ud8$<)N zIziYE5k%{O!3aVkH+-a62QL>B#sWc(1#|Ti2?I@2`gMYsDm2F#H-`=*Hu+9J2(Zj& zJqx*=OcLz_XIp+se3TJIA`#ODSH8(b+(WvC(i)3#i(a%3ediSvbp?6vM|EjTiT1D- zDWpwFyZ^7JYmI8+?7EX=l1#V`5CtU0L4t`Wh(IMN0WykQRB%x6ihbcF6!C)G1QpOE zqzW1VAzCj1Mxly$siHzarI;$0Q~{N?B0->lATOYTg4W{uJ$&C<-@mM^l^^p=o^$ru z=bXJ)t*dC9{iQ%Lj?hB%4hw_1u0*V0OS(j7^294)8Gho3FNtqbB^)gb;;>hEVdo-3 zIwTXlGy`~+aT(Jg#l%uRC}32J^vq7VhTLRp05N>`C^N-M*uXp)mSg&&{D)3W&me_1 zDwL#_1m7oMi<`hDVRlapoLC|-i7pZF_I>zr9&1_FnZj7sLG5NrEt&DFAkOFjy~|Wr zXL#>zy8f?yhxSlKPL<1SK*p;>4W*Zt~TT3dB-r$XY_sB{w7-;1OO^zf0kpLh%WbXy3`Rj!#PN4bWgEQjkG{n-`KMnJ5H%E*4&& zB~u6&XfI~7uvn)Go(9``ye;rxi>utMN0!J32Cbl&elTN?jokGCYxg8xrXdj>^W{<< za!M1gu0@H@T0SE| zW=H1xc%!rqSl*5B++^KA#oJ_e4Z`#9dH}IH5#FINN~9QOw~8?k_P0Ig#PXTdZv>82 zu8I{x$vvgT!9@9R#bp&WsLRh?6$9tMyMkIpE88VD-6PpvA(;nysZ zXaUq?7@*SlV%Yc})U~%B0m6+k(SISfv9JqD8-NZyfWQ@~u4FLP6bCVOlz}b=w?l$a z5$)f=i02d^7O4%i~jJbuf zWfEbb7Fh_4pvy+MnX?{8Y+jRQe-CSD|2*$}sLg>J6mbm0C9}mf6_0XH3UWvyLTSvD zpMpyr>C;|9{A3x^r(?sl?=Np1BK109hs9nynL`&n)r+q*0sK)5>S2l42pk8f&0gew zd~t!RBAA=)*eq$RfYT;%Go2CK+j(=EfKC+?;XA(^c`ZK@?bF0#^->+~f>FS8F?Fb9 zx@|QFm5KTfX4`xO^FfyJ-M5p~77lhWrIn+E98^&ZdHeOUUoYBcUVOfYSKH+C^ZcSq zQ+ZSOsb*2ooQR33AX*)Q=tB>mvE^xho@8; zlLF`C^?3p+Iv*H7N)Zzcb~?U8lHI7b0OFv{;Bj_gej~t)1du`<)QMUa>IJZpylRN& zb6#m;g1Has5RN%wpD&c;Q>Z*FAhV6qXd^k6r)H+6@|6(tDdmP3JC^4~mOA9lSp8t2 z{y2lj@>4%g^fJCJ<0d6f;YW*pXw(_A`b5GV#zFsnuOja(<-Av09kou2N2O%mZSxdc zr)A~>caLi{diYhfL!QxmZF4URqe0 zy}!YL`Sr6+=7pKxePbw*8hbyCB&8fFdk%jcupj;@F1W7Kfmgex>oES=^eaF8Z&QNKEtB0x3d(17D)v4XBu8igc`=aR3EB576QbWC65WheQu| zORefT?-cY>TMmYosmNVvaS!a+v)oIh76+4cSIUzc#pTLneQL|D&e#+RjJcl}nsFy= z`CN~e?wwcu;pM6`e+)C1Z7qB3UFv|E|CRO&i4Pvo51$=Avt#&TMy39*sr!SD4?hd| z_?lt8Hg1#K8|hBrM=x^Zo&SsTxeHVb4-fN5MI{Bwx|}aZ3Fm3Tb!i;|$Er;!V+s&G z0>&AMbwf;O3=PO#1qV4oxFofJ zuxV-H&4KiYFsmL%LkMQ39?>L-B=t6ic-gcXO+PHcPloZ0i%h*s-mbYR&fH zVPdu=!czoGfVVao*+b@YgYcy)EFG0``UJe?h^CJMfzXkBYfADZ>zqOk?Q3Xq)Fk|T ztk=?i*nSGoaFA-u>=hx&yYdwB#P{O6F4u&+oyxgC{>%5(UL`S}(GmOJI=^YVQp?{O zysmT6H!IJs{-A#S)2YIBf3*9!dOF96Fplc|*wukxaB-g(8Js_!s<%*j6T-s>NQx!0c?+6_)WUAuZ_{E7Rq zS0E-?^^?`m*X(62#cc-{y#Ms0r}IVCFC%?G6v6i?bG03oZx6}v_T~;axfYs^0M;ZA zbdUyc;ATL6RAK?_=*L5PfzmEaAg2Fdei*|*B3;yG&^rZ4h^Awhq4SfHhP=TC$>iyq*ZT~EAXcYFq>&Cx_+cXNu!d4eV9Z9z7E z4!yvx|9WB)-<-9JEKyq_3s4I9udPU|HB#9ijwjm zsAM=R7QCRZO(yEOfp>KjNJayg+`K^6KSCmq6Bs_=rb?oqrN`Usfl(TyG~a{FCJ<({ z)L2VKs41OFV*!*TCzk?-8C@bKqi@F(KGT!n)e6db2Q1d|iczx0Eg`N5&VY9n# z^irGqv3!w@z!JtgrRIEO!P5`2nMq+)6gB;pj5R6o&_u$P=E;e5P1JF@rOcOTAmZk( z9G>Npd-0#ScBN+r-4A9rH|1QK>iW7uZ|?o4!6`o6E&Pv`&)=VXG?O=S#*b~#sPUWQ zifdx?;!VA(%(V&IzZ7KM+WN*84>09Kzd7vs;BB73g#arYX5|5ukOvtZNdy$N%?ND! z9JP-(f<;~7@LMI7LKTk7<3pCy3TxqjT3W`qd^8szCo?gbV|XXWwmURS{vpNWc85Vn zIA;f(sG`byq7la3T`?4$QT#rp6y_6NJ0h)xSf5^{ zH!|-Qity!lYo&484Gl>0sl9Yp0~ZZ9MVyw_bogzI&O{^pXN5mrk=Yh;D^hXGj0lf! zTJUU@Q5N71;RLyglxFq9FXf6kuEa8Jq0*|EJ7c!B^4Dg3tq8|Pay=0zPdHvKuQEc4 z09M-5L*_II1twVl!Ol}D(4YE1ORmmM9-p;(*gABfN9MwxE;*kXbU#$7Dk^18b&U>* z$%)@}y_=J-oT{oiKM}m>m<9wO_O>mBf6sRqpbhFwvsShlbsCl={Dv_$npe+zOb+iC zNn(Ge=|SeGu-?~z`h2kHRx{l7%t_9|^34Kz7`Ai(EYsvn;%FMEbICw39=_cI@KlnS z!Bb-jg!-f+7IEWp4pmMA`C~$lfc7yhS&vx9P;JDdS$BbvO9EfY){KrT;4ffFB7-dJ z8&Vvr>7w&FoB_J$-RP>Og~Aa<*6E;5wZ$mb3;!Cnasxc;#Va&oX?ewax&A_LRtNoi zNKr}zl{?W&5bgjCnTIS`3#R)bYih=SzB2TE<6aAXVkII~8#DE+NX+jO;&dyQ@Z9B! zuJ@W4fc$->BMPr*f%R+okLlQ{t({8Cxn=3(vjac0e;aJ?H@qWY+0L>jU-dqI(Vx1( zF<$6vwKhJ!?PcYbzdv_-OnBWN7x!x~IJY7elem?HEe~L` zSnfVa8&hd~2PVWA3g=Skbwscd^F48rd8}`yqZNMEDJ@2dS)fO_5$NE=WjCF zv{}y@cT?~@;t6^U^EP>Sb*d!Ey{d^;&A~R06LDQDhUYHGFY{=BR2VTB_c?U#!~Z)< za^ikN@5Yp?XKSlsgT<{&GI9-CvWnX@2QWd_HhPx-vq7jW>*l7R;JV*~1N}J-X1!x+ z0yhdoIMN!zjk!(V785i_8V@$sVl2VzRkRcqt&>a4Pms&i$cQ}JPH6(HVp)(x-~e>s zfORz)$lRsijXsb7$5cpW2LD-!mrm52Ee+IEG0Up&?Tzp^W&0bDx zK-Vx$+rqYY3Kli64A|9rV#9X)J6Dk--G8)}bvrRn;1mTP5iFP!fY^Yr^U}>twnv04 z;H+=!)N8fe)Lxj4=lM|~4%;MuKiCJBwOhCWOUUJPjf!ooWZ?M4z0C5kv;OL5&rby> zoh)m#@bdRP{_0hh-bFl>sBJe44_v!i^#3^HzfcRhg_|JWm3`QKXdm+Rn45s2zLh|{f<;qP%}9Aa$?*RKmSs@RyjrMFPp@S7cVe45 z1rEc6_zM|u5apta3ucN?pC%YGV5kdfYdb*gg8We)1bl7m%m@m}8GyC8r9Xk!19ren z^g@s&L>3lRf5iPaW^UbwbK7vS~a=-;&|NE@63`b2S~ zLIE=p{62#`oyZ|s{1hq;ggIX@{_=0?EFVYUSR0gIqFJq-5)2; zB>v2=;5^O65%IIqzOC80Xa}!2P80E&J5uw=`p}~)aW9%z-31Ydg|HV&B2waid=Xnv zTs1MC6CHSI=gq-MV5T@Ci?~z>%Y2n3MaBpwO(6rE)H^xQ zSo51uQg%=v1z*iT5!x{7Yd6DP0Up%MP)zVWL1onXTAtZvBbW`~yQ!fEwro@*pk3sm zLuz`koCFFSF`{}`L2j#7vcJPYQ8AdRGX4F1#tPnqK3gsnV_7c|{=Agg(=~i%R)fm`TK9ijEa&k+0zGlVDM=5J|L{O*@xs1nLM{mX5Kt=!U{a zBsn}dbI5zm@&cZoJ@D_2v1HFL!doY7zIuK+U@j0(BxpBuISpL@xjf_f-ICFbVjipQpAa}Zs%rthFgqvCjJ0( zB%K05O}&*8b%`?^Z^NHF=!Fvja|vLxzk9P$MJZ#OF1vioQXS>q06nqjhWv28qI6#q z9$teud64;C^bMXq`*625#&X(SFI2X@wO>(+_mKW>as|{&9c$`<v@n^`J zOGS^Kc{ir9w*ltKP7{S5{x5V9^}c6DNT&07j8w_Yyp64$DO9uVvcTYz6SMu$KO(S8 z>b<_KHgA1gx_xqUc4X>c-5bKgMXa$R)F8EDkDC9tUG2>shzdRuWC19hT>%X7WemmI~nJ z`5W-+I|>~j%@I3uwQ18g(|Zq*#J^xSc(Kv35_Rny`j)Cjf z!Qa1S{0+CSM&KN9;e0MrE1A%g_!&Q?Hqyl8roM4dGVI5zKD=fG?LB+`%W3<+18Rh= zZ%Te=2JSQ%P$Fh@`__ .. |reach-ur10-link| replace:: `Isaac-Reach-UR10-v0 `__ @@ -212,6 +224,10 @@ for the lift-cube environment: .. |cube-shadow-vis-link| replace:: `Isaac-Repose-Cube-Shadow-Vision-Direct-v0 `__ .. |agibot_place_mug-link| replace:: `Isaac-Place-Mug-Agibot-Left-Arm-RmpFlow-v0 `__ .. |agibot_place_toy-link| replace:: `Isaac-Place-Toy2Box-Agibot-Right-Arm-RmpFlow-v0 `__ +.. |reach_openarm_bi-link| replace:: `Isaac-Reach-OpenArm-Bi-v0 `__ +.. |reach_openarm_uni-link| replace:: `Isaac-Reach-OpenArm-v0 `__ +.. |lift_openarm_uni-link| replace:: `Isaac-Lift-Cube-OpenArm-v0 `__ +.. |cabi_openarm_uni-link| replace:: `Isaac-Open-Drawer-OpenArm-v0 `__ Contact-rich Manipulation From 4349142bfa9b85c9e696bf18b6e548e88cc247c3 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 14:38:23 +0900 Subject: [PATCH 15/32] run pre-commit checks and modified codes --- .../isaaclab_assets/robots/openarm.py | 6 +- .../config/openarm/joint_pos_env_cfg.py | 12 +- .../config/openarm/agents/rsl_rl_ppo_cfg.py | 6 +- .../lift/config/openarm/joint_pos_env_cfg.py | 15 +- .../manipulation/lift/lift_openarm_env_cfg.py | 49 ++---- .../openarm/bimanual/agents/rsl_rl_ppo_cfg.py | 8 +- .../openarm/bimanual/joint_pos_env_cfg.py | 20 +-- .../unimanual/agents/rsl_rl_ppo_cfg.py | 4 +- .../openarm/unimanual/joint_pos_env_cfg.py | 12 +- .../reach/reach_openarm_bi_env_cfg.py | 146 ++++++++++-------- .../reach/reach_openarm_uni_env_cfg.py | 78 +++++----- 11 files changed, 167 insertions(+), 189 deletions(-) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index acbafc3c4a6..399a67d8dbc 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -17,14 +17,12 @@ Please `git clone https://github.com/enactic/openarm_isaac_lab` and `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab` to use these configurations. """ +from source.openarm.openarm.tasks.manager_based.openarm_manipulation import OPENARM_ROOT_DIR + import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg -from source.openarm.openarm.tasks.manager_based.openarm_manipulation import ( - OPENARM_ROOT_DIR, -) - OPENARM_BI_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( usd_path=f"{OPENARM_ROOT_DIR}/usds/openarm_bimanual/openarm_bimanual.usd", diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py index a7832a5cd8f..0d4114d932f 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py @@ -3,6 +3,11 @@ # # SPDX-License-Identifier: BSD-3-Clause +## +# Pre-defined configs +## +from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG + from isaaclab.sensors import FrameTransformerCfg from isaaclab.sensors.frame_transformer.frame_transformer_cfg import OffsetCfg from isaaclab.utils import configclass @@ -14,11 +19,6 @@ CabinetEnvCfg, ) -## -# Pre-defined configs -## -from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG - @configclass class OpenArmCabinetEnvCfg(CabinetEnvCfg): @@ -54,7 +54,7 @@ def __post_init__(self): FrameTransformerCfg.FrameCfg( prim_path="{ENV_REGEX_NS}/Robot/openarm_ee_tcp", name="ee_tcp", - offset=OffsetCfg( + offset=OffsetCfg( pos=(0.0, 0.0, -0.003), ), ), diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py index cb94987a450..23a16dc3df8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/rsl_rl_ppo_cfg.py @@ -6,11 +6,7 @@ from isaaclab.utils import configclass -from isaaclab_rl.rsl_rl import ( - RslRlOnPolicyRunnerCfg, - RslRlPpoActorCriticCfg, - RslRlPpoAlgorithmCfg, -) +from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg @configclass diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py index 25c2447a7a9..2b779b7cafc 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py @@ -4,6 +4,10 @@ # SPDX-License-Identifier: BSD-3-Clause +import math + +from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG + from isaaclab.assets import RigidObjectCfg from isaaclab.sensors import FrameTransformerCfg from isaaclab.sim.schemas.schemas_cfg import RigidBodyPropertiesCfg @@ -12,17 +16,12 @@ from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab_tasks.manager_based.manipulation.lift import mdp -from isaaclab_tasks.manager_based.manipulation.lift.lift_openarm_env_cfg import ( - LiftEnvCfg, -) - -import math +from isaaclab_tasks.manager_based.manipulation.lift.lift_openarm_env_cfg import LiftEnvCfg ## # Pre-defined configs ## from isaaclab.markers.config import FRAME_MARKER_CFG # isort: skip -from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG @configclass @@ -58,9 +57,7 @@ def __post_init__(self): # Set Cube as object self.scene.object = RigidObjectCfg( prim_path="{ENV_REGEX_NS}/Object", - init_state=RigidObjectCfg.InitialStateCfg( - pos=[0.4, 0, 0.055], rot=[1, 0, 0, 0] - ), + init_state=RigidObjectCfg.InitialStateCfg(pos=[0.4, 0, 0.055], rot=[1, 0, 0, 0]), spawn=UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Blocks/DexCube/dex_cube_instanceable.usd", scale=(0.8, 0.8, 0.8), diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py index 613f8bfdf7a..9ccf1ccc81d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py @@ -7,12 +7,7 @@ from dataclasses import MISSING import isaaclab.sim as sim_utils -from isaaclab.assets import ( - ArticulationCfg, - AssetBaseCfg, - DeformableObjectCfg, - RigidObjectCfg, -) +from isaaclab.assets import ArticulationCfg, AssetBaseCfg, DeformableObjectCfg, RigidObjectCfg from isaaclab.envs import ManagerBasedRLEnvCfg from isaaclab.managers import CurriculumTermCfg as CurrTerm from isaaclab.managers import EventTermCfg as EventTerm @@ -51,12 +46,8 @@ class ObjectTableSceneCfg(InteractiveSceneCfg): # Table table = AssetBaseCfg( prim_path="{ENV_REGEX_NS}/Table", - init_state=AssetBaseCfg.InitialStateCfg( - pos=[0.5, 0, 0], rot=[0.707, 0, 0, 0.707] - ), - spawn=UsdFileCfg( - usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd" - ), + init_state=AssetBaseCfg.InitialStateCfg(pos=[0.5, 0, 0], rot=[0.707, 0, 0, 0.707]), + spawn=UsdFileCfg(usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd"), ) # plane @@ -103,9 +94,7 @@ class ActionsCfg: """Action specifications for the MDP.""" # will be set by agent env cfg - arm_action: ( - mdp.JointPositionActionCfg | mdp.DifferentialInverseKinematicsActionCfg - ) = MISSING + arm_action: mdp.JointPositionActionCfg | mdp.DifferentialInverseKinematicsActionCfg = MISSING gripper_action: mdp.BinaryJointPositionActionCfg = MISSING @@ -119,24 +108,14 @@ class PolicyCfg(ObsGroup): joint_pos = ObsTerm( func=mdp.joint_pos_rel, - params={ - "asset_cfg": SceneEntityCfg( - "robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"] - ) - }, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"])}, ) joint_vel = ObsTerm( func=mdp.joint_vel_rel, - params={ - "asset_cfg": SceneEntityCfg( - "robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"] - ) - }, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"])}, ) object_position = ObsTerm(func=mdp.object_position_in_robot_root_frame) - target_object_position = ObsTerm( - func=mdp.generated_commands, params={"command_name": "object_pose"} - ) + target_object_position = ObsTerm(func=mdp.generated_commands, params={"command_name": "object_pose"}) actions = ObsTerm(func=mdp.last_action) def __post_init__(self): @@ -168,13 +147,9 @@ class EventCfg: class RewardsCfg: """Reward terms for the MDP.""" - reaching_object = RewTerm( - func=mdp.object_ee_distance, params={"std": 0.1}, weight=1.1 - ) + reaching_object = RewTerm(func=mdp.object_ee_distance, params={"std": 0.1}, weight=1.1) - lifting_object = RewTerm( - func=mdp.object_is_lifted, params={"minimal_height": 0.04}, weight=15.0 - ) + lifting_object = RewTerm(func=mdp.object_is_lifted, params={"minimal_height": 0.04}, weight=15.0) object_goal_tracking = RewTerm( func=mdp.object_goal_distance, @@ -194,11 +169,7 @@ class RewardsCfg: joint_vel = RewTerm( func=mdp.joint_vel_l2, weight=-1e-4, - params={ - "asset_cfg": SceneEntityCfg( - "robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"] - ) - }, + params={"asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_joint.*", "openarm_finger_joint.*"])}, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rsl_rl_ppo_cfg.py index 658f4f9f525..f5dbea6ff22 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rsl_rl_ppo_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/rsl_rl_ppo_cfg.py @@ -3,14 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_rl.rsl_rl import ( - RslRlOnPolicyRunnerCfg, - RslRlPpoActorCriticCfg, - RslRlPpoAlgorithmCfg, -) - from isaaclab.utils import configclass +from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg + @configclass class OpenArmReachPPORunnerCfg(RslRlOnPolicyRunnerCfg): diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py index 6ae7e1ee76e..19ec27f6443 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py @@ -3,18 +3,16 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab.utils import configclass - -import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_bi_env_cfg import ( - ReachEnvCfg, -) - ## # Pre-defined configs ## from isaaclab_assets.robots.openarm import OPENARM_BI_HIGH_PD_CFG +from isaaclab.utils import configclass + +import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp +from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_bi_env_cfg import ReachEnvCfg + ## # Environment configuration ## @@ -32,11 +30,15 @@ def __post_init__(self): # override rewards self.rewards.left_end_effector_position_tracking.params["asset_cfg"].body_names = ["openarm_left_hand"] - self.rewards.left_end_effector_position_tracking_fine_grained.params["asset_cfg"].body_names = ["openarm_left_hand"] + self.rewards.left_end_effector_position_tracking_fine_grained.params["asset_cfg"].body_names = [ + "openarm_left_hand" + ] self.rewards.left_end_effector_orientation_tracking.params["asset_cfg"].body_names = ["openarm_left_hand"] self.rewards.right_end_effector_position_tracking.params["asset_cfg"].body_names = ["openarm_right_hand"] - self.rewards.right_end_effector_position_tracking_fine_grained.params["asset_cfg"].body_names = ["openarm_right_hand"] + self.rewards.right_end_effector_position_tracking_fine_grained.params["asset_cfg"].body_names = [ + "openarm_right_hand" + ] self.rewards.right_end_effector_orientation_tracking.params["asset_cfg"].body_names = ["openarm_right_hand"] # override actions diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py index 4a1e9f3cbac..356642892a1 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/agents/rsl_rl_ppo_cfg.py @@ -4,10 +4,10 @@ # SPDX-License-Identifier: BSD-3-Clause -from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg - from isaaclab.utils import configclass +from isaaclab_rl.rsl_rl import RslRlOnPolicyRunnerCfg, RslRlPpoActorCriticCfg, RslRlPpoAlgorithmCfg + @configclass class OpenArmReachPPORunnerCfg(RslRlOnPolicyRunnerCfg): diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py index 961cd059312..a7c1ca1f1fe 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py @@ -3,18 +3,16 @@ # # SPDX-License-Identifier: BSD-3-Clause -from isaaclab.utils import configclass - -import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_uni_env_cfg import ( - ReachEnvCfg, -) - ## # Pre-defined configs ## from isaaclab_assets.robots.openarm import OPENARM_UNI_CFG + from isaaclab.assets.articulation import ArticulationCfg +from isaaclab.utils import configclass + +import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp +from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_uni_env_cfg import ReachEnvCfg ## # Environment configuration diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py index 5e6ad87d6e8..bc3eb0b61df 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py @@ -3,11 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause +import math from dataclasses import MISSING import isaaclab.sim as sim_utils -from isaaclab.actuators import ImplicitActuatorCfg -from isaaclab.assets.articulation import ArticulationCfg from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.envs import ManagerBasedRLEnvCfg from isaaclab.managers import ActionTermCfg as ActionTerm @@ -20,13 +19,10 @@ from isaaclab.managers import TerminationTermCfg as DoneTerm from isaaclab.scene import InteractiveSceneCfg from isaaclab.utils import configclass -from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab.utils.noise import AdditiveUniformNoiseCfg as Unoise import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -import math - ## # Scene definition ## @@ -113,14 +109,18 @@ class PolicyCfg(ObsGroup): left_joint_pos = ObsTerm( func=mdp.joint_pos_rel, params={ - "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_left_joint1", - "openarm_left_joint2", - "openarm_left_joint3", - "openarm_left_joint4", - "openarm_left_joint5", - "openarm_left_joint6", - "openarm_left_joint7", - ]) + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_left_joint1", + "openarm_left_joint2", + "openarm_left_joint3", + "openarm_left_joint4", + "openarm_left_joint5", + "openarm_left_joint6", + "openarm_left_joint7", + ], + ) }, noise=Unoise(n_min=-0.01, n_max=0.01), ) @@ -128,14 +128,18 @@ class PolicyCfg(ObsGroup): right_joint_pos = ObsTerm( func=mdp.joint_pos_rel, params={ - "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_right_joint1", - "openarm_right_joint2", - "openarm_right_joint3", - "openarm_right_joint4", - "openarm_right_joint5", - "openarm_right_joint6", - "openarm_right_joint7" - ]) + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_right_joint1", + "openarm_right_joint2", + "openarm_right_joint3", + "openarm_right_joint4", + "openarm_right_joint5", + "openarm_right_joint6", + "openarm_right_joint7", + ], + ) }, noise=Unoise(n_min=-0.01, n_max=0.01), ) @@ -143,43 +147,43 @@ class PolicyCfg(ObsGroup): left_joint_vel = ObsTerm( func=mdp.joint_vel_rel, params={ - "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_left_joint1", - "openarm_left_joint2", - "openarm_left_joint3", - "openarm_left_joint4", - "openarm_left_joint5", - "openarm_left_joint6", - "openarm_left_joint7", - ]) + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_left_joint1", + "openarm_left_joint2", + "openarm_left_joint3", + "openarm_left_joint4", + "openarm_left_joint5", + "openarm_left_joint6", + "openarm_left_joint7", + ], + ) }, noise=Unoise(n_min=-0.01, n_max=0.01), ) right_joint_vel = ObsTerm( func=mdp.joint_vel_rel, params={ - "asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_right_joint1", - "openarm_right_joint2", - "openarm_right_joint3", - "openarm_right_joint4", - "openarm_right_joint5", - "openarm_right_joint6", - "openarm_right_joint7" - ]) + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_right_joint1", + "openarm_right_joint2", + "openarm_right_joint3", + "openarm_right_joint4", + "openarm_right_joint5", + "openarm_right_joint6", + "openarm_right_joint7", + ], + ) }, noise=Unoise(n_min=-0.01, n_max=0.01), ) - left_pose_command = ObsTerm( - func=mdp.generated_commands, params={"command_name": "left_ee_pose"} - ) - right_pose_command = ObsTerm( - func=mdp.generated_commands, params={"command_name": "right_ee_pose"} - ) - left_actions = ObsTerm(func=mdp.last_action, - params={ - "action_name": "left_arm_action"}) - right_actions = ObsTerm(func=mdp.last_action, - params={ - "action_name": "right_arm_action"}) + left_pose_command = ObsTerm(func=mdp.generated_commands, params={"command_name": "left_ee_pose"}) + right_pose_command = ObsTerm(func=mdp.generated_commands, params={"command_name": "right_ee_pose"}) + left_actions = ObsTerm(func=mdp.last_action, params={"action_name": "left_arm_action"}) + right_actions = ObsTerm(func=mdp.last_action, params={"action_name": "right_arm_action"}) def __post_init__(self): self.enable_corruption = True @@ -269,26 +273,38 @@ class RewardsCfg: left_joint_vel = RewTerm( func=mdp.joint_vel_l2, weight=-0.0001, - params={"asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_left_joint1", - "openarm_left_joint2", - "openarm_left_joint3", - "openarm_left_joint4", - "openarm_left_joint5", - "openarm_left_joint6", - "openarm_left_joint7", - ])}, + params={ + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_left_joint1", + "openarm_left_joint2", + "openarm_left_joint3", + "openarm_left_joint4", + "openarm_left_joint5", + "openarm_left_joint6", + "openarm_left_joint7", + ], + ) + }, ) right_joint_vel = RewTerm( func=mdp.joint_vel_l2, weight=-0.0001, - params={"asset_cfg": SceneEntityCfg("robot", joint_names=["openarm_right_joint1", - "openarm_right_joint2", - "openarm_right_joint3", - "openarm_right_joint4", - "openarm_right_joint5", - "openarm_right_joint6", - "openarm_right_joint7" - ])}, + params={ + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_right_joint1", + "openarm_right_joint2", + "openarm_right_joint3", + "openarm_right_joint4", + "openarm_right_joint5", + "openarm_right_joint6", + "openarm_right_joint7", + ], + ) + }, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py index 638ef821161..cf76eeb00d6 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py @@ -3,11 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause +import math from dataclasses import MISSING import isaaclab.sim as sim_utils -from isaaclab.actuators import ImplicitActuatorCfg -from isaaclab.assets.articulation import ArticulationCfg from isaaclab.assets import ArticulationCfg, AssetBaseCfg from isaaclab.envs import ManagerBasedRLEnvCfg from isaaclab.managers import ActionTermCfg as ActionTerm @@ -25,8 +24,6 @@ import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -import math - ## # Scene definition ## @@ -48,9 +45,7 @@ class ReachSceneCfg(InteractiveSceneCfg): spawn=sim_utils.UsdFileCfg( usd_path=f"{ISAAC_NUCLEUS_DIR}/Props/Mounts/SeattleLabTable/table_instanceable.usd", ), - init_state=AssetBaseCfg.InitialStateCfg( - pos=(0.55, 0.0, 0.0), rot=(0.70711, 0.0, 0.0, 0.70711) - ), + init_state=AssetBaseCfg.InitialStateCfg(pos=(0.55, 0.0, 0.0), rot=(0.70711, 0.0, 0.0, 0.70711)), ) # robots @@ -108,36 +103,40 @@ class PolicyCfg(ObsGroup): joint_pos = ObsTerm( func=mdp.joint_pos_rel, params={ - "asset_cfg": SceneEntityCfg("robot", joint_names=[ - "openarm_joint1", - "openarm_joint2", - "openarm_joint3", - "openarm_joint4", - "openarm_joint5", - "openarm_joint6", - "openarm_joint7", - ]) + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_joint1", + "openarm_joint2", + "openarm_joint3", + "openarm_joint4", + "openarm_joint5", + "openarm_joint6", + "openarm_joint7", + ], + ) }, noise=Unoise(n_min=-0.01, n_max=0.01), ) joint_vel = ObsTerm( func=mdp.joint_vel_rel, params={ - "asset_cfg": SceneEntityCfg("robot", joint_names=[ - "openarm_joint1", - "openarm_joint2", - "openarm_joint3", - "openarm_joint4", - "openarm_joint5", - "openarm_joint6", - "openarm_joint7", - ]) + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_joint1", + "openarm_joint2", + "openarm_joint3", + "openarm_joint4", + "openarm_joint5", + "openarm_joint6", + "openarm_joint7", + ], + ) }, noise=Unoise(n_min=-0.01, n_max=0.01), ) - pose_command = ObsTerm( - func=mdp.generated_commands, params={"command_name": "ee_pose"} - ) + pose_command = ObsTerm(func=mdp.generated_commands, params={"command_name": "ee_pose"}) actions = ObsTerm(func=mdp.last_action) def __post_init__(self): @@ -198,15 +197,20 @@ class RewardsCfg: joint_vel = RewTerm( func=mdp.joint_vel_l2, weight=-0.0001, - params={"asset_cfg": SceneEntityCfg("robot", joint_names=[ - "openarm_joint1", - "openarm_joint2", - "openarm_joint3", - "openarm_joint4", - "openarm_joint5", - "openarm_joint6", - "openarm_joint7", - ])}, + params={ + "asset_cfg": SceneEntityCfg( + "robot", + joint_names=[ + "openarm_joint1", + "openarm_joint2", + "openarm_joint3", + "openarm_joint4", + "openarm_joint5", + "openarm_joint6", + "openarm_joint7", + ], + ) + }, ) From eb559cc8fd25ed4e9221c29f763b6e1cce02cb53 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 15:03:02 +0900 Subject: [PATCH 16/32] removed unnecessary lines --- .../manipulation/lift/config/openarm/joint_pos_env_cfg.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py index 2b779b7cafc..0d076628ec5 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py @@ -40,7 +40,7 @@ def __post_init__(self): "openarm_joint.*", ], scale=0.5, - use_default_offset=True, # False + use_default_offset=True, ) self.actions.gripper_action = mdp.BinaryJointPositionActionCfg( From 53c415566d7eb59fba267f74ca27c0527a5932f4 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 17:01:00 +0900 Subject: [PATCH 17/32] Updated Comprehensive Environment List in the Documentation --- docs/source/overview/environments.rst | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index ccec6ba235c..df35c52f58d 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -1151,3 +1151,19 @@ inferencing, including reading from an already trained checkpoint and disabling - Isaac-Velocity-Rough-Unitree-Go2-Play-v0 - Manager Based - **rsl_rl** (PPO), **skrl** (PPO) + * - Isaac-Reach-OpenArm-Bi-v0 + - Isaac-Reach-OpenArm-Bi-Play-v0 + - Manager Based + - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) + * - Isaac-Reach-OpenArm-v0 + - Isaac-Reach-OpenArm-Play-v0 + - Manager Based + - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) + * - Isaac-Lift-Cube-OpenArm-v0 + - Isaac-Lift-Cube-OpenArm-Play-v0 + - Manager Based + - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) + * - Isaac-Open-Drawer-OpenArm-v0 + - Isaac-Open-Drawer-OpenArm-Play-v0 + - Manager Based + - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) From 41354da70d6aee209355e149582cadc51d220937 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 26 Nov 2025 17:56:15 +0900 Subject: [PATCH 18/32] modified changelog --- source/isaaclab_tasks/docs/CHANGELOG.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 7da42aaea24..56d8e13ff89 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -9,7 +9,7 @@ Added * Added reaching task environments for OpenArm unimanual robot: * :class:`OpenArmReachEnvCfg`; Gym ID ``Isaac-Reach-OpenArm-v0``. - * :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``OpenArmReachEnvCfg_PLAY``. + * :class:`OpenArmReachEnvCfg_PLAY`; Gym ID ``Isaac-Reach-OpenArm-Play-v0``. * Added lifting a cube task environments for OpenArm unimanual robot: * :class:`OpenArmCubeLiftEnvCfg`; Gym ID ``Isaac-Lift-Cube-OpenArm-v0``. * :class:`OpenArmCubeLiftEnvCfg_PLAY`; Gym ID ``Isaac-Lift-Cube-OpenArm-Play-v0``. From 41341df3e071f155d4b46909775f7c6d168b16e5 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Thu, 11 Dec 2025 19:56:18 +0900 Subject: [PATCH 19/32] updated joint names --- .../reach/reach_openarm_uni_env_cfg.py | 24 +++---------------- 1 file changed, 3 insertions(+), 21 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py index cf76eeb00d6..6ece6f3cf31 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py @@ -106,13 +106,7 @@ class PolicyCfg(ObsGroup): "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_joint1", - "openarm_joint2", - "openarm_joint3", - "openarm_joint4", - "openarm_joint5", - "openarm_joint6", - "openarm_joint7", + "openarm_joint.*" ], ) }, @@ -124,13 +118,7 @@ class PolicyCfg(ObsGroup): "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_joint1", - "openarm_joint2", - "openarm_joint3", - "openarm_joint4", - "openarm_joint5", - "openarm_joint6", - "openarm_joint7", + "openarm_joint.*" ], ) }, @@ -201,13 +189,7 @@ class RewardsCfg: "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_joint1", - "openarm_joint2", - "openarm_joint3", - "openarm_joint4", - "openarm_joint5", - "openarm_joint6", - "openarm_joint7", + "openarm_joint.*" ], ) }, From c1379caf22f71bb0641d473ac97f95e723b2ad0e Mon Sep 17 00:00:00 2001 From: JinnnK Date: Thu, 11 Dec 2025 19:58:43 +0900 Subject: [PATCH 20/32] updated joint names in asset --- .../isaaclab_assets/robots/openarm.py | 15 +-------------- 1 file changed, 1 insertion(+), 14 deletions(-) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index 399a67d8dbc..f3b76e1355e 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -38,20 +38,7 @@ ), init_state=ArticulationCfg.InitialStateCfg( joint_pos={ - "openarm_left_joint1": 0.0, - "openarm_left_joint2": 0.0, - "openarm_left_joint3": 0.0, - "openarm_left_joint4": 0.0, - "openarm_left_joint5": 0.0, - "openarm_left_joint6": 0.0, - "openarm_left_joint7": 0.0, - "openarm_right_joint1": 0.0, - "openarm_right_joint2": 0.0, - "openarm_right_joint3": 0.0, - "openarm_right_joint4": 0.0, - "openarm_right_joint5": 0.0, - "openarm_right_joint6": 0.0, - "openarm_right_joint7": 0.0, + "openarm_.*_joint.*": 0.0, "openarm_left_finger_joint.*": 0.0, "openarm_right_finger_joint.*": 0.0, }, From ed0ddb27dd7a684c00466902d19694a875609649 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Thu, 11 Dec 2025 22:57:21 +0900 Subject: [PATCH 21/32] updated joint names --- source/isaaclab_assets/isaaclab_assets/robots/openarm.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index f3b76e1355e..1f2e59ad27e 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -38,7 +38,8 @@ ), init_state=ArticulationCfg.InitialStateCfg( joint_pos={ - "openarm_.*_joint.*": 0.0, + "openarm_left_joint.*": 0.0, + "openarm_right_joint.*": 0.0, "openarm_left_finger_joint.*": 0.0, "openarm_right_finger_joint.*": 0.0, }, From 6f6efe69d37f8423f30bb31bc2a3ebdbdff8214a Mon Sep 17 00:00:00 2001 From: JinnnK Date: Thu, 11 Dec 2025 23:11:28 +0900 Subject: [PATCH 22/32] removed the low-performing policies --- .../cabinet/config/openarm/__init__.py | 2 - .../config/openarm/agents/skrl_ppo_cfg.yaml | 85 ------------------- .../lift/config/openarm/__init__.py | 4 - .../config/openarm/agents/skrl_ppo_cfg.yaml | 85 ------------------- .../reach/config/openarm/bimanual/__init__.py | 2 - .../openarm/bimanual/agents/skrl_ppo_cfg.yaml | 85 ------------------- 6 files changed, 263 deletions(-) delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml delete mode 100644 source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/skrl_ppo_cfg.yaml diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py index e6d5a0c31cc..be1eae32f25 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/__init__.py @@ -22,7 +22,6 @@ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCabinetEnvCfg", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmCabinetPPORunnerCfg", "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", - "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", }, disable_env_checker=True, ) @@ -34,7 +33,6 @@ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCabinetEnvCfg_PLAY", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmCabinetPPORunnerCfg", "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", - "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", }, disable_env_checker=True, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml deleted file mode 100644 index 7af74961593..00000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/agents/skrl_ppo_cfg.yaml +++ /dev/null @@ -1,85 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -seed: 42 - - -# Models are instantiated using skrl's model instantiator utility -# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html -models: - separate: False - policy: # see gaussian_model parameters - class: GaussianMixin - clip_actions: False - clip_log_std: True - min_log_std: -20.0 - max_log_std: 2.0 - initial_log_std: 0.0 - network: - - name: net - input: STATES - layers: [256, 128, 64] - activations: elu - output: ACTIONS - value: # see deterministic_model parameters - class: DeterministicMixin - clip_actions: False - network: - - name: net - input: STATES - layers: [256, 128, 64] - activations: elu - output: ONE - - -# Rollout memory -# https://skrl.readthedocs.io/en/latest/api/memories/random.html -memory: - class: RandomMemory - memory_size: -1 # automatically determined (same as agent:rollouts) - - -# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) -# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html -agent: - class: PPO - rollouts: 96 - learning_epochs: 5 - mini_batches: 96 - discount_factor: 0.99 - lambda: 0.95 - learning_rate: 5.0e-04 - learning_rate_scheduler: KLAdaptiveLR - learning_rate_scheduler_kwargs: - kl_threshold: 0.008 - state_preprocessor: null - state_preprocessor_kwargs: null - value_preprocessor: null - value_preprocessor_kwargs: null - random_timesteps: 0 - learning_starts: 0 - grad_norm_clip: 1.0 - ratio_clip: 0.2 - value_clip: 0.2 - clip_predicted_values: True - entropy_loss_scale: 0.001 - value_loss_scale: 2.0 - kl_threshold: 0.0 - rewards_shaper_scale: 1 - time_limit_bootstrap: False - # logging and checkpoint - experiment: - directory: "openarm_open_drawer" - experiment_name: "" - write_interval: auto - checkpoint_interval: auto - - -# Sequential trainer -# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html -trainer: - class: SequentialTrainer - timesteps: 38400 - environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py index b9c4c89479e..ffb058ad1a8 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/__init__.py @@ -21,9 +21,7 @@ kwargs={ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCubeLiftEnvCfg", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmLiftCubePPORunnerCfg", - "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", - "sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml", }, disable_env_checker=True, ) @@ -34,9 +32,7 @@ kwargs={ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmCubeLiftEnvCfg_PLAY", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmLiftCubePPORunnerCfg", - "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", - "sb3_cfg_entry_point": f"{agents.__name__}:sb3_ppo_cfg.yaml", }, disable_env_checker=True, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml deleted file mode 100644 index 4f0b7ecd3a0..00000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/agents/skrl_ppo_cfg.yaml +++ /dev/null @@ -1,85 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -seed: 42 - - -# Models are instantiated using skrl's model instantiator utility -# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html -models: - separate: False - policy: # see gaussian_model parameters - class: GaussianMixin - clip_actions: False - clip_log_std: True - min_log_std: -20.0 - max_log_std: 2.0 - initial_log_std: 0.0 - network: - - name: net - input: STATES - layers: [256, 128, 64] - activations: elu - output: ACTIONS - value: # see deterministic_model parameters - class: DeterministicMixin - clip_actions: False - network: - - name: net - input: STATES - layers: [256, 128, 64] - activations: elu - output: ONE - - -# Rollout memory -# https://skrl.readthedocs.io/en/latest/api/memories/random.html -memory: - class: RandomMemory - memory_size: -1 # automatically determined (same as agent:rollouts) - - -# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) -# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html -agent: - class: PPO - rollouts: 24 - learning_epochs: 8 - mini_batches: 4 - discount_factor: 0.99 - lambda: 0.95 - learning_rate: 1.0e-04 - learning_rate_scheduler: KLAdaptiveLR - learning_rate_scheduler_kwargs: - kl_threshold: 0.01 - state_preprocessor: RunningStandardScaler - state_preprocessor_kwargs: null - value_preprocessor: RunningStandardScaler - value_preprocessor_kwargs: null - random_timesteps: 0 - learning_starts: 0 - grad_norm_clip: 1.0 - ratio_clip: 0.2 - value_clip: 0.2 - clip_predicted_values: True - entropy_loss_scale: 0.001 - value_loss_scale: 2.0 - kl_threshold: 0.0 - rewards_shaper_scale: 0.01 - time_limit_bootstrap: False - # logging and checkpoint - experiment: - directory: "openarm_lift" - experiment_name: "" - write_interval: auto - checkpoint_interval: auto - - -# Sequential trainer -# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html -trainer: - class: SequentialTrainer - timesteps: 36000 - environment_info: log diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/__init__.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/__init__.py index 2de6f9a6777..829aa7fee6a 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/__init__.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/__init__.py @@ -23,7 +23,6 @@ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmReachEnvCfg", "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmReachPPORunnerCfg", - "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", }, ) @@ -35,6 +34,5 @@ "env_cfg_entry_point": f"{__name__}.joint_pos_env_cfg:OpenArmReachEnvCfg_PLAY", "rl_games_cfg_entry_point": f"{agents.__name__}:rl_games_ppo_cfg.yaml", "rsl_rl_cfg_entry_point": f"{agents.__name__}.rsl_rl_ppo_cfg:OpenArmReachPPORunnerCfg", - "skrl_cfg_entry_point": f"{agents.__name__}:skrl_ppo_cfg.yaml", }, ) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/skrl_ppo_cfg.yaml b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/skrl_ppo_cfg.yaml deleted file mode 100644 index c037a4b4ce0..00000000000 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/agents/skrl_ppo_cfg.yaml +++ /dev/null @@ -1,85 +0,0 @@ -# Copyright (c) 2022-2025, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: BSD-3-Clause - -seed: 42 - - -# Models are instantiated using skrl's model instantiator utility -# https://skrl.readthedocs.io/en/latest/api/utils/model_instantiators.html -models: - separate: False - policy: # see gaussian_model parameters - class: GaussianMixin - clip_actions: False - clip_log_std: True - min_log_std: -20.0 - max_log_std: 2.0 - initial_log_std: 0.0 - network: - - name: net - input: STATES - layers: [64, 64] - activations: elu - output: ACTIONS - value: # see deterministic_model parameters - class: DeterministicMixin - clip_actions: False - network: - - name: net - input: STATES - layers: [64, 64] - activations: elu - output: ONE - - -# Rollout memory -# https://skrl.readthedocs.io/en/latest/api/memories/random.html -memory: - class: RandomMemory - memory_size: -1 # automatically determined (same as agent:rollouts) - - -# PPO agent configuration (field names are from PPO_DEFAULT_CONFIG) -# https://skrl.readthedocs.io/en/latest/api/agents/ppo.html -agent: - class: PPO - rollouts: 24 - learning_epochs: 5 - mini_batches: 4 - discount_factor: 0.99 - lambda: 0.95 - learning_rate: 1.0e-03 - learning_rate_scheduler: KLAdaptiveLR - learning_rate_scheduler_kwargs: - kl_threshold: 0.01 - state_preprocessor: RunningStandardScaler - state_preprocessor_kwargs: null - value_preprocessor: RunningStandardScaler - value_preprocessor_kwargs: null - random_timesteps: 0 - learning_starts: 0 - grad_norm_clip: 1.0 - ratio_clip: 0.2 - value_clip: 0.2 - clip_predicted_values: True - entropy_loss_scale: 0.01 - value_loss_scale: 1.0 - kl_threshold: 0.0 - rewards_shaper_scale: 1.0 - time_limit_bootstrap: False - # logging and checkpoint - experiment: - directory: "openarm_bi_reach" - experiment_name: "" - write_interval: auto - checkpoint_interval: auto - - -# Sequential trainer -# https://skrl.readthedocs.io/en/latest/api/trainers/sequential.html -trainer: - class: SequentialTrainer - timesteps: 24000 - environment_info: log From 3634e4a3eb22589d0cda275f513f10b2ca1aaf0c Mon Sep 17 00:00:00 2001 From: JinnnK Date: Thu, 11 Dec 2025 23:14:58 +0900 Subject: [PATCH 23/32] updated docs --- docs/source/overview/environments.rst | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index df35c52f58d..9f2d2ff28b1 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -1154,16 +1154,16 @@ inferencing, including reading from an already trained checkpoint and disabling * - Isaac-Reach-OpenArm-Bi-v0 - Isaac-Reach-OpenArm-Bi-Play-v0 - Manager Based - - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) + - **rsl_rl** (PPO), **rl_games** (PPO) * - Isaac-Reach-OpenArm-v0 - Isaac-Reach-OpenArm-Play-v0 - Manager Based - - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) + - **rsl_rl** (PPO), **skrl** (PPO), **rl_games** (PPO) * - Isaac-Lift-Cube-OpenArm-v0 - Isaac-Lift-Cube-OpenArm-Play-v0 - Manager Based - - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) + - **rsl_rl** (PPO), **rl_games** (PPO) * - Isaac-Open-Drawer-OpenArm-v0 - Isaac-Open-Drawer-OpenArm-Play-v0 - Manager Based - - **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO) + - **rsl_rl** (PPO), **rl_games** (PPO) From d7ff33a1cd2ba263ce41ce2c6f05e94f6aa0690e Mon Sep 17 00:00:00 2001 From: JinnnK Date: Thu, 11 Dec 2025 23:18:32 +0900 Subject: [PATCH 24/32] updated joint names --- .../openarm/bimanual/joint_pos_env_cfg.py | 16 +------ .../reach/reach_openarm_bi_env_cfg.py | 48 +++---------------- 2 files changed, 8 insertions(+), 56 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py index 19ec27f6443..6fcff5196e2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py @@ -45,13 +45,7 @@ def __post_init__(self): self.actions.left_arm_action = mdp.JointPositionActionCfg( asset_name="robot", joint_names=[ - "openarm_left_joint1", - "openarm_left_joint2", - "openarm_left_joint3", - "openarm_left_joint4", - "openarm_left_joint5", - "openarm_left_joint6", - "openarm_left_joint7", + "openarm_left_joint.*", ], scale=0.5, use_default_offset=True, @@ -60,13 +54,7 @@ def __post_init__(self): self.actions.right_arm_action = mdp.JointPositionActionCfg( asset_name="robot", joint_names=[ - "openarm_right_joint1", - "openarm_right_joint2", - "openarm_right_joint3", - "openarm_right_joint4", - "openarm_right_joint5", - "openarm_right_joint6", - "openarm_right_joint7", + "openarm_right_joint.*", ], scale=0.5, use_default_offset=True, diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py index bc3eb0b61df..55dc45f7b0d 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py @@ -112,13 +112,7 @@ class PolicyCfg(ObsGroup): "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_left_joint1", - "openarm_left_joint2", - "openarm_left_joint3", - "openarm_left_joint4", - "openarm_left_joint5", - "openarm_left_joint6", - "openarm_left_joint7", + "openarm_left_joint.*", ], ) }, @@ -131,13 +125,7 @@ class PolicyCfg(ObsGroup): "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_right_joint1", - "openarm_right_joint2", - "openarm_right_joint3", - "openarm_right_joint4", - "openarm_right_joint5", - "openarm_right_joint6", - "openarm_right_joint7", + "openarm_right_joint.*", ], ) }, @@ -150,13 +138,7 @@ class PolicyCfg(ObsGroup): "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_left_joint1", - "openarm_left_joint2", - "openarm_left_joint3", - "openarm_left_joint4", - "openarm_left_joint5", - "openarm_left_joint6", - "openarm_left_joint7", + "openarm_left_joint.*", ], ) }, @@ -168,13 +150,7 @@ class PolicyCfg(ObsGroup): "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_right_joint1", - "openarm_right_joint2", - "openarm_right_joint3", - "openarm_right_joint4", - "openarm_right_joint5", - "openarm_right_joint6", - "openarm_right_joint7", + "openarm_right_joint.*", ], ) }, @@ -277,13 +253,7 @@ class RewardsCfg: "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_left_joint1", - "openarm_left_joint2", - "openarm_left_joint3", - "openarm_left_joint4", - "openarm_left_joint5", - "openarm_left_joint6", - "openarm_left_joint7", + "openarm_left_joint.*", ], ) }, @@ -295,13 +265,7 @@ class RewardsCfg: "asset_cfg": SceneEntityCfg( "robot", joint_names=[ - "openarm_right_joint1", - "openarm_right_joint2", - "openarm_right_joint3", - "openarm_right_joint4", - "openarm_right_joint5", - "openarm_right_joint6", - "openarm_right_joint7", + "openarm_right_joint.*", ], ) }, From 18e44c99b6a53aa5511a20d5aec84b982b7ef07d Mon Sep 17 00:00:00 2001 From: JinnnK Date: Fri, 12 Dec 2025 11:20:42 +0900 Subject: [PATCH 25/32] updated feedback --- .../cabinet/{ => config/openarm}/cabinet_openarm_env_cfg.py | 6 +++--- .../cabinet/config/openarm/joint_pos_env_cfg.py | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/{ => config/openarm}/cabinet_openarm_env_cfg.py (98%) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py similarity index 98% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py index 740b95a586f..24d437319af 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/cabinet_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py @@ -29,7 +29,7 @@ FRAME_MARKER_SMALL_CFG = FRAME_MARKER_CFG.copy() FRAME_MARKER_SMALL_CFG.markers["frame"].scale = (0.10, 0.10, 0.10) -from . import mdp +from ... import mdp ## # Scene definition @@ -180,8 +180,8 @@ class EventCfg: mode="startup", params={ "asset_cfg": SceneEntityCfg("cabinet", body_names="drawer_handle_bottom"), - "static_friction_range": (2.0, 2.25), - "dynamic_friction_range": (2.25, 2.5), + "static_friction_range": (2.25, 2.5), + "dynamic_friction_range": (2.0, 2.25), "restitution_range": (0.0, 0.0), "num_buckets": 16, }, diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py index 0d4114d932f..123ea047e63 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/joint_pos_env_cfg.py @@ -14,7 +14,7 @@ from isaaclab_tasks.manager_based.manipulation.cabinet import mdp -from isaaclab_tasks.manager_based.manipulation.cabinet.cabinet_openarm_env_cfg import ( # isort: skip +from isaaclab_tasks.manager_based.manipulation.cabinet.config.openarm.cabinet_openarm_env_cfg import ( # isort: skip FRAME_MARKER_SMALL_CFG, CabinetEnvCfg, ) From 9c789e32b4e20a36ddfe18afa5e9f5929f194510 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Fri, 12 Dec 2025 11:27:27 +0900 Subject: [PATCH 26/32] Directory update for lift_openarm_env_cfg.py --- .../manipulation/lift/config/openarm/joint_pos_env_cfg.py | 2 +- .../lift/{ => config/openarm}/lift_openarm_env_cfg.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/{ => config/openarm}/lift_openarm_env_cfg.py (99%) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py index 0d076628ec5..16e54b396ef 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/joint_pos_env_cfg.py @@ -16,7 +16,7 @@ from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR from isaaclab_tasks.manager_based.manipulation.lift import mdp -from isaaclab_tasks.manager_based.manipulation.lift.lift_openarm_env_cfg import LiftEnvCfg +from isaaclab_tasks.manager_based.manipulation.lift.config.openarm.lift_openarm_env_cfg import LiftEnvCfg ## # Pre-defined configs diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py similarity index 99% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py index 9ccf1ccc81d..e928f321780 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/lift_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py @@ -22,7 +22,7 @@ from isaaclab.utils import configclass from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR -from . import mdp +from ... import mdp ## # Scene definition From 80bb6be108faab3d7dd992d8bddf3c78c57c3378 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Fri, 12 Dec 2025 11:49:06 +0900 Subject: [PATCH 27/32] Add motor specification references --- .../isaaclab_assets/robots/openarm.py | 20 ++++++++++++++++++- 1 file changed, 19 insertions(+), 1 deletion(-) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index 1f2e59ad27e..e57658b32ca 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -12,7 +12,18 @@ * :obj:`OPENARM_UNI_CFG`: OpenArm robot with one arm. * :obj:`OPENARM_UNI_HIGH_PD_CFG`: OpenArm robot with one arm and stiffer PD control. -Reference: https://github.com/enactic/openarm_isaac_lab +References: +OpenArm repositories: +* https://github.com/enactic/openarm +* https://github.com/enactic/openarm_isaac_lab + +Motor spec sheets: +* Joint 1–2 (DM-J8009P-2EC): + https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J8009P-2EC_User_Manual.pdf?v=1755481750 +* Joint 3–4 (DM-J4340P-2EC / DM-J4340-2EC): + https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J4340-2EC_User_Manual.pdf?v=1756883905 +* Joint 5–8 (DM-J4310-2EC V1.1): + https://files.seeedstudio.com/products/Damiao/DM-J4310-en.pdf Please `git clone https://github.com/enactic/openarm_isaac_lab` and `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab` to use these configurations. """ @@ -44,6 +55,13 @@ "openarm_right_finger_joint.*": 0.0, }, ), + # spec sheet for reference + # DM-J8009P-2EC (Joint 1, 2): + # https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J8009P-2EC_User_Manual.pdf?v=1755481750 + # DM-J4340P-2EC, DM-J4340-2EC (Joint 3, 4): + # https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J4340-2EC_User_Manual.pdf?v=1756883905 + # DM-J4310-2EC V1.1 (Joint 5, 6, 7, 8): + # https://files.seeedstudio.com/products/Damiao/DM-J4310-en.pdf actuators={ "openarm_arm": ImplicitActuatorCfg( joint_names_expr=[ From c1e884a0a4788ba818e6d52e2660d47d13888743 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Fri, 12 Dec 2025 12:17:42 +0900 Subject: [PATCH 28/32] Add comment explaining environment modifications --- .../cabinet/config/openarm/cabinet_openarm_env_cfg.py | 4 ++++ .../manipulation/lift/config/openarm/lift_openarm_env_cfg.py | 3 +++ 2 files changed, 7 insertions(+) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py index 24d437319af..d93459fabab 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/cabinet/config/openarm/cabinet_openarm_env_cfg.py @@ -3,6 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause +""" +We modified parts of the environment—such as the target’s position and orientation, as well as certain object properties—to better suit the smaller robot. +""" + from dataclasses import MISSING import isaaclab.sim as sim_utils diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py index e928f321780..1a0943db851 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/lift/config/openarm/lift_openarm_env_cfg.py @@ -3,6 +3,9 @@ # # SPDX-License-Identifier: BSD-3-Clause +""" +We modified parts of the environment—such as the target’s position and orientation, as well as certain object properties—to better suit the smaller robot. +""" from dataclasses import MISSING From 1770886d0f34cd4d2005e0849158ba40188f7632 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Fri, 12 Dec 2025 14:45:30 +0900 Subject: [PATCH 29/32] Add comment explaining environment modifications of reach tasks --- .../reach/config/openarm/bimanual/joint_pos_env_cfg.py | 2 +- .../{ => config/openarm/bimanual}/reach_openarm_bi_env_cfg.py | 4 ++++ .../reach/config/openarm/unimanual/joint_pos_env_cfg.py | 2 +- .../openarm/unimanual}/reach_openarm_uni_env_cfg.py | 4 ++++ 4 files changed, 10 insertions(+), 2 deletions(-) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/{ => config/openarm/bimanual}/reach_openarm_bi_env_cfg.py (98%) rename source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/{ => config/openarm/unimanual}/reach_openarm_uni_env_cfg.py (98%) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py index 6fcff5196e2..e36e3ae7fbb 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/joint_pos_env_cfg.py @@ -11,7 +11,7 @@ from isaaclab.utils import configclass import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_bi_env_cfg import ReachEnvCfg +from isaaclab_tasks.manager_based.manipulation.reach.config.openarm.bimanual.reach_openarm_bi_env_cfg import ReachEnvCfg ## # Environment configuration diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py similarity index 98% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py index 55dc45f7b0d..2375ad02b17 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_bi_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/bimanual/reach_openarm_bi_env_cfg.py @@ -3,6 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause +""" +We modified parts of the environment—such as the target’s position and orientation—to better suit the smaller robot. +""" + import math from dataclasses import MISSING diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py index a7c1ca1f1fe..8e4564077f9 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py @@ -12,7 +12,7 @@ from isaaclab.utils import configclass import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -from isaaclab_tasks.manager_based.manipulation.reach.reach_openarm_uni_env_cfg import ReachEnvCfg +from isaaclab_tasks.manager_based.manipulation.reach.config.openarm.unimanual.reach_openarm_uni_env_cfg import ReachEnvCfg ## # Environment configuration diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py similarity index 98% rename from source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py rename to source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py index 6ece6f3cf31..732fcbe6e7b 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py @@ -3,6 +3,10 @@ # # SPDX-License-Identifier: BSD-3-Clause +""" +We modified parts of the environment—such as the target’s position and orientation—to better suit the smaller robot. +""" + import math from dataclasses import MISSING From 6ec29cc77edd4662582fb4b714f06bb87c2fc09d Mon Sep 17 00:00:00 2001 From: JinnnK Date: Tue, 16 Dec 2025 10:52:54 +0900 Subject: [PATCH 30/32] Change asset path --- source/isaaclab_assets/isaaclab_assets/robots/openarm.py | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py index e57658b32ca..ab6660286ac 100644 --- a/source/isaaclab_assets/isaaclab_assets/robots/openarm.py +++ b/source/isaaclab_assets/isaaclab_assets/robots/openarm.py @@ -24,19 +24,16 @@ https://cdn.shopify.com/s/files/1/0673/6848/5000/files/DM-J4340-2EC_User_Manual.pdf?v=1756883905 * Joint 5–8 (DM-J4310-2EC V1.1): https://files.seeedstudio.com/products/Damiao/DM-J4310-en.pdf - -Please `git clone https://github.com/enactic/openarm_isaac_lab` and `export PYTHONPATH=$PYTHONPATH:~/openarm_isaac_lab` to use these configurations. """ -from source.openarm.openarm.tasks.manager_based.openarm_manipulation import OPENARM_ROOT_DIR - import isaaclab.sim as sim_utils from isaaclab.actuators import ImplicitActuatorCfg from isaaclab.assets.articulation import ArticulationCfg +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR OPENARM_BI_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( - usd_path=f"{OPENARM_ROOT_DIR}/usds/openarm_bimanual/openarm_bimanual.usd", + usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/OpenArm/openarm_bimanual/openarm_bimanual.usd", rigid_props=sim_utils.RigidBodyPropertiesCfg( disable_gravity=False, max_depenetration_velocity=5.0, @@ -104,7 +101,7 @@ OPENARM_UNI_CFG = ArticulationCfg( spawn=sim_utils.UsdFileCfg( - usd_path=f"{OPENARM_ROOT_DIR}/usds/openarm_unimanual/openarm_unimanual.usd", + usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/OpenArm/openarm_unimanual/openarm_unimanual.usd", rigid_props=sim_utils.RigidBodyPropertiesCfg( disable_gravity=False, max_depenetration_velocity=5.0, From 65762bb0fede0859b8daf665febad39bc7677bf9 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 17 Dec 2025 15:32:47 +0900 Subject: [PATCH 31/32] updated docs --- source/isaaclab_tasks/docs/CHANGELOG.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/isaaclab_tasks/docs/CHANGELOG.rst b/source/isaaclab_tasks/docs/CHANGELOG.rst index 4da834118cc..c2b67f5f78e 100644 --- a/source/isaaclab_tasks/docs/CHANGELOG.rst +++ b/source/isaaclab_tasks/docs/CHANGELOG.rst @@ -2,7 +2,7 @@ Changelog --------- 0.11.11 (2025-12-16) -~~~~~~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~ Added ^^^^^ From 0f1391dcf5a15a8eac8e43be2f80c196a81c28b8 Mon Sep 17 00:00:00 2001 From: JinnnK Date: Wed, 17 Dec 2025 15:49:03 +0900 Subject: [PATCH 32/32] updated pre-commit --- .../config/openarm/unimanual/joint_pos_env_cfg.py | 4 +++- .../openarm/unimanual/reach_openarm_uni_env_cfg.py | 12 +++--------- 2 files changed, 6 insertions(+), 10 deletions(-) diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py index 8e4564077f9..b3532bb3fc2 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/joint_pos_env_cfg.py @@ -12,7 +12,9 @@ from isaaclab.utils import configclass import isaaclab_tasks.manager_based.manipulation.reach.mdp as mdp -from isaaclab_tasks.manager_based.manipulation.reach.config.openarm.unimanual.reach_openarm_uni_env_cfg import ReachEnvCfg +from isaaclab_tasks.manager_based.manipulation.reach.config.openarm.unimanual.reach_openarm_uni_env_cfg import ( + ReachEnvCfg, +) ## # Environment configuration diff --git a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py index 732fcbe6e7b..5ce2d692885 100644 --- a/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py +++ b/source/isaaclab_tasks/isaaclab_tasks/manager_based/manipulation/reach/config/openarm/unimanual/reach_openarm_uni_env_cfg.py @@ -109,9 +109,7 @@ class PolicyCfg(ObsGroup): params={ "asset_cfg": SceneEntityCfg( "robot", - joint_names=[ - "openarm_joint.*" - ], + joint_names=["openarm_joint.*"], ) }, noise=Unoise(n_min=-0.01, n_max=0.01), @@ -121,9 +119,7 @@ class PolicyCfg(ObsGroup): params={ "asset_cfg": SceneEntityCfg( "robot", - joint_names=[ - "openarm_joint.*" - ], + joint_names=["openarm_joint.*"], ) }, noise=Unoise(n_min=-0.01, n_max=0.01), @@ -192,9 +188,7 @@ class RewardsCfg: params={ "asset_cfg": SceneEntityCfg( "robot", - joint_names=[ - "openarm_joint.*" - ], + joint_names=["openarm_joint.*"], ) }, )